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