mars_lib 0.1.0.2abe2576fe7f
Modular and Robust Sensor-Fusion
Loading...
Searching...
No Matches
Public Member Functions | List of all members
mars::VelocitySensorClass Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/velocity/velocity_sensor_class.h>

+ Inheritance diagram for mars::VelocitySensorClass:
+ Collaboration diagram for mars::VelocitySensorClass:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW VelocitySensorClass (const std::string &name, std::shared_ptr< CoreState > core_states)
 
virtual ~VelocitySensorClass ()=default
 
VelocitySensorStateType get_state (const std::shared_ptr< void > &sensor_data)
 
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 sensor is responsible to cast its own data type
 
void set_initial_calib (std::shared_ptr< void > calibration)
 set_initial_calib Sets the calibration of an individual sensor
 
BufferDataType Initialize (const Time &timestamp, std::shared_ptr< void >, std::shared_ptr< CoreType > latest_core_data)
 Initialize the state of an individual sensor.
 
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.
 
VelocitySensorStateType ApplyCorrection (const VelocitySensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
 
- Public Member Functions inherited from mars::SensorInterface
virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW ~SensorInterface ()=default
 

Additional Inherited Members

- Public Attributes inherited from mars::UpdateSensorAbsClass
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int aux_states_
 
int aux_error_states_
 
int ref_to_nav_
 
Eigen::MatrixXd residual_
 
Eigen::VectorXd R_
 Measurement noise "squared".
 
Eigen::MatrixXd F_
 
Eigen::MatrixXd H_
 
Eigen::MatrixXd Q_
 
std::shared_ptr< void > initial_calib_ { nullptr }
 
bool initial_calib_provided_ { false }
 True if an initial calibration was provided.
 
Chi2 chi2_
 
std::shared_ptr< CoreStatecore_states_
 
- Public Attributes inherited from mars::SensorAbsClass
int id_ { -1 }
 
std::string name_
 Name of the individual sensor instance.
 
bool is_initialized_ { false }
 True if the sensor has been initialized.
 
bool do_update_ { true }
 True if updates should be performed with the sensor.
 
int type_ { -1 }
 Future feature, holds information such as position or orientation for highlevel decissions.
 
bool const_ref_to_nav_ { true }
 True if the reference should not be estimated.
 
bool ref_to_nav_given_ { false }
 True if the reference to the navigation frame is given by initial calibration.
 
bool use_dynamic_meas_noise_ { false }
 True if dynamic noise values from measurements should be used.
 

Constructor & Destructor Documentation

◆ VelocitySensorClass()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW mars::VelocitySensorClass::VelocitySensorClass ( const std::string &  name,
std::shared_ptr< CoreState core_states 
)
inline
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 }
void set_dof(const int &value)
set_dof Set degree of freedom for the X2 distribution
std::string name_
Name of the individual sensor instance.
Definition sensor_abs_class.h:23
bool const_ref_to_nav_
True if the reference should not be estimated.
Definition sensor_abs_class.h:27
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
Chi2 chi2_
Definition update_sensor_abs_class.h:40
+ Here is the call graph for this function:

◆ ~VelocitySensorClass()

virtual mars::VelocitySensorClass::~VelocitySensorClass ( )
virtualdefault

Member Function Documentation

◆ get_state()

VelocitySensorStateType mars::VelocitySensorClass::get_state ( const std::shared_ptr< void > &  sensor_data)
inline
54 {
55 VelocitySensorData data = *static_cast<VelocitySensorData*>(sensor_data.get());
56 return data.state_;
57 }
BindSensorData< VelocitySensorStateType > VelocitySensorData
Definition velocity_sensor_class.h:31

◆ get_covariance()

Eigen::MatrixXd mars::VelocitySensorClass::get_covariance ( const std::shared_ptr< void > &  sensor_data)
inlinevirtual

get_covariance Resolves a void pointer to the covariance matrix of the corresponding sensor type Each sensor is responsible to cast its own data type

Parameters
sensor_data
Returns
Covariance matrix contained in the sensor data struct

Implements mars::SensorInterface.

60 {
61 VelocitySensorData data = *static_cast<VelocitySensorData*>(sensor_data.get());
62 return data.get_full_cov();
63 }
+ Here is the call graph for this function:

◆ set_initial_calib()

void mars::VelocitySensorClass::set_initial_calib ( std::shared_ptr< void >  calibration)
inlinevirtual

set_initial_calib Sets the calibration of an individual sensor

Parameters
calibration

Implements mars::SensorInterface.

66 {
67 initial_calib_ = calibration;
69 }
std::shared_ptr< void > initial_calib_
Definition update_sensor_abs_class.h:37

◆ Initialize()

BufferDataType mars::VelocitySensorClass::Initialize ( const Time timestamp,
std::shared_ptr< void >  measurement,
std::shared_ptr< CoreType latest_core_data 
)
inlinevirtual

Initialize the state of an individual sensor.

Parameters
timestampcurrent timestamp
measurementcurrent sensor measurement
latest_core_data
Returns

Implements mars::SensorInterface.

73 {
74 // VelocityMeasurementType measurement = *static_cast<VelocityMeasurementType*>(sensor_data.get());
75
76 VelocitySensorData sensor_state;
77 std::string calibration_type;
78
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 }
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24

◆ CalcUpdate()

bool mars::VelocitySensorClass::CalcUpdate ( const Time timestamp,
std::shared_ptr< void >  measurement,
const CoreStateType prior_core_state_data,
std::shared_ptr< void >  latest_sensor_data,
const Eigen::MatrixXd &  prior_cov,
BufferDataType new_state_data 
)
inlinevirtual

CalcUpdate Calculates the update for an individual sensor definition.

Parameters
timestampcurrent timestamp
measurementcurrent sensor measurement
prior_core_state_data
latest_sensor_data
prior_covPrior covariance containing core, sensor and sensor cross covariance
new_state_dataUpdated state data
Returns
True if the update was successful, false if the update was rejected

< Angular Velocity of the IMU Frame

Implements mars::SensorInterface.

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;
132 if (meas->has_meas_noise && use_dynamic_meas_noise_)
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
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 }
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 PrintReport(const std::string &name)
PrintReport Print a formated report e.g. if the test did not pass.
static constexpr int size_error_
Definition core_state_type.h:38
static CoreStateType ApplyCorrection(CoreStateType state_prior, Eigen::Matrix< double, CoreStateType::size_error_, 1 > correction)
ApplyCorrection.
Definition core_state_type.h:46
Definition ekf.h:92
bool use_dynamic_meas_noise_
True if dynamic noise values from measurements should be used.
Definition sensor_abs_class.h:29
Eigen::VectorXd R_
Measurement noise "squared".
Definition update_sensor_abs_class.h:32
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
VelocitySensorStateType ApplyCorrection(const VelocitySensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition velocity_sensor_class.h:239
Eigen::Matrix< double, CoreStateType::size_error_, 1 > CoreStateVector
Definition core_state_type.h:135
+ Here is the call graph for this function:

◆ ApplyCorrection()

VelocitySensorStateType mars::VelocitySensorClass::ApplyCorrection ( const VelocitySensorStateType prior_sensor_state,
const Eigen::MatrixXd &  correction 
)
inline
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 }
+ Here is the caller graph for this function:

The documentation for this class was generated from the following file: