mars_lib  0.1.0.3dc76ee85e09
Modular and Robust Sensor-Fusion
bodyvel_sensor_class.h
Go to the documentation of this file.
1 // Copyright (C) 2021 Martin Scheiber and Christian Brommer, Control of Networked Systems, University of Klagenfurt,
2 // Austria.
3 //
4 // All rights reserved.
5 //
6 // This software is licensed under the terms of the BSD-2-Clause-License with
7 // no commercial use allowed, the full terms of which are made available
8 // in the LICENSE file. No license in patents is granted.
9 //
10 // You can contact the authors at <martin.scheiber@ieee.org>
11 // and <christian.brommer@ieee.org>.
12 
13 #ifndef BODYVELSENSORCLASS_H
14 #define BODYVELSENSORCLASS_H
15 
16 #include <mars/core_state.h>
17 #include <mars/ekf.h>
23 #include <mars/time.h>
26 #include <cmath>
27 #include <iostream>
28 #include <memory>
29 #include <string>
30 #include <utility>
31 
32 namespace mars
33 {
35 
37 {
38 public:
39  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 
41  BodyvelSensorClass(const std::string& name, std::shared_ptr<CoreState> core_states)
42  {
43  name_ = name;
44  core_states_ = std::move(core_states);
45  const_ref_to_nav_ = false;
47 
48  // chi2
49  chi2_.set_dof(3);
50 
51  std::cout << "Created: [" << this->name_ << "] Sensor" << std::endl;
52  }
53 
54  virtual ~BodyvelSensorClass() = default;
55 
56  BodyvelSensorStateType get_state(const std::shared_ptr<void>& sensor_data)
57  {
58  BodyvelSensorData data = *static_cast<BodyvelSensorData*>(sensor_data.get());
59  return data.state_;
60  }
61 
62  Eigen::MatrixXd get_covariance(const std::shared_ptr<void>& sensor_data)
63  {
64  BodyvelSensorData data = *static_cast<BodyvelSensorData*>(sensor_data.get());
65  return data.get_full_cov();
66  }
67 
68  void set_initial_calib(std::shared_ptr<void> calibration)
69  {
70  initial_calib_ = calibration;
72  }
73 
74  BufferDataType Initialize(const Time& timestamp, std::shared_ptr<void> /*sensor_data*/,
75  std::shared_ptr<CoreType> latest_core_data)
76  {
77  // BodyvelMeasurementType measurement = *static_cast<BodyvelMeasurementType*>(sensor_data.get());
78 
79  BodyvelSensorData sensor_state;
80  std::string calibration_type;
81 
82  if (this->initial_calib_provided_)
83  {
84  calibration_type = "Given";
85 
86  BodyvelSensorData calib = *static_cast<BodyvelSensorData*>(initial_calib_.get());
87 
88  sensor_state.state_ = calib.state_;
89  sensor_state.sensor_cov_ = calib.sensor_cov_;
90  }
91  else
92  {
93  calibration_type = "Auto";
94 
95  std::cout << "Bodyvel calibration AUTO init not implemented yet" << std::endl;
96  exit(EXIT_FAILURE);
97  }
98 
99  // Bypass core state for the returned object
100  BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
101  std::make_shared<BodyvelSensorData>(sensor_state));
102 
103  is_initialized_ = true;
104 
105  std::cout << "Info: Initialized [" << name_ << "] with [" << calibration_type << "] Calibration at t=" << timestamp
106  << std::endl;
107 
109  {
110  std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
111  std::cout << "\tPosition[m]: [" << sensor_state.state_.p_ib_.transpose() << " ]" << std::endl;
112  std::cout << "\tOrientation[deg]: ["
113  << sensor_state.state_.q_ib_.toRotationMatrix().eulerAngles(0, 1, 2).transpose() * (180 / M_PI) << " ]"
114  << std::endl;
115  }
116 
117  return result;
118  }
119 
120  bool CalcUpdate(const Time& /*timestamp*/, std::shared_ptr<void> measurement, const CoreStateType& prior_core_state,
121  std::shared_ptr<void> latest_sensor_data, const Eigen::MatrixXd& prior_cov,
122  BufferDataType* new_state_data)
123  {
124  // Cast the sensor measurement and prior state information
125  BodyvelMeasurementType* meas = static_cast<BodyvelMeasurementType*>(measurement.get());
126  BodyvelSensorData* prior_sensor_data = static_cast<BodyvelSensorData*>(latest_sensor_data.get());
127 
128  // Decompose sensor measurement
129  Eigen::Vector3d v_meas = meas->velocity_;
130 
131  // Extract sensor state
132  BodyvelSensorStateType prior_sensor_state(prior_sensor_data->state_);
133 
134  // Generate measurement noise matrix and check
135  // if noisevalues from the measurement object should be used
136  Eigen::MatrixXd R_meas_dyn;
138  {
139  meas->get_meas_noise(&R_meas_dyn);
140  }
141  else
142  {
143  R_meas_dyn = this->R_.asDiagonal();
144  }
145  const Eigen::Matrix<double, 3, 3> R_meas = R_meas_dyn;
146 
147  const int size_of_core_state = CoreStateType::size_error_;
148  const int size_of_sensor_state = prior_sensor_state.cov_size_;
149  const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
150  const Eigen::MatrixXd P = prior_cov;
151  assert(P.size() == size_of_full_error_state * size_of_full_error_state);
152 
153  // Calculate the measurement jacobian H
154  // const Eigen::Matrix3d I_3 = Eigen::Matrix3d::Identity();
155  const Eigen::Matrix3d Z_3 = Eigen::Matrix3d::Zero();
156  // const Eigen::Vector3d P_wi = prior_core_state.p_wi_;
157  const Eigen::Vector3d V_wi = prior_core_state.v_wi_;
158  const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
159  const Eigen::Vector3d P_ib = prior_sensor_state.p_ib_;
160  const Eigen::Matrix3d R_ib = prior_sensor_state.q_ib_.toRotationMatrix();
161 
162  const Eigen::Vector3d w_wi = prior_core_state.w_m_ - prior_core_state.b_w_;
163  const Eigen::Matrix3d w_wi_skew = Utils::Skew(w_wi);
164 
165  // Linear Velocity
166  const Eigen::Matrix3d Hv_pwi = Z_3;
167  const Eigen::Matrix3d Hv_vwi = R_ib.transpose() * R_wi.transpose();
168  const Eigen::Matrix3d Hv_rwi = R_ib.transpose() * Utils::Skew(R_wi.transpose() * V_wi);
169  const Eigen::Matrix3d Hv_bw = R_ib.transpose() * Utils::Skew(P_ib); // Z_3;
170  const Eigen::Matrix3d Hv_ba = Z_3;
171  const Eigen::Matrix3d Hv_pib = R_ib.transpose() * w_wi_skew;
172  const Eigen::Matrix3d Hv_rib =
173  Utils::Skew(R_ib.transpose() * R_wi.transpose() * V_wi) + Utils::Skew(R_ib.transpose() * w_wi_skew * P_ib);
174 
175  // Assemble the jacobian for the velocity (horizontal)
176  // H_v = [Hv_pwi Hv_vwi Hv_rwi Hv_bw Hv_ba Hv_pib Hv_rib];
177  Eigen::MatrixXd H_v(3, Hv_pwi.cols() + Hv_vwi.cols() + Hv_rwi.cols() + Hv_bw.cols() + Hv_ba.cols() + Hv_pib.cols() +
178  Hv_rib.cols());
179  H_v << Hv_pwi, Hv_vwi, Hv_rwi, Hv_bw, Hv_ba, Hv_pib, Hv_rib;
180 
181  // Combine all jacobians (vertical)
182  Eigen::MatrixXd H(H_v.rows(), H_v.cols());
183  H << H_v;
184 
185  // Calculate the residual z = z~ - (estimate)
186  // Velocity
187  const Eigen::Vector3d v_est = R_ib.transpose() * R_wi.transpose() * V_wi + R_ib.transpose() * w_wi_skew * P_ib;
188  residual_ = Eigen::MatrixXd(v_est.rows(), 1);
189  residual_ = v_meas - v_est;
190 
191  // Perform EKF calculations
192  mars::Ekf ekf(H, R_meas, residual_, P);
193  const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
194  assert(correction.size() == size_of_full_error_state * 1);
195 
196  // Perform Chi2 test
197  if (!chi2_.passed_ && chi2_.do_test_)
198  {
200  return false;
201  }
202 
203  Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
204  assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
205  P_updated = Utils::EnforceMatrixSymmetry(P_updated);
206 
207  // Apply Core Correction
208  CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
209  CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
210 
211  // Apply Sensor Correction
212  const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
213  const BodyvelSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
214 
215  // Return Results
216  // CoreState data
217  CoreType core_data;
218  core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
219  core_data.state_ = corrected_core_state;
220 
221  // SensorState data
222  std::shared_ptr<BodyvelSensorData> sensor_data(std::make_shared<BodyvelSensorData>());
223  sensor_data->set_cov(P_updated);
224  sensor_data->state_ = corrected_sensor_state;
225 
226  BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
227 
228  if (const_ref_to_nav_)
229  {
230  // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
231  }
232  else
233  {
234  // TODO also estimate ref to nav
235  }
236 
237  *new_state_data = state_entry;
238 
239  return true;
240  }
241 
243  const Eigen::MatrixXd& correction)
244  {
245  // state + error state correction
246  // with quaternion from small angle approx -> new state
247 
248  BodyvelSensorStateType corrected_sensor_state;
249  corrected_sensor_state.p_ib_ = prior_sensor_state.p_ib_ + correction.block(0, 0, 3, 1);
250  corrected_sensor_state.q_ib_ =
251  Utils::ApplySmallAngleQuatCorr(prior_sensor_state.q_ib_, correction.block(3, 0, 3, 1));
252  return corrected_sensor_state;
253  }
254 };
255 } // namespace mars
256 
257 #endif // BODYVELSENSORCLASS_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:30
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
Definition: bodyvel_measurement_type.h:23
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d velocity_
Velocity [x y z].
Definition: bodyvel_measurement_type.h:27
Definition: bodyvel_sensor_class.h:37
virtual ~BodyvelSensorClass()=default
void set_initial_calib(std::shared_ptr< void > calibration)
set_initial_calib Sets the calibration of an individual sensor
Definition: bodyvel_sensor_class.h:68
BodyvelSensorStateType ApplyCorrection(const BodyvelSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition: bodyvel_sensor_class.h:242
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: bodyvel_sensor_class.h:62
BodyvelSensorStateType get_state(const std::shared_ptr< void > &sensor_data)
Definition: bodyvel_sensor_class.h:56
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: bodyvel_sensor_class.h:120
EIGEN_MAKE_ALIGNED_OPERATOR_NEW BodyvelSensorClass(const std::string &name, std::shared_ptr< CoreState > core_states)
Definition: bodyvel_sensor_class.h:41
BufferDataType Initialize(const Time &timestamp, std::shared_ptr< void >, std::shared_ptr< CoreType > latest_core_data)
Initialize the state of an individual sensor.
Definition: bodyvel_sensor_class.h:74
Definition: bodyvel_sensor_state_type.h:22
Eigen::Quaternion< double > q_ib_
Definition: bodyvel_sensor_state_type.h:27
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d p_ib_
Definition: bodyvel_sensor_state_type.h:26
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
Eigen::Vector3d w_m_
Definition: core_state_type.h:34
static constexpr int size_error_
Definition: core_state_type.h:38
Eigen::Vector3d v_wi_
Definition: core_state_type.h:28
Eigen::Vector3d b_w_
Definition: core_state_type.h:30
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.
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