PX4 Firmware
PX4 Autopilot Software http://px4.io
sensors::TemperatureCompensation Class Reference

class TemperatureCompensation Applies temperature compensation to sensor data. More...

#include <temperature_compensation.h>

Collaboration diagram for sensors::TemperatureCompensation:

Classes

struct  ParameterHandles
 
struct  Parameters
 
struct  PerSensorData
 
struct  SensorCalData1D
 
struct  SensorCalData3D
 
struct  SensorCalHandles1D
 
struct  SensorCalHandles3D
 

Public Member Functions

int parameters_update (bool hil_enabled=false)
 (re)load the parameters. More...
 
int set_sensor_id_gyro (uint32_t device_id, int topic_instance)
 supply information which device_id matches a specific uORB topic_instance (needed if a system has multiple sensors of the same type) More...
 
int set_sensor_id_accel (uint32_t device_id, int topic_instance)
 
int set_sensor_id_baro (uint32_t device_id, int topic_instance)
 
int apply_corrections_gyro (int topic_instance, matrix::Vector3f &sensor_data, float temperature, float *offsets, float *scales)
 Apply Thermal corrections to gyro (& other) sensor data. More...
 
int apply_corrections_accel (int topic_instance, matrix::Vector3f &sensor_data, float temperature, float *offsets, float *scales)
 
int apply_corrections_baro (int topic_instance, float &sensor_data, float temperature, float *offsets, float *scales)
 
void print_status ()
 output current configuration status to console More...
 

Private Member Functions

bool calc_thermal_offsets_1D (SensorCalData1D &coef, float measured_temp, float &offset)
 Calculate the offset required to compensate the sensor for temperature effects using a 5th order method If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false. More...
 
bool calc_thermal_offsets_3D (const SensorCalData3D &coef, float measured_temp, float offset[])
 Calculate the offsets required to compensate the sensor for temperature effects If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false. More...
 

Static Private Member Functions

static int initialize_parameter_handles (ParameterHandles &parameter_handles)
 initialize ParameterHandles struct More...
 
template<typename T >
static int set_sensor_id (uint32_t device_id, int topic_instance, PerSensorData &sensor_data, const T *sensor_cal_data, uint8_t sensor_count_max)
 

Private Attributes

Parameters _parameters
 
PerSensorData _gyro_data
 
PerSensorData _accel_data
 
PerSensorData _baro_data
 

Detailed Description

class TemperatureCompensation Applies temperature compensation to sensor data.

Loads the parameters from PX4 param storage.

Definition at line 66 of file temperature_compensation.h.

Member Function Documentation

◆ apply_corrections_accel()

int sensors::TemperatureCompensation::apply_corrections_accel ( int  topic_instance,
matrix::Vector3f sensor_data,
float  temperature,
float *  offsets,
float *  scales 
)

Definition at line 424 of file temperature_compensation.cpp.

References _accel_data, _parameters, sensors::TemperatureCompensation::Parameters::accel_cal_data, sensors::TemperatureCompensation::Parameters::accel_tc_enable, calc_thermal_offsets_3D(), sensors::TemperatureCompensation::PerSensorData::device_mapping, sensors::TemperatureCompensation::PerSensorData::last_temperature, and sensors::TemperatureCompensation::SensorCalData3D::scale.

Referenced by sensors::VotedSensorsUpdate::accelPoll().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ apply_corrections_baro()

int sensors::TemperatureCompensation::apply_corrections_baro ( int  topic_instance,
float &  sensor_data,
float  temperature,
float *  offsets,
float *  scales 
)

Definition at line 453 of file temperature_compensation.cpp.

References _baro_data, _parameters, sensors::TemperatureCompensation::Parameters::baro_cal_data, sensors::TemperatureCompensation::Parameters::baro_tc_enable, calc_thermal_offsets_1D(), sensors::TemperatureCompensation::PerSensorData::device_mapping, sensors::TemperatureCompensation::PerSensorData::last_temperature, and sensors::TemperatureCompensation::SensorCalData1D::scale.

Referenced by sensors::VotedSensorsUpdate::baroPoll().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ apply_corrections_gyro()

int sensors::TemperatureCompensation::apply_corrections_gyro ( int  topic_instance,
matrix::Vector3f sensor_data,
float  temperature,
float *  offsets,
float *  scales 
)

Apply Thermal corrections to gyro (& other) sensor data.

Parameters
topic_instanceuORB topic instance
sensor_datainput sensor data, output sensor data with applied corrections
temperaturemeasured current temperature
offsetsreturns offsets that were applied (length = 3, except for baro), depending on return value
scalesreturns scales that were applied (length = 3), depending on return value
Returns
-1: error: correction enabled, but no sensor mapping set (
See also
set_sendor_id_gyro) 0: no changes (correction not enabled), 1: corrections applied but no changes to offsets & scales, 2: corrections applied and offsets & scales updated

Definition at line 395 of file temperature_compensation.cpp.

References _gyro_data, _parameters, calc_thermal_offsets_3D(), sensors::TemperatureCompensation::PerSensorData::device_mapping, sensors::TemperatureCompensation::Parameters::gyro_cal_data, sensors::TemperatureCompensation::Parameters::gyro_tc_enable, sensors::TemperatureCompensation::PerSensorData::last_temperature, and sensors::TemperatureCompensation::SensorCalData3D::scale.

Referenced by sensors::VotedSensorsUpdate::gyroPoll().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ calc_thermal_offsets_1D()

bool sensors::TemperatureCompensation::calc_thermal_offsets_1D ( SensorCalData1D coef,
float  measured_temp,
float &  offset 
)
private

Calculate the offset required to compensate the sensor for temperature effects using a 5th order method If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false.

If the measured temperature is within the calibration range, return true.

Arguments:

coef : reference to struct containing calibration coefficients measured_temp : temperature measured at the sensor (deg C) offset : reference to sensor offset

Returns:

Boolean true if the measured temperature is inside the valid range for the compensation

Definition at line 286 of file temperature_compensation.cpp.

References sensors::TemperatureCompensation::SensorCalData1D::max_temp, sensors::TemperatureCompensation::SensorCalData1D::min_temp, sensors::TemperatureCompensation::SensorCalData1D::ref_temp, sensors::TemperatureCompensation::SensorCalData1D::x0, sensors::TemperatureCompensation::SensorCalData1D::x1, sensors::TemperatureCompensation::SensorCalData1D::x2, sensors::TemperatureCompensation::SensorCalData1D::x3, sensors::TemperatureCompensation::SensorCalData1D::x4, and sensors::TemperatureCompensation::SensorCalData1D::x5.

Referenced by apply_corrections_baro().

Here is the caller graph for this function:

◆ calc_thermal_offsets_3D()

bool sensors::TemperatureCompensation::calc_thermal_offsets_3D ( const SensorCalData3D coef,
float  measured_temp,
float  offset[] 
)
private

Calculate the offsets required to compensate the sensor for temperature effects If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false.

If the measured temperature is within the calibration range, return true.

Arguments:

coef : reference to struct containing calibration coefficients measured_temp : temperature measured at the sensor (deg C) offset : reference to sensor offset - array of 3

Returns:

Boolean true if the measured temperature is inside the valid range for the compensation

Definition at line 322 of file temperature_compensation.cpp.

References sensors::TemperatureCompensation::SensorCalData3D::max_temp, sensors::TemperatureCompensation::SensorCalData3D::min_temp, sensors::TemperatureCompensation::SensorCalData3D::ref_temp, sensors::TemperatureCompensation::SensorCalData3D::x0, sensors::TemperatureCompensation::SensorCalData3D::x1, sensors::TemperatureCompensation::SensorCalData3D::x2, and sensors::TemperatureCompensation::SensorCalData3D::x3.

Referenced by apply_corrections_accel(), and apply_corrections_gyro().

Here is the caller graph for this function:

◆ initialize_parameter_handles()

int sensors::TemperatureCompensation::initialize_parameter_handles ( ParameterHandles parameter_handles)
staticprivate

initialize ParameterHandles struct

Returns
0 on succes, <0 on error

Definition at line 50 of file temperature_compensation.cpp.

References sensors::TemperatureCompensation::ParameterHandles::accel_cal_handles, sensors::ACCEL_COUNT_MAX, sensors::TemperatureCompensation::ParameterHandles::accel_tc_enable, sensors::TemperatureCompensation::ParameterHandles::baro_cal_handles, sensors::BARO_COUNT_MAX, sensors::TemperatureCompensation::ParameterHandles::baro_tc_enable, sensors::TemperatureCompensation::ParameterHandles::gyro_cal_handles, sensors::GYRO_COUNT_MAX, sensors::TemperatureCompensation::ParameterHandles::gyro_tc_enable, sensors::TemperatureCompensation::SensorCalHandles1D::ID, sensors::TemperatureCompensation::SensorCalHandles3D::ID, sensors::TemperatureCompensation::SensorCalHandles1D::max_temp, sensors::TemperatureCompensation::SensorCalHandles3D::max_temp, sensors::TemperatureCompensation::SensorCalHandles1D::min_temp, sensors::TemperatureCompensation::SensorCalHandles3D::min_temp, param_find(), param_get(), sensors::TemperatureCompensation::SensorCalHandles1D::ref_temp, sensors::TemperatureCompensation::SensorCalHandles3D::ref_temp, sensors::TemperatureCompensation::SensorCalHandles1D::scale, sensors::TemperatureCompensation::SensorCalHandles3D::scale, sensors::TemperatureCompensation::SensorCalHandles1D::x0, sensors::TemperatureCompensation::SensorCalHandles3D::x0, sensors::TemperatureCompensation::SensorCalHandles1D::x1, sensors::TemperatureCompensation::SensorCalHandles3D::x1, sensors::TemperatureCompensation::SensorCalHandles1D::x2, sensors::TemperatureCompensation::SensorCalHandles3D::x2, sensors::TemperatureCompensation::SensorCalHandles1D::x3, sensors::TemperatureCompensation::SensorCalHandles3D::x3, sensors::TemperatureCompensation::SensorCalHandles1D::x4, and sensors::TemperatureCompensation::SensorCalHandles1D::x5.

Referenced by parameters_update().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ parameters_update()

int sensors::TemperatureCompensation::parameters_update ( bool  hil_enabled = false)

(re)load the parameters.

Make sure to call this on startup as well

Definition at line 154 of file temperature_compensation.cpp.

References _accel_data, _baro_data, _gyro_data, _parameters, sensors::TemperatureCompensation::Parameters::accel_cal_data, sensors::TemperatureCompensation::ParameterHandles::accel_cal_handles, sensors::ACCEL_COUNT_MAX, sensors::TemperatureCompensation::Parameters::accel_tc_enable, sensors::TemperatureCompensation::ParameterHandles::accel_tc_enable, sensors::TemperatureCompensation::Parameters::baro_cal_data, sensors::TemperatureCompensation::ParameterHandles::baro_cal_handles, sensors::BARO_COUNT_MAX, sensors::TemperatureCompensation::Parameters::baro_tc_enable, sensors::TemperatureCompensation::ParameterHandles::baro_tc_enable, sensors::TemperatureCompensation::Parameters::gyro_cal_data, sensors::TemperatureCompensation::ParameterHandles::gyro_cal_handles, sensors::GYRO_COUNT_MAX, sensors::TemperatureCompensation::Parameters::gyro_tc_enable, sensors::TemperatureCompensation::ParameterHandles::gyro_tc_enable, sensors::TemperatureCompensation::SensorCalData1D::ID, sensors::TemperatureCompensation::SensorCalHandles1D::ID, sensors::TemperatureCompensation::SensorCalData3D::ID, sensors::TemperatureCompensation::SensorCalHandles3D::ID, initialize_parameter_handles(), sensors::TemperatureCompensation::SensorCalData1D::max_temp, sensors::TemperatureCompensation::SensorCalHandles1D::max_temp, sensors::TemperatureCompensation::SensorCalData3D::max_temp, sensors::TemperatureCompensation::SensorCalHandles3D::max_temp, sensors::TemperatureCompensation::SensorCalData1D::min_temp, sensors::TemperatureCompensation::SensorCalHandles1D::min_temp, sensors::TemperatureCompensation::SensorCalData3D::min_temp, sensors::TemperatureCompensation::SensorCalHandles3D::min_temp, param_get(), sensors::TemperatureCompensation::SensorCalData1D::ref_temp, sensors::TemperatureCompensation::SensorCalHandles1D::ref_temp, sensors::TemperatureCompensation::SensorCalData3D::ref_temp, sensors::TemperatureCompensation::SensorCalHandles3D::ref_temp, sensors::TemperatureCompensation::PerSensorData::reset_temperature(), sensors::TemperatureCompensation::SensorCalData1D::scale, sensors::TemperatureCompensation::SensorCalHandles1D::scale, sensors::TemperatureCompensation::SensorCalData3D::scale, sensors::TemperatureCompensation::SensorCalHandles3D::scale, sensors::TemperatureCompensation::SensorCalData1D::x0, sensors::TemperatureCompensation::SensorCalHandles1D::x0, sensors::TemperatureCompensation::SensorCalData3D::x0, sensors::TemperatureCompensation::SensorCalHandles3D::x0, sensors::TemperatureCompensation::SensorCalData1D::x1, sensors::TemperatureCompensation::SensorCalHandles1D::x1, sensors::TemperatureCompensation::SensorCalData3D::x1, sensors::TemperatureCompensation::SensorCalHandles3D::x1, sensors::TemperatureCompensation::SensorCalData1D::x2, sensors::TemperatureCompensation::SensorCalHandles1D::x2, sensors::TemperatureCompensation::SensorCalData3D::x2, sensors::TemperatureCompensation::SensorCalHandles3D::x2, sensors::TemperatureCompensation::SensorCalData1D::x3, sensors::TemperatureCompensation::SensorCalHandles1D::x3, sensors::TemperatureCompensation::SensorCalData3D::x3, sensors::TemperatureCompensation::SensorCalHandles3D::x3, sensors::TemperatureCompensation::SensorCalData1D::x4, sensors::TemperatureCompensation::SensorCalHandles1D::x4, sensors::TemperatureCompensation::SensorCalData1D::x5, and sensors::TemperatureCompensation::SensorCalHandles1D::x5.

Referenced by sensors::VotedSensorsUpdate::parametersUpdate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ print_status()

◆ set_sensor_id()

template<typename T >
int sensors::TemperatureCompensation::set_sensor_id ( uint32_t  device_id,
int  topic_instance,
PerSensorData sensor_data,
const T *  sensor_cal_data,
uint8_t  sensor_count_max 
)
inlinestaticprivate

Definition at line 382 of file temperature_compensation.cpp.

References sensors::TemperatureCompensation::PerSensorData::device_mapping, and ID.

Referenced by set_sensor_id_accel(), set_sensor_id_baro(), and set_sensor_id_gyro().

Here is the caller graph for this function:

◆ set_sensor_id_accel()

int sensors::TemperatureCompensation::set_sensor_id_accel ( uint32_t  device_id,
int  topic_instance 
)

Definition at line 363 of file temperature_compensation.cpp.

References _accel_data, _parameters, sensors::TemperatureCompensation::Parameters::accel_cal_data, sensors::ACCEL_COUNT_MAX, sensors::TemperatureCompensation::Parameters::accel_tc_enable, and set_sensor_id().

Referenced by sensors::VotedSensorsUpdate::parametersUpdate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_sensor_id_baro()

int sensors::TemperatureCompensation::set_sensor_id_baro ( uint32_t  device_id,
int  topic_instance 
)

Definition at line 372 of file temperature_compensation.cpp.

References _baro_data, _parameters, sensors::TemperatureCompensation::Parameters::baro_cal_data, sensors::BARO_COUNT_MAX, sensors::TemperatureCompensation::Parameters::baro_tc_enable, and set_sensor_id().

Referenced by sensors::VotedSensorsUpdate::parametersUpdate().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_sensor_id_gyro()

int sensors::TemperatureCompensation::set_sensor_id_gyro ( uint32_t  device_id,
int  topic_instance 
)

supply information which device_id matches a specific uORB topic_instance (needed if a system has multiple sensors of the same type)

Returns
index for compensation parameter entry containing matching device ID on success, <0 otherwise

Definition at line 354 of file temperature_compensation.cpp.

References _gyro_data, _parameters, sensors::TemperatureCompensation::Parameters::gyro_cal_data, sensors::GYRO_COUNT_MAX, sensors::TemperatureCompensation::Parameters::gyro_tc_enable, and set_sensor_id().

Referenced by sensors::VotedSensorsUpdate::parametersUpdate().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _accel_data

PerSensorData sensors::TemperatureCompensation::_accel_data
private

◆ _baro_data

PerSensorData sensors::TemperatureCompensation::_baro_data
private

◆ _gyro_data

PerSensorData sensors::TemperatureCompensation::_gyro_data
private

◆ _parameters


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