#include </home/runner/work/mars_lib/mars_lib/source/mars/include/mars/sensors/empty/empty_sensor_class.h>
◆ EmptySensorClass()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW mars::EmptySensorClass::EmptySensorClass |
( |
const std::string & |
name, |
|
|
std::shared_ptr< CoreState > |
core_states |
|
) |
| |
|
inline |
39 {
44
45 std::cout <<
"Created: [" << this->
name_ <<
"] Sensor" << std::endl;
46 }
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
◆ ~EmptySensorClass()
virtual mars::EmptySensorClass::~EmptySensorClass |
( |
| ) |
|
|
virtualdefault |
◆ get_state()
EmptySensorStateType mars::EmptySensorClass::get_state |
( |
const std::shared_ptr< void > & |
sensor_data | ) |
|
|
inline |
51 {
53 return data.state_;
54 }
BindSensorData< EmptySensorStateType > EmptySensorData
Definition empty_sensor_class.h:30
◆ get_covariance()
Eigen::MatrixXd mars::EmptySensorClass::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
-
- Returns
- Covariance matrix contained in the sensor data struct
Implements mars::SensorInterface.
57 {
59 return data.get_full_cov();
60 }
◆ set_initial_calib()
void mars::EmptySensorClass::set_initial_calib |
( |
std::shared_ptr< void > |
calibration | ) |
|
|
inlinevirtual |
set_initial_calib Sets the calibration of an individual sensor
- Parameters
-
Implements mars::SensorInterface.
63 {
66 }
std::shared_ptr< void > initial_calib_
Definition update_sensor_abs_class.h:37
◆ Initialize()
BufferDataType mars::EmptySensorClass::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
-
timestamp | current timestamp |
measurement | current sensor measurement |
latest_core_data | |
- Returns
Implements mars::SensorInterface.
70 {
71
72
74 std::string calibration_type;
75
77 {
78 calibration_type = "Given";
79
81
82 sensor_state.state_ = calib.state_;
83 sensor_state.sensor_cov_ = calib.sensor_cov_;
84 }
85 else
86 {
87 std::cout << "Empty calibration AUTO init not implemented yet" << std::endl;
88 exit(EXIT_FAILURE);
89 }
90
91
92 BufferDataType result(std::make_shared<CoreType>(*latest_core_data.get()),
93 std::make_shared<EmptySensorData>(sensor_state));
94
96
97 std::cout <<
"Info: Initialized [" <<
name_ <<
"] with [" << calibration_type <<
"] Calibration at t=" << timestamp
98 << std::endl;
99
100 std::cout <<
"Info: [" <<
name_ <<
"] Calibration(rounded):" << std::endl;
101 std::cout << "\tPosition[m]: [" << sensor_state.state_.value_.transpose() << " ]" << std::endl;
102
103 return result;
104 }
bool is_initialized_
True if the sensor has been initialized.
Definition sensor_abs_class.h:24
◆ CalcUpdate()
bool mars::EmptySensorClass::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
-
timestamp | current timestamp |
measurement | current sensor measurement |
prior_core_state_data | |
latest_sensor_data | |
prior_cov | Prior covariance containing core, sensor and sensor cross covariance |
new_state_data | Updated state data |
- Returns
- True if the update was successful, false if the update was rejected
Implements mars::SensorInterface.
109 {
110
111
113
114
115 EmptySensorStateType prior_sensor_state(prior_sensor_data->state_);
116
117
118
119 CoreType core_data;
121 core_data.state_ = prior_core_state;
122
123
124 std::shared_ptr<EmptySensorData> sensor_data(std::make_shared<EmptySensorData>());
125 sensor_data->set_cov(prior_cov);
126 sensor_data->state_ = prior_sensor_state;
127
128 BufferDataType state_entry(std::make_shared<CoreType>(core_data), sensor_data);
129
130 *new_state_data = state_entry;
131
132 return true;
133 }
static constexpr int size_error_
Definition core_state_type.h:38
◆ ApplyCorrection()
137 {
138
139
140
141 EmptySensorStateType corrected_sensor_state;
142 corrected_sensor_state.value_ = prior_sensor_state.value_ + correction.block(0, 0, 3, 1);
143 return corrected_sensor_state;
144 }
The documentation for this class was generated from the following file: