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

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/pressure/pressure_sensor_class.h>

+ Inheritance diagram for mars::PressureSensorClass:
+ Collaboration diagram for mars::PressureSensorClass:

Public Member Functions

 PressureSensorClass (const std::string &name, std::shared_ptr< CoreState > core_states)
 
virtual ~PressureSensorClass ()=default
 
PressureSensorStateType get_state (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
 
void set_pressure_reference (const double &pressure, const double &temperature)
 
void set_pressure_reference (const mars::Pressure &pressure)
 
BufferDataType Initialize (const Time &timestamp, std::shared_ptr< void > sensor_data, 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.
 
PressureSensorStateType ApplyCorrection (const PressureSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
 
- Public Member Functions inherited from mars::SensorInterface
virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW ~SensorInterface ()=default
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PressureConversion pressure_conversion_
 
bool pressure_reference_is_set_
 
- 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

◆ PressureSensorClass()

mars::PressureSensorClass::PressureSensorClass ( const std::string &  name,
std::shared_ptr< CoreState core_states 
)
inline
42 {
43 name_ = name;
44 core_states_ = std::move(core_states);
45 const_ref_to_nav_ = false;
48
49 // chi2
50 chi2_.set_dof(1);
51
52 std::cout << "Created: [" << this->name_ << "] Sensor" << std::endl;
53 }
void set_dof(const int &value)
set_dof Set degree of freedom for the X2 distribution
bool pressure_reference_is_set_
Definition pressure_sensor_class.h:39
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:

◆ ~PressureSensorClass()

virtual mars::PressureSensorClass::~PressureSensorClass ( )
virtualdefault

Member Function Documentation

◆ get_state()

PressureSensorStateType mars::PressureSensorClass::get_state ( std::shared_ptr< void >  sensor_data)
inline
58 {
59 PressureSensorData data = *static_cast<PressureSensorData*>(sensor_data.get());
60 return data.state_;
61 }
BindSensorData< PressureSensorStateType > PressureSensorData
Definition pressure_sensor_class.h:31

◆ get_covariance()

Eigen::MatrixXd mars::PressureSensorClass::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.

64 {
65 PressureSensorData data = *static_cast<PressureSensorData*>(sensor_data.get());
66 return data.get_full_cov();
67 }
+ Here is the call graph for this function:

◆ set_initial_calib()

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

set_initial_calib Sets the calibration of an individual sensor

Parameters
calibration

Implements mars::SensorInterface.

70 {
71 initial_calib_ = calibration;
73 }
std::shared_ptr< void > initial_calib_
Definition update_sensor_abs_class.h:37

◆ set_pressure_reference() [1/2]

void mars::PressureSensorClass::set_pressure_reference ( const double &  pressure,
const double &  temperature 
)
inline
76 {
78 }
void set_pressure_reference(const double &pressure, const double &temperature)
Definition pressure_sensor_class.h:75
The Pressure struct describes the raw pressure measurement used for conversion later.
Definition pressure_conversion.h:25
@ GAS
pressure measruement is in gas medium, e.g., air
+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ set_pressure_reference() [2/2]

void mars::PressureSensorClass::set_pressure_reference ( const mars::Pressure pressure)
inline
81 {
83 {
86 std::cout << "Info: [" << name_ << "] Set pressure reference: \n" << pressure << std::endl;
87 }
88 else
89 {
90 std::cout << "Warning: [" << name_ << "] "
91 << "Trying to set pressure reference but reference was already set. Action has no effect." << std::endl;
92 }
93 }
void set_pressure_reference(Pressure pressure)
Setter function to set the reference pressure after construction of object.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW PressureConversion pressure_conversion_
Definition pressure_sensor_class.h:38
+ Here is the call graph for this function:

◆ Initialize()

BufferDataType mars::PressureSensorClass::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.

97 {
98 PressureMeasurementType measurement = *static_cast<PressureMeasurementType*>(sensor_data.get());
99
101 {
102 Pressure pressure(measurement.pressure_.data_, measurement.pressure_.temperature_K_, measurement.pressure_.type_);
103
106 std::cout << "Info: [" << name_ << "] Set pressure reference: \n" << pressure << std::endl;
107 }
108
109 PressureSensorData sensor_state;
110 std::string calibration_type;
111
112 if (this->initial_calib_provided_)
113 {
114 calibration_type = "Given";
115
116 PressureSensorData calib = *static_cast<PressureSensorData*>(initial_calib_.get());
117
118 sensor_state.state_ = calib.state_;
119 sensor_state.sensor_cov_ = calib.sensor_cov_;
120 }
121 else
122 {
123 calibration_type = "Auto";
124 std::cout << "Pressure calibration AUTO init not implemented yet" << std::endl;
125 exit(EXIT_FAILURE);
126 }
127
128 // Bypass core state for the returned object
129 BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
130 std::make_shared<PressureSensorData>(sensor_state));
131
132 is_initialized_ = true;
133
134 std::cout << "Info: Initialized [" << name_ << "] with [" << calibration_type << "] Calibration at t=" << timestamp
135 << std::endl;
136
137 std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
138 std::cout << "\tPosition[m]: [" << sensor_state.state_.p_ip_.transpose() << " ]" << std::endl;
139 std::cout << "\tBias[m]: " << sensor_state.state_.bias_p_ << std::endl;
140
141 return result;
142 }
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24
+ Here is the call graph for this function:

◆ CalcUpdate()

bool mars::PressureSensorClass::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

Implements mars::SensorInterface.

147 {
148 // Cast the sensor measurement and prior state information
149 PressureMeasurementType* meas = static_cast<PressureMeasurementType*>(measurement.get());
150 PressureSensorData* prior_sensor_data = static_cast<PressureSensorData*>(latest_sensor_data.get());
151
152 // Decompose sensor measurement
153 Eigen::Matrix<double, 1, 1> h_meas = pressure_conversion_.get_height(meas->pressure_);
154
155 // Extract sensor state
156 PressureSensorStateType prior_sensor_state(prior_sensor_data->state_);
157
158 // Generate measurement noise matrix and check
159 // if noisevalues from the measurement object should be used
160 Eigen::MatrixXd R_meas_dyn;
161 if (meas->has_meas_noise && use_dynamic_meas_noise_)
162 {
163 meas->get_meas_noise(&R_meas_dyn);
164 }
165 else
166 {
167 R_meas_dyn = this->R_.asDiagonal();
168 }
169 const Eigen::Matrix<double, 1, 1> R_meas = R_meas_dyn;
170
171 const int size_of_core_state = CoreStateType::size_error_;
172 const int size_of_sensor_state = prior_sensor_state.cov_size_;
173 const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
174 const Eigen::MatrixXd P = prior_cov;
175 assert(P.size() == size_of_full_error_state * size_of_full_error_state);
176
177 // Calculate the measurement jacobian H
178 typedef Eigen::Matrix<double, 1, 3> Matrix13d_t;
179 typedef Eigen::Matrix<double, 1, 1> Matrix1d_t;
180 const Matrix1d_t I_1{ 1 };
181 const Matrix13d_t I_el3{ 0, 0, 1 };
182 const Matrix13d_t Z_el3{ 0, 0, 0 };
183 const Eigen::Vector3d P_wi = prior_core_state.p_wi_;
184 const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
185 const Eigen::Vector3d P_ip = prior_sensor_state.p_ip_;
186 const Eigen::Vector3d bias_p = Eigen::Vector3d(0, 0, prior_sensor_state.bias_p_);
187
188 // Position
189 const Matrix13d_t Hp_pwi = I_el3;
190 const Matrix13d_t Hp_vwi = Z_el3;
191 const Eigen::Matrix3d Hp_rwi3 = -R_wi * Utils::Skew(P_ip);
192 const Matrix13d_t Hp_rwi = I_el3 * Hp_rwi3;
193 const Matrix13d_t Hp_bw = Z_el3;
194 const Matrix13d_t Hp_ba = Z_el3;
195
196 // with bias
197 const Eigen::Matrix3d Hp_pip3 = R_wi;
198 const Matrix13d_t Hp_pip = I_el3 * Hp_pip3;
199 const Matrix1d_t Hp_biasp = I_1;
200
201 // H_p = [Hp_pwi Hp_vwi Hp_rwi Hp_bw Hp_ba Hp_pip Hp_biasp];
202 Eigen::MatrixXd H(1, Hp_pwi.cols() + Hp_vwi.cols() + Hp_rwi.cols() + Hp_bw.cols() + Hp_ba.cols() + Hp_pip.cols() +
203 Hp_biasp.cols());
204
205 H << Hp_pwi, Hp_vwi, Hp_rwi, Hp_bw, Hp_ba, Hp_pip, Hp_biasp;
206
207 // Calculate the residual z = z~ - (estimate)
208 // Position
209 const Eigen::Vector3d h_est3 = P_wi + R_wi * P_ip + bias_p;
210 const Matrix1d_t h_est = I_el3 * h_est3;
211 residual_ = Eigen::MatrixXd(h_est.rows(), 1);
212 residual_ = h_meas - h_est;
213
214 // Perform EKF calculations
215 mars::Ekf ekf(H, R_meas, residual_, P);
216 const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
217 assert(correction.size() == size_of_full_error_state * 1);
218
219 // Perform Chi2 test
220 if (!chi2_.passed_ && chi2_.do_test_)
221 {
223 return false;
224 }
225
226 Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
227 assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
228 P_updated = Utils::EnforceMatrixSymmetry(P_updated);
229
230 // Apply Core Correction
231 CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
232 CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
233
234 // Apply Sensor Correction
235 const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
236 const PressureSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
237
238 // Return Results
239 // CoreState data
240 CoreType core_data;
241 core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
242 core_data.state_ = corrected_core_state;
243
244 // SensorState data
245 std::shared_ptr<PressureSensorData> sensor_data(std::make_shared<PressureSensorData>());
246 sensor_data->set_cov(P_updated);
247 sensor_data->state_ = corrected_sensor_state;
248
249 BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
250
252 {
253 // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
254 }
255 else
256 {
257 // TODO also estimate ref to nav
258 }
259
260 *new_state_data = state_entry;
261
262 return true;
263 }
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
Matrix1d get_height(Pressure pressure)
Converts the given pressure measurement to a height (distance) value.
PressureSensorStateType ApplyCorrection(const PressureSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition pressure_sensor_class.h:265
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
Eigen::Matrix< double, CoreStateType::size_error_, 1 > CoreStateVector
Definition core_state_type.h:135
+ Here is the call graph for this function:

◆ ApplyCorrection()

PressureSensorStateType mars::PressureSensorClass::ApplyCorrection ( const PressureSensorStateType prior_sensor_state,
const Eigen::MatrixXd &  correction 
)
inline
267 {
268 // state + error state correction
269 PressureSensorStateType corrected_sensor_state;
270 corrected_sensor_state.p_ip_ = prior_sensor_state.p_ip_ + correction.block(0, 0, 3, 1);
271 corrected_sensor_state.bias_p_ = prior_sensor_state.bias_p_ + correction(3);
272
273 return corrected_sensor_state;
274 }
+ Here is the caller graph for this function:

Member Data Documentation

◆ pressure_conversion_

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PressureConversion mars::PressureSensorClass::pressure_conversion_

◆ pressure_reference_is_set_

bool mars::PressureSensorClass::pressure_reference_is_set_

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