9 namespace configuration
44 SensorConfiguration(
const uint8_t calibrationMatrixActive,
const uint8_t temperatureCompensationActive,
45 const uint8_t imuActive,
const uint8_t coordinateSystemConfigurationActive,
46 const uint8_t inertiaCompensationActive,
const uint8_t orientationEstimationActive);
void setCoordinateSystemConfigurationActive(const uint8_t coordinateSystemConfigurationActive)
Sets the coordinateSystemConfigurationActive variable.
uint8_t inertiaCompensationActive_
void setTemperatureCompensationActive(const uint8_t temperatureCompensationActive)
Sets the temperatureCompensationActive variable.
uint8_t getTemperatureCompensationActive() const
Gets the temperatureCompensationActive variable.
void setImuActive(const uint8_t imuActive)
Sets the imuActive variable.
void print() const
Prints the existing sensor configuration settings.
uint8_t getInertiaCompensationActive() const
Gets the inertiaCompensationActive variable.
void setCalibrationMatrixActive(const uint8_t calibrationMatrixActive)
Sets the calibrationMatrixActive variable.
uint8_t orientationEstimationActive_
std::shared_ptr< ros::NodeHandle > NodeHandlePtr
Class holding the sensor configuration settings.
uint8_t getCoordinateSystemConfigurationActive() const
Gets the coordinateSystemConfigurationActive variable.
uint8_t temperatureCompensationActive_
uint8_t coordinateSystemConfigurationActive_
~SensorConfiguration()=default
uint8_t getOrientationEstimationActive() const
Gets the orientationEstimationActive variable.
void setOrientationEstimationActive(const uint8_t orientationEstimationActive)
Sets the orientationEstimationActive variable.
uint8_t getCalibrationMatrixActive() const
Gets the calibrationMatrixActive variable.
void setInertiaCompensationActive(const uint8_t inertiaCompensationActive)
Sets the inertiaCompensationActive variable.
bool load(const std::string &key, NodeHandlePtr nh)
Loads the sensor configuration from the parameter server.
SensorConfiguration()=default
Default constructor.
uint8_t getImuActive() const
Gets the imuActive variable.
uint8_t calibrationMatrixActive_