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

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/position/position_sensor_class.h>

+ Inheritance diagram for mars::PositionSensorClass:
+ Collaboration diagram for mars::PositionSensorClass:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PositionSensorClass (const std::string &name, std::shared_ptr< CoreState > core_states)
 
virtual ~PositionSensorClass ()=default
 
PositionSensorStateType 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.
 
PositionSensorStateType ApplyCorrection (const PositionSensorStateType &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

◆ PositionSensorClass()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW mars::PositionSensorClass::PositionSensorClass ( const std::string &  name,
std::shared_ptr< CoreState core_states 
)
inline
37 {
38 name_ = name;
39 core_states_ = std::move(core_states);
40 const_ref_to_nav_ = false;
42
43 // chi2
44 chi2_.set_dof(3);
45
46 std::cout << "Created: [" << this->name_ << "] Sensor" << std::endl;
47 }
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:

◆ ~PositionSensorClass()

virtual mars::PositionSensorClass::~PositionSensorClass ( )
virtualdefault

Member Function Documentation

◆ get_state()

PositionSensorStateType mars::PositionSensorClass::get_state ( const std::shared_ptr< void > &  sensor_data)
inline
52 {
53 PositionSensorData data = *static_cast<PositionSensorData*>(sensor_data.get());
54 return data.state_;
55 }
BindSensorData< PositionSensorStateType > PositionSensorData
Definition position_sensor_class.h:29

◆ get_covariance()

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

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

◆ set_initial_calib()

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

set_initial_calib Sets the calibration of an individual sensor

Parameters
calibration

Implements mars::SensorInterface.

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

◆ Initialize()

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

71 {
72 // PositionMeasurementType measurement = *static_cast<PositionMeasurementType*>(sensor_data.get());
73
74 PositionSensorData sensor_state;
75 std::string calibration_type;
76
78 {
79 calibration_type = "Given";
80
81 PositionSensorData calib = *static_cast<PositionSensorData*>(initial_calib_.get());
82
83 sensor_state.state_ = calib.state_;
84 sensor_state.sensor_cov_ = calib.sensor_cov_;
85 }
86 else
87 {
88 calibration_type = "Auto";
89 std::cout << "Position calibration AUTO init not implemented yet" << std::endl;
90 exit(EXIT_FAILURE);
91 }
92
93 // Bypass core state for the returned object
94 BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
95 std::make_shared<PositionSensorData>(sensor_state));
96
97 is_initialized_ = true;
98
99 std::cout << "Info: Initialized [" << name_ << "] with [" << calibration_type << "] Calibration at t=" << timestamp
100 << std::endl;
101
102 std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
103 std::cout << "\tPosition[m]: [" << sensor_state.state_.p_ip_.transpose() << " ]" << std::endl;
104
105 return result;
106 }
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24

◆ CalcUpdate()

bool mars::PositionSensorClass::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.

111 {
112 // Cast the sensor measurement and prior state information
113 PositionMeasurementType* meas = static_cast<PositionMeasurementType*>(measurement.get());
114 PositionSensorData* prior_sensor_data = static_cast<PositionSensorData*>(latest_sensor_data.get());
115
116 // Decompose sensor measurement
117 Eigen::Vector3d p_meas = meas->position_;
118
119 // Extract sensor state
120 PositionSensorStateType prior_sensor_state(prior_sensor_data->state_);
121
122 // Generate measurement noise matrix and check
123 // if noisevalues from the measurement object should be used
124 Eigen::MatrixXd R_meas_dyn;
125 if (meas->has_meas_noise && use_dynamic_meas_noise_)
126 {
127 meas->get_meas_noise(&R_meas_dyn);
128 }
129 else
130 {
131 R_meas_dyn = this->R_.asDiagonal();
132 }
133 const Eigen::Matrix<double, 3, 3> R_meas = R_meas_dyn;
134
135 const int size_of_core_state = CoreStateType::size_error_;
136 const int size_of_sensor_state = prior_sensor_state.cov_size_;
137 const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
138 const Eigen::MatrixXd P = prior_cov;
139 assert(P.size() == size_of_full_error_state * size_of_full_error_state);
140
141 // Calculate the measurement jacobian H
142 const Eigen::Matrix3d I_3 = Eigen::Matrix3d::Identity();
143 const Eigen::Vector3d P_wi = prior_core_state.p_wi_;
144 const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
145 const Eigen::Vector3d P_ip = prior_sensor_state.p_ip_;
146
147 // Position
148 const Eigen::Matrix3d Hp_pwi = I_3;
149 const Eigen::Matrix3d Hp_vwi = Eigen::Matrix3d::Zero();
150 const Eigen::Matrix3d Hp_rwi = -R_wi * Utils::Skew(P_ip);
151 const Eigen::Matrix3d Hp_bw = Eigen::Matrix3d::Zero();
152 const Eigen::Matrix3d Hp_ba = Eigen::Matrix3d::Zero();
153 const Eigen::Matrix3d Hp_pip = R_wi;
154
155 // Assemble the jacobian for the position (horizontal)
156 // H_p = [Hp_pwi Hp_vwi Hp_rwi Hp_bw Hp_ba Hp_pig ];
157 Eigen::MatrixXd H(3, Hp_pwi.cols() + Hp_vwi.cols() + Hp_rwi.cols() + Hp_bw.cols() + Hp_ba.cols() + Hp_pip.cols());
158
159 H << Hp_pwi, Hp_vwi, Hp_rwi, Hp_bw, Hp_ba, Hp_pip;
160
161 // Calculate the residual z = z~ - (estimate)
162 // Position
163 const Eigen::Vector3d p_est = P_wi + R_wi * P_ip;
164 residual_ = Eigen::MatrixXd(p_est.rows(), 1);
165 residual_ = p_meas - p_est;
166
167 // Perform EKF calculations
168 mars::Ekf ekf(H, R_meas, residual_, P);
169 const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
170 assert(correction.size() == size_of_full_error_state * 1);
171
172 // Perform Chi2 test
173 if (!chi2_.passed_ && chi2_.do_test_)
174 {
176 return false;
177 }
178
179 Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
180 assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
181 P_updated = Utils::EnforceMatrixSymmetry(P_updated);
182
183 // Apply Core Correction
184 CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
185 CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
186
187 // Apply Sensor Correction
188 const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
189 const PositionSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
190
191 // Return Results
192 // CoreState data
193 CoreType core_data;
194 core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
195 core_data.state_ = corrected_core_state;
196
197 // SensorState data
198 std::shared_ptr<PositionSensorData> sensor_data(std::make_shared<PositionSensorData>());
199 sensor_data->set_cov(P_updated);
200 sensor_data->state_ = corrected_sensor_state;
201
202 BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
203
205 {
206 // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
207 }
208 else
209 {
210 // TODO(chb) also estimate ref to nav
211 }
212
213 *new_state_data = state_entry;
214
215 return true;
216 }
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
PositionSensorStateType ApplyCorrection(const PositionSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition position_sensor_class.h:218
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()

PositionSensorStateType mars::PositionSensorClass::ApplyCorrection ( const PositionSensorStateType prior_sensor_state,
const Eigen::MatrixXd &  correction 
)
inline
220 {
221 // state + error state correction
222
223 PositionSensorStateType corrected_sensor_state;
224 corrected_sensor_state.p_ip_ = prior_sensor_state.p_ip_ + correction.block(0, 0, 3, 1);
225 return corrected_sensor_state;
226 }
+ Here is the caller graph for this function:

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