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

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

+ Inheritance diagram for mars::SensorAbsClass:
+ Collaboration diagram for mars::SensorAbsClass:

Public Attributes

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.
 

Friends

std::ostream & operator<< (std::ostream &out, const SensorAbsClass &sensor)
 operator << Overload the << operator for easy printing of the sensor information
 

Additional Inherited Members

- Public Member Functions inherited from mars::SensorInterface
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
 
virtual BufferDataType Initialize (const Time &timestamp, std::shared_ptr< void > measurement, std::shared_ptr< CoreType > latest_core_data)=0
 Initialize the state of an individual sensor.
 
virtual bool 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)=0
 CalcUpdate Calculates the update for an individual sensor definition.
 
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
 

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  out,
const SensorAbsClass sensor 
)
friend

operator << Overload the << operator for easy printing of the sensor information

35 {
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;
41 return out;
42 }

Member Data Documentation

◆ id_

int mars::SensorAbsClass::id_ { -1 }
22{ -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.

24{ false };

◆ do_update_

bool mars::SensorAbsClass::do_update_ { true }

True if updates should be performed with the sensor.

25{ true };

◆ type_

int mars::SensorAbsClass::type_ { -1 }

Future feature, holds information such as position or orientation for highlevel decissions.

26{ -1 };

◆ const_ref_to_nav_

bool mars::SensorAbsClass::const_ref_to_nav_ { true }

True if the reference should not be estimated.

27{ true };

◆ 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.

28{ false };

◆ use_dynamic_meas_noise_

bool mars::SensorAbsClass::use_dynamic_meas_noise_ { false }

True if dynamic noise values from measurements should be used.

29{ false };

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