#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/sensor_abs_class.h>
|
std::ostream & | operator<< (std::ostream &out, const SensorAbsClass &sensor) |
| operator << Overload the << operator for easy printing of the sensor information More...
|
|
|
virtual EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ~SensorInterface ()=default |
|
virtual void | set_initial_calib (std::shared_ptr< void > calibration)=0 |
| set_initial_calib Sets the calibration of an individual sensor More...
|
|
virtual BufferDataType | Initialize (const Time ×tamp, std::shared_ptr< void > measurement, std::shared_ptr< CoreType > latest_core_data)=0 |
| Initialize the state of an individual sensor. More...
|
|
virtual bool | CalcUpdate (const Time ×tamp, 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)=0 |
| CalcUpdate Calculates the update for an individual sensor definition. More...
|
|
virtual Eigen::MatrixXd | get_covariance (const std::shared_ptr< void > &sensor_data)=0 |
| 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...
|
|
◆ operator<<
std::ostream& operator<< |
( |
std::ostream & |
out, |
|
|
const SensorAbsClass & |
sensor |
|
) |
| |
|
friend |
operator << Overload the << operator for easy printing of the sensor information
36 out <<
"\tSensor: " << sensor.name_ << std::endl;
37 out <<
"\tInitialized: " << sensor.is_initialized_ << std::endl;
38 out <<
"\tDo update: " << sensor.do_update_ << std::endl;
39 out <<
"\tReference to nav: " << sensor.const_ref_to_nav_ << std::endl;
40 out <<
"\tUse dynamic noise: " << sensor.use_dynamic_meas_noise_ << std::endl;
◆ id_
int mars::SensorAbsClass::id_ { -1 } |
◆ name_
std::string mars::SensorAbsClass::name_ |
Name of the individual sensor instance.
◆ is_initialized_
bool mars::SensorAbsClass::is_initialized_ { false } |
True if the sensor has been initialized.
◆ do_update_
bool mars::SensorAbsClass::do_update_ { true } |
True if updates should be performed with the sensor.
◆ type_
int mars::SensorAbsClass::type_ { -1 } |
Future feature, holds information such as position or orientation for highlevel decissions.
◆ const_ref_to_nav_
bool mars::SensorAbsClass::const_ref_to_nav_ { true } |
True if the reference should not be estimated.
◆ ref_to_nav_given_
bool mars::SensorAbsClass::ref_to_nav_given_ { false } |
True if the reference to the navigation frame is given by initial calibration.
◆ use_dynamic_meas_noise_
bool mars::SensorAbsClass::use_dynamic_meas_noise_ { false } |
True if dynamic noise values from measurements should be used.
The documentation for this class was generated from the following file: