mars_lib 0.1.0.2abe2576fe7f
Modular and Robust Sensor-Fusion
Loading...
Searching...
No Matches
mag_sensor_class.h
Go to the documentation of this file.
1// Copyright (C) 2021 Christian Brommer, Control of Networked Systems, University of Klagenfurt, Austria.
2//
3// All rights reserved.
4//
5// This software is licensed under the terms of the BSD-2-Clause-License with
6// no commercial use allowed, the full terms of which are made available
7// in the LICENSE file. No license in patents is granted.
8//
9// You can contact the author at <christian.brommer@ieee.org>
10
11#ifndef MAG_SENSOR_CLASS_H
12#define MAG_SENSOR_CLASS_H
13
14#include <mars/core_state.h>
15#include <mars/ekf.h>
21#include <mars/time.h>
24#include <cmath>
25#include <iostream>
26#include <memory>
27#include <string>
28#include <utility>
29
30namespace mars
31{
33
35{
36private:
37 bool normalize_{ false };
38 bool apply_intrinsic_{ false };
39 Eigen::Vector3d mag_intr_offset_{ Eigen::Vector3d::Zero() };
40 Eigen::Matrix3d mag_intr_transform_{ Eigen::Matrix3d::Identity() };
41
42public:
43 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44
45 MagSensorClass(const std::string& name, std::shared_ptr<CoreState> core_states)
46 {
47 name_ = name;
48 core_states_ = std::move(core_states);
49 const_ref_to_nav_ = false;
51
52 // chi2
53 chi2_.set_dof(3);
54
55 // Sensor specific information
56 // setup_sensor_properties();
57 std::cout << "Created: [" << this->name_ << "] Sensor" << std::endl;
58 }
59
60 virtual ~MagSensorClass() = default;
61
62 MagSensorStateType get_state(const std::shared_ptr<void>& sensor_data)
63 {
64 MagSensorData data = *static_cast<MagSensorData*>(sensor_data.get());
65 return data.state_;
66 }
67
68 Eigen::MatrixXd get_covariance(const std::shared_ptr<void>& sensor_data)
69 {
70 MagSensorData data = *static_cast<MagSensorData*>(sensor_data.get());
71 return data.get_full_cov();
72 }
73
74 void set_initial_calib(std::shared_ptr<void> calibration)
75 {
76 initial_calib_ = calibration;
78 }
79
80 BufferDataType Initialize(const Time& timestamp, std::shared_ptr<void> /*sensor_data*/,
81 std::shared_ptr<CoreType> latest_core_data)
82 {
83 // MagMeasurementType measurement = *static_cast<MagMeasurementType*>(sensor_data.get());
84
85 MagSensorData sensor_state;
86 std::string calibration_type;
87
89 {
90 calibration_type = "Given";
91
92 MagSensorData calib = *static_cast<MagSensorData*>(initial_calib_.get());
93
94 sensor_state.state_ = calib.state_;
95 sensor_state.sensor_cov_ = calib.sensor_cov_;
96 }
97 else
98 {
99 calibration_type = "Auto";
100 std::cout << "Magnetometer calibration AUTO init not implemented yet" << std::endl;
101 exit(EXIT_FAILURE);
102 }
103
104 // Bypass core state for the returned object
105 BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
106 std::make_shared<MagSensorData>(sensor_state));
107
108 // TODO (chb)
109 // sensor_data.ref_to_nav = 0; //obj.calc_ref_to_nav(measurement, latest_core_state);
110
111 is_initialized_ = true;
112
113 std::cout << "Info: Initialized [" << name_ << "] with [" << calibration_type << "] Calibration at t=" << timestamp
114 << std::endl;
115
117 {
118 std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
119 std::cout << "\tMag Vector []: [" << sensor_state.state_.mag_.transpose() << " ]" << std::endl;
120 std::cout << "\tOrientation Mag in IMU [deg]: ["
121 << sensor_state.state_.q_im_.toRotationMatrix().eulerAngles(0, 1, 2).transpose() * (180 / M_PI) << " ]"
122 << std::endl;
123 }
124
125 return result;
126 }
127
128 bool CalcUpdate(const Time& /*timestamp*/, std::shared_ptr<void> measurement, const CoreStateType& prior_core_state,
129 std::shared_ptr<void> latest_sensor_data, const Eigen::MatrixXd& prior_cov,
130 BufferDataType* new_state_data)
131 {
132 // Cast the sensor measurement and prior state information
133 MagMeasurementType* meas = static_cast<MagMeasurementType*>(measurement.get());
134 MagSensorData* prior_sensor_data = static_cast<MagSensorData*>(latest_sensor_data.get());
135
136 // Decompose sensor measurement
137 Eigen::Vector3d mag_meas(meas->mag_vector_);
138
139 // Correct measurement with intrinsic calibration
141 {
142 mag_meas = mag_intr_transform_ * (mag_meas - mag_intr_offset_);
143 }
144
145 // Perform normalization
146 if (normalize_)
147 {
148 mag_meas = mag_meas / mag_meas.norm();
149 }
150
151 // Extract sensor state
152 MagSensorStateType prior_sensor_state(prior_sensor_data->state_);
153
154 // Generate measurement noise matrix and check
155 // if noisevalues from the measurement object should be used
156 Eigen::MatrixXd R_meas_dyn;
158 {
159 meas->get_meas_noise(&R_meas_dyn);
160 }
161 else
162 {
163 R_meas_dyn = this->R_.asDiagonal();
164 }
165 const Eigen::Matrix<double, 3, 3> R_meas = R_meas_dyn;
166
167 const int size_of_core_state = CoreStateType::size_error_;
168 const int size_of_sensor_state = prior_sensor_state.cov_size_;
169 const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
170 const Eigen::MatrixXd P = prior_cov;
171 assert(P.size() == size_of_full_error_state * size_of_full_error_state);
172
173 // Calculate the measurement jacobian H
174 // const Eigen::Matrix3d I_3 = Eigen::Matrix3d::Identity();
175 const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
176 const Eigen::Vector3d mag_w = prior_sensor_state.mag_;
177 const Eigen::Matrix3d R_im = prior_sensor_state.q_im_.toRotationMatrix();
178
179 // Orientation
180 const Eigen::Matrix3d Hm_pwi = Eigen::Matrix3d::Zero();
181 const Eigen::Matrix3d Hm_vwi = Eigen::Matrix3d::Zero();
182 const Eigen::Matrix3d Hm_rwi = R_im.transpose() * Utils::Skew(R_wi.transpose() * mag_w);
183 const Eigen::Matrix3d Hm_bw = Eigen::Matrix3d::Zero();
184 const Eigen::Matrix3d Hm_ba = Eigen::Matrix3d::Zero();
185 const Eigen::Matrix3d Hm_mag = R_im.transpose() * R_wi.transpose();
186 const Eigen::Matrix3d Hm_rim = Utils::Skew(R_im.transpose() * R_wi.transpose() * mag_w);
187
188 // Assemble the jacobian for the orientation (horizontal)
189 // H_r = [Hr_pwi Hr_vwi Hr_rwi Hr_bw Hr_ba Hr_mag Hr_rim];
190 Eigen::MatrixXd H(3, Hm_pwi.cols() + Hm_vwi.cols() + Hm_rwi.cols() + Hm_bw.cols() + Hm_ba.cols() + Hm_mag.cols() +
191 Hm_rim.cols());
192 H << Hm_pwi, Hm_vwi, Hm_rwi, Hm_bw, Hm_ba, Hm_mag, Hm_rim;
193
194 // Calculate the residual z = z~ - (estimate)
195 // Position
196 const Eigen::Vector3d mag_est = R_im.transpose() * R_wi.transpose() * mag_w;
197 residual_ = Eigen::MatrixXd(mag_est.rows(), 1);
198 residual_ = mag_meas - mag_est;
199
200 // Perform EKF calculations
201 mars::Ekf ekf(H, R_meas, residual_, P);
202 const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
203 assert(correction.size() == size_of_full_error_state * 1);
204
205 // Perform Chi2 test
206 if (!chi2_.passed_ && chi2_.do_test_)
207 {
209 return false;
210 }
211
212 Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
213 assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
214 P_updated = Utils::EnforceMatrixSymmetry(P_updated);
215
216 // Apply Core Correction
217 CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
218 CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
219
220 // Apply Sensor Correction
221 const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
222 const MagSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
223
224 // Return Results
225 // CoreState data
226 CoreType core_data;
227 core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
228 core_data.state_ = corrected_core_state;
229
230 // SensorState data
231 std::shared_ptr<MagSensorData> sensor_data(std::make_shared<MagSensorData>());
232 sensor_data->set_cov(P_updated);
233 sensor_data->state_ = corrected_sensor_state;
234
235 BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
236
238 {
239 // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
240 }
241 else
242 {
243 // TODO(chb) also estimate ref to nav
244 }
245
246 *new_state_data = state_entry;
247
248 return true;
249 }
250
251 MagSensorStateType ApplyCorrection(const MagSensorStateType& prior_sensor_state, const Eigen::MatrixXd& correction)
252 {
253 // state + error state correction
254 // with quaternion from small angle approx -> new state
255
256 MagSensorStateType corrected_sensor_state;
257 corrected_sensor_state.mag_ = prior_sensor_state.mag_ + correction.block(0, 0, 3, 1);
258 corrected_sensor_state.q_im_ =
259 Utils::ApplySmallAngleQuatCorr(prior_sensor_state.q_im_, correction.block(3, 0, 3, 1));
260 return corrected_sensor_state;
261 }
262
263 void set_normalize(const bool& value)
264 {
265 normalize_ = value;
266 }
267
268 void set_apply_intrinsic(const bool& value)
269 {
270 apply_intrinsic_ = value;
271 }
272
273 void set_intr_offset(const Eigen::Vector3d& v_offset)
274 {
275 mag_intr_offset_ = v_offset;
276 }
277
278 void set_intr_transform(const Eigen::Matrix3d& m_transform)
279 {
280 mag_intr_transform_ = m_transform;
281 }
282};
283} // namespace mars
284
285#endif // MAG_SENSOR_CLASS_H
bool has_meas_noise
Definition measurement_base_class.h:23
bool get_meas_noise(Eigen::MatrixXd *meas_noise)
get the measurement noise associated with the current sensor measurement
Definition measurement_base_class.h:25
int cov_size_
Definition base_states.h:25
The BaseSensorData class binds the sensor state and covariance matrix.
Definition bind_sensor_data.h:29
EIGEN_MAKE_ALIGNED_OPERATOR_NEW T state_
Definition bind_sensor_data.h:35
Eigen::MatrixXd get_full_cov() const
get_full_cov builds the full covariance matrix
Definition bind_sensor_data.h:63
Eigen::MatrixXd sensor_cov_
covariance of the sensor states
Definition bind_sensor_data.h:37
The BufferDataType binds the core and sensor state in form of a shared void pointer.
Definition buffer_data_type.h:36
bool passed_
Determine if the test is performed or not.
Definition ekf.h:84
bool do_test_
Upper critival value.
Definition ekf.h:83
void set_dof(const int &value)
set_dof Set degree of freedom for the X2 distribution
void PrintReport(const std::string &name)
PrintReport Print a formated report e.g. if the test did not pass.
Definition core_state_type.h:21
static constexpr int size_error_
Definition core_state_type.h:38
Eigen::Quaternion< double > q_wi_
Definition core_state_type.h:29
static CoreStateType ApplyCorrection(CoreStateType state_prior, Eigen::Matrix< double, CoreStateType::size_error_, 1 > correction)
ApplyCorrection.
Definition core_state_type.h:46
Definition core_type.h:19
CoreStateMatrix cov_
Definition core_type.h:22
CoreStateType state_
Definition core_type.h:21
Definition ekf.h:92
Eigen::MatrixXd CalculateCovUpdate()
CalculateCovUpdate Updating the state covariance after the state update.
Eigen::MatrixXd CalculateCorrection()
Kalman gain.
Definition mag_measurement_type.h:21
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d mag_vector_
Raw magnetometer measurement [x y z].
Definition mag_measurement_type.h:25
Definition mag_sensor_class.h:35
MagSensorStateType get_state(const std::shared_ptr< void > &sensor_data)
Definition mag_sensor_class.h:62
void set_initial_calib(std::shared_ptr< void > calibration)
set_initial_calib Sets the calibration of an individual sensor
Definition mag_sensor_class.h:74
void set_intr_offset(const Eigen::Vector3d &v_offset)
Definition mag_sensor_class.h:273
Eigen::Matrix3d mag_intr_transform_
Intrinsic cal distortion.
Definition mag_sensor_class.h:40
MagSensorStateType ApplyCorrection(const MagSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition mag_sensor_class.h:251
bool normalize_
The measurement will be normalized if True.
Definition mag_sensor_class.h:37
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MagSensorClass(const std::string &name, std::shared_ptr< CoreState > core_states)
Definition mag_sensor_class.h:45
void set_intr_transform(const Eigen::Matrix3d &m_transform)
Definition mag_sensor_class.h:278
virtual ~MagSensorClass()=default
bool CalcUpdate(const Time &, std::shared_ptr< void > measurement, const CoreStateType &prior_core_state, std::shared_ptr< void > latest_sensor_data, const Eigen::MatrixXd &prior_cov, BufferDataType *new_state_data)
CalcUpdate Calculates the update for an individual sensor definition.
Definition mag_sensor_class.h:128
BufferDataType Initialize(const Time &timestamp, std::shared_ptr< void >, std::shared_ptr< CoreType > latest_core_data)
Initialize the state of an individual sensor.
Definition mag_sensor_class.h:80
void set_normalize(const bool &value)
Definition mag_sensor_class.h:263
void set_apply_intrinsic(const bool &value)
Definition mag_sensor_class.h:268
Eigen::Vector3d mag_intr_offset_
Intrinsic cal offset.
Definition mag_sensor_class.h:39
Eigen::MatrixXd get_covariance(const std::shared_ptr< void > &sensor_data)
get_covariance Resolves a void pointer to the covariance matrix of the corresponding sensor type Each...
Definition mag_sensor_class.h:68
bool apply_intrinsic_
The intrinsic calibration will be aplied if True.
Definition mag_sensor_class.h:38
Definition mag_sensor_state_type.h:20
Eigen::Quaterniond q_im_
Definition mag_sensor_state_type.h:25
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d mag_
Definition mag_sensor_state_type.h:24
std::string name_
Name of the individual sensor instance.
Definition sensor_abs_class.h:23
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24
bool const_ref_to_nav_
True if the reference should not be estimated.
Definition sensor_abs_class.h:27
bool use_dynamic_meas_noise_
True if dynamic noise values from measurements should be used.
Definition sensor_abs_class.h:29
Definition time.h:20
Definition update_sensor_abs_class.h:24
bool initial_calib_provided_
True if an initial calibration was provided.
Definition update_sensor_abs_class.h:38
std::shared_ptr< CoreState > core_states_
Definition update_sensor_abs_class.h:42
Eigen::VectorXd R_
Measurement noise "squared".
Definition update_sensor_abs_class.h:32
std::shared_ptr< void > initial_calib_
Definition update_sensor_abs_class.h:37
Chi2 chi2_
Definition update_sensor_abs_class.h:40
Eigen::MatrixXd residual_
Definition update_sensor_abs_class.h:31
static Eigen::MatrixXd EnforceMatrixSymmetry(const Eigen::Ref< const Eigen::MatrixXd > &mat_in)
EnforceMatrixSymmetry.
static Eigen::Matrix3d Skew(const Eigen::Vector3d &v)
skew generate the skew symmetric matrix of v
static Eigen::Quaterniond ApplySmallAngleQuatCorr(const Eigen::Quaterniond &q_prior, const Eigen::Vector3d &correction)
ApplySmallAngleQuatCorr.
Definition buffer.h:27
Eigen::Matrix< double, CoreStateType::size_error_, 1 > CoreStateVector
Definition core_state_type.h:135