mars_lib  0.1.0.3dc76ee85e09
Modular and Robust Sensor-Fusion
Public Member Functions | List of all members
mars::PoseSensorClass Class Reference

#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/pose/pose_sensor_class.h>

+ Inheritance diagram for mars::PoseSensorClass:
+ Collaboration diagram for mars::PoseSensorClass:

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PoseSensorClass (const std::string &name, std::shared_ptr< CoreState > core_states)
 
virtual ~PoseSensorClass ()=default
 
PoseSensorStateType 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 More...
 
void set_initial_calib (std::shared_ptr< void > calibration)
 set_initial_calib Sets the calibration of an individual sensor More...
 
BufferDataType Initialize (const Time &timestamp, std::shared_ptr< void >, std::shared_ptr< CoreType > latest_core_data)
 Initialize the state of an individual sensor. More...
 
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. More...
 
PoseSensorStateType ApplyCorrection (const PoseSensorStateType &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". More...
 
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. More...
 
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. More...
 
bool is_initialized_ { false }
 True if the sensor has been initialized. More...
 
bool do_update_ { true }
 True if updates should be performed with the sensor. More...
 
int type_ { -1 }
 Future feature, holds information such as position or orientation for highlevel decissions. More...
 
bool const_ref_to_nav_ { true }
 True if the reference should not be estimated. More...
 
bool ref_to_nav_given_ { false }
 True if the reference to the navigation frame is given by initial calibration. More...
 
bool use_dynamic_meas_noise_ { false }
 True if dynamic noise values from measurements should be used. More...
 

Constructor & Destructor Documentation

◆ PoseSensorClass()

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

◆ ~PoseSensorClass()

virtual mars::PoseSensorClass::~PoseSensorClass ( )
virtualdefault

Member Function Documentation

◆ get_state()

PoseSensorStateType mars::PoseSensorClass::get_state ( const std::shared_ptr< void > &  sensor_data)
inline
55  {
56  PoseSensorData data = *static_cast<PoseSensorData*>(sensor_data.get());
57  return data.state_;
58  }
BindSensorData< PoseSensorStateType > PoseSensorData
Definition: pose_sensor_class.h:32

◆ get_covariance()

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

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

◆ set_initial_calib()

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

set_initial_calib Sets the calibration of an individual sensor

Parameters
calibration

Implements mars::SensorInterface.

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

◆ Initialize()

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

74  {
75  // PoseMeasurementType measurement = *static_cast<PoseMeasurementType*>(sensor_data.get());
76 
77  PoseSensorData sensor_state;
78  std::string calibration_type;
79 
80  if (this->initial_calib_provided_)
81  {
82  calibration_type = "Given";
83 
84  PoseSensorData calib = *static_cast<PoseSensorData*>(initial_calib_.get());
85 
86  sensor_state.state_ = calib.state_;
87  sensor_state.sensor_cov_ = calib.sensor_cov_;
88  }
89  else
90  {
91  calibration_type = "Auto";
92  std::cout << "Pose 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<PoseSensorData>(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 
106  {
107  std::cout << "Info: [" << name_ << "] Calibration(rounded):" << std::endl;
108  std::cout << "\tPosition[m]: [" << sensor_state.state_.p_ip_.transpose() << " ]" << std::endl;
109  std::cout << "\tOrientation[deg]: ["
110  << sensor_state.state_.q_ip_.toRotationMatrix().eulerAngles(0, 1, 2).transpose() * (180 / M_PI) << " ]"
111  << std::endl;
112  }
113 
114  return result;
115  }
bool is_initialized_
True if the sensor has been initialized.
Definition: sensor_abs_class.h:24

◆ CalcUpdate()

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

120  {
121  // Cast the sensor measurement and prior state information
122  PoseMeasurementType* meas = static_cast<PoseMeasurementType*>(measurement.get());
123  PoseSensorData* prior_sensor_data = static_cast<PoseSensorData*>(latest_sensor_data.get());
124 
125  // Decompose sensor measurement
126  Eigen::Vector3d p_meas = meas->position_;
127  Eigen::Quaternion<double> q_meas = meas->orientation_;
128 
129  // Extract sensor state
130  PoseSensorStateType prior_sensor_state(prior_sensor_data->state_);
131 
132  // Generate measurement noise matrix and check
133  // if noisevalues from the measurement object should be used
134  Eigen::MatrixXd R_meas_dyn;
135  if (meas->has_meas_noise && use_dynamic_meas_noise_)
136  {
137  meas->get_meas_noise(&R_meas_dyn);
138  }
139  else
140  {
141  R_meas_dyn = this->R_.asDiagonal();
142  }
143  const Eigen::Matrix<double, 6, 6> R_meas = R_meas_dyn;
144 
145  const int size_of_core_state = CoreStateType::size_error_;
146  const int size_of_sensor_state = prior_sensor_state.cov_size_;
147  const int size_of_full_error_state = size_of_core_state + size_of_sensor_state;
148  const Eigen::MatrixXd P = prior_cov;
149  assert(P.size() == size_of_full_error_state * size_of_full_error_state);
150 
151  // Calculate the measurement jacobian H
152  const Eigen::Matrix3d I_3 = Eigen::Matrix3d::Identity();
153  const Eigen::Vector3d P_wi = prior_core_state.p_wi_;
154  const Eigen::Matrix3d R_wi = prior_core_state.q_wi_.toRotationMatrix();
155  const Eigen::Vector3d P_ip = prior_sensor_state.p_ip_;
156  const Eigen::Matrix3d R_ip = prior_sensor_state.q_ip_.toRotationMatrix();
157 
158  // Position
159  const Eigen::Matrix3d Hp_pwi = I_3;
160  const Eigen::Matrix3d Hp_vwi = Eigen::Matrix3d::Zero();
161  const Eigen::Matrix3d Hp_rwi = -R_wi * Utils::Skew(P_ip);
162  const Eigen::Matrix3d Hp_bw = Eigen::Matrix3d::Zero();
163  const Eigen::Matrix3d Hp_ba = Eigen::Matrix3d::Zero();
164  const Eigen::Matrix3d Hp_ip = R_wi;
165  const Eigen::Matrix3d Hp_rip = Eigen::Matrix3d::Zero();
166 
167  // Assemble the jacobian for the position (horizontal)
168  // H_p = [Hp_pwi Hp_vwi Hp_rwi Hp_bw Hp_ba Hp_ip Hp_rip];
169  Eigen::MatrixXd H_p(3, Hp_pwi.cols() + Hp_vwi.cols() + Hp_rwi.cols() + Hp_bw.cols() + Hp_ba.cols() + Hp_ip.cols() +
170  Hp_rip.cols());
171  H_p << Hp_pwi, Hp_vwi, Hp_rwi, Hp_bw, Hp_ba, Hp_ip, Hp_rip;
172 
173  // Orientation
174  const Eigen::Matrix3d Hr_pwi = Eigen::Matrix3d::Zero();
175  const Eigen::Matrix3d Hr_vwi = Eigen::Matrix3d::Zero();
176  const Eigen::Matrix3d Hr_rwi = R_ip.transpose();
177  const Eigen::Matrix3d Hr_bw = Eigen::Matrix3d::Zero();
178  const Eigen::Matrix3d Hr_ba = Eigen::Matrix3d::Zero();
179  const Eigen::Matrix3d Hr_pip = Eigen::Matrix3d::Zero();
180  const Eigen::Matrix3d Hr_rip = I_3;
181 
182  // Assemble the jacobian for the orientation (horizontal)
183  // H_r = [Hr_pwi Hr_vwi Hr_rwi Hr_bw Hr_ba Hr_pip Hr_rip];
184  Eigen::MatrixXd H_r(3, Hr_pwi.cols() + Hr_vwi.cols() + Hr_rwi.cols() + Hr_bw.cols() + Hr_ba.cols() + Hr_pip.cols() +
185  Hr_rip.cols());
186  H_r << Hr_pwi, Hr_vwi, Hr_rwi, Hr_bw, Hr_ba, Hr_pip, Hr_rip;
187 
188  // Combine all jacobians (vertical)
189  Eigen::MatrixXd H(H_p.rows() + H_r.rows(), H_r.cols());
190  H << H_p, H_r;
191 
192  // Calculate the residual z = z~ - (estimate)
193  // Position
194  const Eigen::Vector3d p_est = P_wi + R_wi * P_ip;
195  const Eigen::Vector3d res_p = p_meas - p_est;
196  // Orientation
197  const Eigen::Quaternion<double> q_est = prior_core_state.q_wi_ * prior_sensor_state.q_ip_;
198  const Eigen::Quaternion<double> res_q = q_est.inverse() * q_meas;
199  const Eigen::Vector3d res_r = 2 * res_q.vec() / res_q.w();
200 
201  // Combine residuals (vertical)
202  residual_ = Eigen::MatrixXd(res_p.rows() + res_r.rows(), 1);
203  residual_ << res_p, res_r;
204 
205  // Perform EKF calculations
206  mars::Ekf ekf(H, R_meas, residual_, P);
207  const Eigen::MatrixXd correction = ekf.CalculateCorrection(&chi2_);
208  assert(correction.size() == size_of_full_error_state * 1);
209 
210  // Perform Chi2 test
211  if (!chi2_.passed_ && chi2_.do_test_)
212  {
214  return false;
215  }
216 
217  Eigen::MatrixXd P_updated = ekf.CalculateCovUpdate();
218  assert(P_updated.size() == size_of_full_error_state * size_of_full_error_state);
219  P_updated = Utils::EnforceMatrixSymmetry(P_updated);
220 
221  // Apply Core Correction
222  CoreStateVector core_correction = correction.block(0, 0, CoreStateType::size_error_, 1);
223  CoreStateType corrected_core_state = CoreStateType::ApplyCorrection(prior_core_state, core_correction);
224 
225  // Apply Sensor Correction
226  const Eigen::MatrixXd sensor_correction = correction.block(size_of_core_state, 0, size_of_sensor_state, 1);
227  const PoseSensorStateType corrected_sensor_state = ApplyCorrection(prior_sensor_state, sensor_correction);
228 
229  // Return Results
230  // CoreState data
231  CoreType core_data;
232  core_data.cov_ = P_updated.block(0, 0, CoreStateType::size_error_, CoreStateType::size_error_);
233  core_data.state_ = corrected_core_state;
234 
235  // SensorState data
236  std::shared_ptr<PoseSensorData> sensor_data(std::make_shared<PoseSensorData>());
237  sensor_data->set_cov(P_updated);
238  sensor_data->state_ = corrected_sensor_state;
239 
240  BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
241 
242  if (const_ref_to_nav_)
243  {
244  // corrected_sensor_data.ref_to_nav = prior_ref_to_nav;
245  }
246  else
247  {
248  // TODO(chb) also estimate ref to nav
249  }
250 
251  *new_state_data = state_entry;
252 
253  return true;
254  }
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
PoseSensorStateType ApplyCorrection(const PoseSensorStateType &prior_sensor_state, const Eigen::MatrixXd &correction)
Definition: pose_sensor_class.h:256
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()

PoseSensorStateType mars::PoseSensorClass::ApplyCorrection ( const PoseSensorStateType prior_sensor_state,
const Eigen::MatrixXd &  correction 
)
inline
257  {
258  // state + error state correction
259  // with quaternion from small angle approx -> new state
260 
261  PoseSensorStateType corrected_sensor_state;
262  corrected_sensor_state.p_ip_ = prior_sensor_state.p_ip_ + correction.block(0, 0, 3, 1);
263  corrected_sensor_state.q_ip_ =
264  Utils::ApplySmallAngleQuatCorr(prior_sensor_state.q_ip_, correction.block(3, 0, 3, 1));
265  return corrected_sensor_state;
266  }
static Eigen::Quaterniond ApplySmallAngleQuatCorr(const Eigen::Quaterniond &q_prior, const Eigen::Vector3d &correction)
ApplySmallAngleQuatCorr.
+ Here is the call graph for this function:
+ Here is the caller graph for this function:

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