PX4 Firmware
PX4 Autopilot Software http://px4.io
temperature_compensation.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file temperature_compensation.h
36  *
37  * Sensor correction methods
38  *
39  * @author Paul Riseborough <gncsolns@gmail.com>
40  * @author Beat Küng <beat-kueng@gmx.net>
41  */
42 
43 #pragma once
44 
45 #include <parameters/param.h>
46 #include <mathlib/mathlib.h>
47 #include <matrix/math.hpp>
48 
49 #include "common.h"
50 
51 
52 namespace sensors
53 {
54 
55 static_assert(GYRO_COUNT_MAX == 3,
56  "GYRO_COUNT_MAX must be 3 (if changed, add/remove TC_* params to match the count)");
57 static_assert(ACCEL_COUNT_MAX == 3,
58  "ACCEL_COUNT_MAX must be 3 (if changed, add/remove TC_* params to match the count)");
59 static_assert(BARO_COUNT_MAX == 3,
60  "BARO_COUNT_MAX must be 3 (if changed, add/remove TC_* params to match the count)");
61 
62 /**
63  ** class TemperatureCompensation
64  * Applies temperature compensation to sensor data. Loads the parameters from PX4 param storage.
65  */
67 {
68 public:
69 
70  /** (re)load the parameters. Make sure to call this on startup as well */
71  int parameters_update(bool hil_enabled = false);
72 
73  /** supply information which device_id matches a specific uORB topic_instance
74  * (needed if a system has multiple sensors of the same type)
75  * @return index for compensation parameter entry containing matching device ID on success, <0 otherwise */
76  int set_sensor_id_gyro(uint32_t device_id, int topic_instance);
77  int set_sensor_id_accel(uint32_t device_id, int topic_instance);
78  int set_sensor_id_baro(uint32_t device_id, int topic_instance);
79 
80 
81  /**
82  * Apply Thermal corrections to gyro (& other) sensor data.
83  * @param topic_instance uORB topic instance
84  * @param sensor_data input sensor data, output sensor data with applied corrections
85  * @param temperature measured current temperature
86  * @param offsets returns offsets that were applied (length = 3, except for baro), depending on return value
87  * @param scales returns scales that were applied (length = 3), depending on return value
88  * @return -1: error: correction enabled, but no sensor mapping set (@see set_sendor_id_gyro)
89  * 0: no changes (correction not enabled),
90  * 1: corrections applied but no changes to offsets & scales,
91  * 2: corrections applied and offsets & scales updated
92  */
93  int apply_corrections_gyro(int topic_instance, matrix::Vector3f &sensor_data, float temperature, float *offsets,
94  float *scales);
95 
96  int apply_corrections_accel(int topic_instance, matrix::Vector3f &sensor_data, float temperature, float *offsets,
97  float *scales);
98 
99  int apply_corrections_baro(int topic_instance, float &sensor_data, float temperature, float *offsets, float *scales);
100 
101  /** output current configuration status to console */
102  void print_status();
103 private:
104 
105  /* Struct containing parameters used by the single axis 5th order temperature compensation algorithm
106 
107  Input:
108 
109  measured_temp : temperature measured at the sensor (deg C)
110  raw_value : reading from the sensor before compensation
111  corrected_value : reading from the sensor after compensation for errors
112 
113  Compute:
114 
115  delta_temp = measured_temp - ref_temp
116  offset = x5 * delta_temp^5 + x4 * delta_temp^4 + x3 * delta_temp^3 + x2 * delta_temp^2 + x1 * delta_temp + x0
117  corrected_value = (raw_value - offset) * scale
118 
119  */
121  int32_t ID;
122  float x5;
123  float x4;
124  float x3;
125  float x2;
126  float x1;
127  float x0;
128  float scale;
129  float ref_temp;
130  float min_temp;
131  float max_temp;
132  };
133 
146  };
147 
148 
149  /* Struct containing parameters used by the 3-axis 3rd order temperature compensation algorithm
150 
151  Input:
152 
153  measured_temp : temperature measured at the sensor (deg C)
154  raw_value[3] : XYZ readings from the sensor before compensation
155  corrected_value[3] : XYZ readings from the sensor after compensation for errors
156 
157  Compute for each measurement index:
158 
159  delta_temp = measured_temp - ref_temp
160  offset = x3 * delta_temp^3 + x2 * delta_temp^2 + x1 * delta_temp + x0
161  corrected_value = (raw_value - offset) * scale
162 
163  */
165  int32_t ID; /**< sensor device ID*/
166  float x3[3]; /**< x^3 term of polynomial */
167  float x2[3]; /**< x^2 term of polynomial */
168  float x1[3]; /**< x^1 term of polynomial */
169  float x0[3]; /**< x^0 / offset term of polynomial */
170  float scale[3]; /**< scale factor correction */
171  float ref_temp; /**< reference temperature used by the curve-fit */
172  float min_temp; /**< minimum temperature with valid compensation data */
173  float max_temp; /**< maximum temperature with valid compensation data */
174  };
175 
186  };
187 
188  // create a struct containing all thermal calibration parameters
189  struct Parameters {
190  int32_t gyro_tc_enable;
194  int32_t baro_tc_enable;
196  };
197 
198  // create a struct containing the handles required to access all calibration parameters
206  };
207 
208 
209  /**
210  * initialize ParameterHandles struct
211  * @return 0 on succes, <0 on error
212  */
213  static int initialize_parameter_handles(ParameterHandles &parameter_handles);
214 
215 
216  /**
217 
218  Calculate the offset required to compensate the sensor for temperature effects using a 5th order method
219  If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false.
220  If the measured temperature is within the calibration range, return true.
221 
222  Arguments:
223 
224  coef : reference to struct containing calibration coefficients
225  measured_temp : temperature measured at the sensor (deg C)
226  offset : reference to sensor offset
227 
228  Returns:
229 
230  Boolean true if the measured temperature is inside the valid range for the compensation
231 
232  */
233  bool calc_thermal_offsets_1D(SensorCalData1D &coef, float measured_temp, float &offset);
234 
235  /**
236 
237  Calculate the offsets required to compensate the sensor for temperature effects
238  If the measured temperature is outside the calibration range, clip the temperature to remain within the range and return false.
239  If the measured temperature is within the calibration range, return true.
240 
241  Arguments:
242 
243  coef : reference to struct containing calibration coefficients
244  measured_temp : temperature measured at the sensor (deg C)
245  offset : reference to sensor offset - array of 3
246 
247  Returns:
248 
249  Boolean true if the measured temperature is inside the valid range for the compensation
250 
251  */
252  bool calc_thermal_offsets_3D(const SensorCalData3D &coef, float measured_temp, float offset[]);
253 
254 
256 
257 
258  struct PerSensorData {
260  {
261  for (int i = 0; i < SENSOR_COUNT_MAX; ++i) { device_mapping[i] = 255; last_temperature[i] = -100.0f; }
262  }
264  {
265  for (int i = 0; i < SENSOR_COUNT_MAX; ++i) { last_temperature[i] = -100.0f; }
266  }
267  uint8_t device_mapping[SENSOR_COUNT_MAX]; /// map a topic instance to the parameters index
268  float last_temperature[SENSOR_COUNT_MAX];
269  };
273 
274 
275  template<typename T>
276  static inline int set_sensor_id(uint32_t device_id, int topic_instance, PerSensorData &sensor_data,
277  const T *sensor_cal_data, uint8_t sensor_count_max);
278 };
279 
280 }
float ref_temp
reference temperature used by the curve-fit
constexpr uint8_t GYRO_COUNT_MAX
Definition: common.h:47
int set_sensor_id_accel(uint32_t device_id, int topic_instance)
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)
static int32_t device_id[max_accel_sens]
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 meth...
Global flash based parameter store.
class TemperatureCompensation Applies temperature compensation to sensor data.
constexpr uint8_t ACCEL_COUNT_MAX
Definition: common.h:48
int parameters_update(bool hil_enabled=false)
(re)load the parameters.
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 tempe...
constexpr uint8_t SENSOR_COUNT_MAX
Definition: common.h:51
Definition: common.h:43
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 mul...
float min_temp
minimum temperature with valid compensation data
void print_status()
output current configuration status to console
int apply_corrections_baro(int topic_instance, float &sensor_data, float temperature, float *offsets, float *scales)
int apply_corrections_accel(int topic_instance, matrix::Vector3f &sensor_data, float temperature, float *offsets, float *scales)
float max_temp
maximum temperature with valid compensation data
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.
static int initialize_parameter_handles(ParameterHandles &parameter_handles)
initialize ParameterHandles struct
int set_sensor_id_baro(uint32_t device_id, int topic_instance)
constexpr uint8_t BARO_COUNT_MAX
Definition: common.h:49
uint32_t param_t
Parameter handle.
Definition: param.h:98