APM:Libraries
AP_TempCalibration.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  temperature calibration library
17  */
18 
19 #include "AP_TempCalibration.h"
20 #include <stdio.h>
21 
22 extern const AP_HAL::HAL& hal;
23 
24 #define TCAL_DEBUG 0
25 
26 #if TCAL_DEBUG
27 # define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
28 #else
29 # define debug(fmt, args ...)
30 #endif
31 
32 // table of user settable and learned parameters
34 
35  // @Param: ENABLED
36  // @DisplayName: Temperature calibration enable
37  // @Description: Enable temperature calibration. Set to 0 to disable. Set to 1 to use learned values. Set to 2 to learn new values and use the values
38  // @Values: 0:Disabled,1:Enabled,2:EnableAndLearn
39  // @User: Advanced
40  AP_GROUPINFO_FLAGS("_ENABLED", 1, AP_TempCalibration, enabled, TC_DISABLED, AP_PARAM_FLAG_ENABLE),
41 
42  // @Param: TEMP_MIN
43  // @DisplayName: Min learned temperature
44  // @Description: Minimum learned temperature. This is automatically set by the learning process
45  // @Units: degC
46  // @ReadOnly: True
47  // @Volatile: True
48  // @User: Advanced
49  AP_GROUPINFO("_TEMP_MIN", 2, AP_TempCalibration, temp_min, 0),
50 
51  // @Param: TEMP_MIN
52  // @DisplayName: Min learned temperature
53  // @Description: Minimum learned temperature. This is automatically set by the learning process
54  // @Units: degC
55  // @ReadOnly: True
56  // @Volatile: True
57  // @User: Advanced
58  AP_GROUPINFO("_TEMP_MIN", 3, AP_TempCalibration, temp_min, 0),
59 
60  // @Param: TEMP_MAX
61  // @DisplayName: Max learned temperature
62  // @Description: Maximum learned temperature. This is automatically set by the learning process
63  // @Units: degC
64  // @ReadOnly: True
65  // @Volatile: True
66  // @User: Advanced
67  AP_GROUPINFO("_TEMP_MAX", 4, AP_TempCalibration, temp_max, 0),
68 
69  // @Param: BARO_EXP
70  // @DisplayName: Barometer exponent
71  // @Description: Learned exponent for barometer temperature correction
72  // @ReadOnly: True
73  // @Volatile: True
74  // @User: Advanced
75  AP_GROUPINFO("_BARO_EXP", 5, AP_TempCalibration, baro_exponent, 0),
76 
78 };
79 
80 /*
81  calculate the correction given an exponent and a temperature
82 
83  This one parameter correction is deliberately chosen to be very
84  robust for extrapolation. It fits the characteristics of the
85  ICM-20789 barometer nicely.
86  */
87 float AP_TempCalibration::calculate_correction(float temp, float exponent) const
88 {
89  return powf(MAX(temp - Tzero, 0), exponent);
90 }
91 
92 
93 /*
94  setup for learning
95  */
97 {
99  learn_temp_step = 0.25;
100  learn_count = 200;
101  learn_i = 0;
102  if (learn_values != nullptr) {
103  delete [] learn_values;
104  }
105  learn_values = new float[learn_count];
106  if (learn_values == nullptr) {
107  return;
108  }
109 }
110 
111 /*
112  calculate the sum of squares range of pressure values we get with
113  the current data. This is the function we try to minimise in the
114  calibration
115  */
116 float AP_TempCalibration::calculate_p_range(float baro_factor) const
117 {
118  float sum = 0;
119  float P0 = learn_values[0] + calculate_correction(learn_temp_start, baro_factor);
120  for (uint16_t i=0; i<learn_i; i++) {
121  if (is_zero(learn_values[i])) {
122  // gap in the data
123  continue;
124  }
125  float temp = learn_temp_start + learn_temp_step*i;
126  float correction = calculate_correction(temp, baro_factor);
127  float P = learn_values[i] + correction;
128  sum += sq(P - P0);
129  }
130  return sum / learn_i;
131 }
132 
133 /*
134  calculate a calibration value
135 
136  This fits a simple single value power function to the baro data to
137  find the calibration exponent.
138  */
140 {
141  float current_err = calculate_p_range(baro_exponent);
142  float test_exponent = baro_exponent + learn_delta;
143  float test_err = calculate_p_range(test_exponent);
144  if (test_err >= current_err) {
145  test_exponent = baro_exponent - learn_delta;
146  test_err = calculate_p_range(test_exponent);
147  }
148  if (test_exponent <= exp_limit_max &&
149  test_exponent >= exp_limit_min &&
150  test_err < current_err) {
151  // move to new value
152  debug("CAL: %.2f\n", test_exponent);
153  if (!is_equal(test_exponent, baro_exponent.get())) {
154  baro_exponent.set_and_save(test_exponent);
155  }
156  temp_min.set_and_save_ifchanged(learn_temp_start);
157  temp_max.set_and_save_ifchanged(learn_temp_start + learn_i*learn_temp_step);
158  }
159 }
160 
161 /*
162  update calibration learning
163  */
165 {
166  // just for first baro now
167  const AP_Baro &baro = AP::baro();
168  if (!baro.healthy(0) ||
169  hal.util->get_soft_armed() ||
170  baro.get_temperature(0) < Tzero) {
171  return;
172  }
173 
174  // if we have any movement then we reset learning
175  if (learn_values == nullptr ||
176  !AP::ins().is_still()) {
177  debug("learn reset\n");
178  setup_learning();
179  if (learn_values == nullptr) {
180  return;
181  }
182  }
183  float temp = baro.get_temperature(0);
184  float P = baro.get_pressure(0);
185  uint16_t idx = (temp - learn_temp_start) / learn_temp_step;
186  if (idx >= learn_count) {
187  // could change learn_temp_step here
188  return;
189  }
190  if (is_zero(learn_values[idx])) {
191  learn_values[idx] = P;
192  debug("learning %u %.2f at %.2f\n", idx, learn_values[idx], temp);
193  } else {
194  // filter in new value
195  learn_values[idx] = 0.9 * learn_values[idx] + 0.1 * P;
196  }
197  learn_i = MAX(learn_i, idx);
198 
199  uint32_t now = AP_HAL::millis();
200  if (now - last_learn_ms > 100 &&
202  temp - learn_temp_start > temp_max - temp_min) {
203  last_learn_ms = now;
204  // run estimation and update parameters
206  }
207 }
208 
209 /*
210  apply learned calibration for current temperature
211  */
213 {
214  AP_Baro &baro = AP::baro();
215  // just for first baro now
216  if (!baro.healthy(0)) {
217  return;
218  }
219  float temp = baro.get_temperature(0);
220  float correction = calculate_correction(temp, baro_exponent);
221  baro.set_pressure_correction(0, correction);
222 }
223 
224 /*
225  called at 10Hz from the main thread. This is called both when armed
226  and disarmed. It only does learning while disarmed, but needs to
227  supply the corrections to the sensor libraries at all times
228  */
230 {
231  switch (enabled.get()) {
232  case TC_DISABLED:
233  break;
234  case TC_ENABLE_LEARN:
236  FALLTHROUGH;
237  case TC_ENABLE_USE:
239  break;
240  }
241 }
const float min_learn_temp_range
bool get_soft_armed() const
Definition: Util.h:15
#define AP_PARAM_FLAG_ENABLE
Definition: AP_Param.h:56
#define FALLTHROUGH
Definition: AP_Common.h:50
float get_temperature(void) const
Definition: AP_Baro.h:63
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
#define debug(fmt, args ...)
void set_pressure_correction(uint8_t instance, float p_correction)
Definition: AP_Baro.cpp:728
AP_HAL::Util * util
Definition: HAL.h:115
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define AP_GROUPINFO_FLAGS(name, idx, clazz, element, def, flags)
Definition: AP_Param.h:93
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
static AP_Baro baro
Definition: ModuleTest.cpp:18
uint32_t millis()
Definition: system.cpp:157
bool healthy(void) const
Definition: AP_Baro.h:52
float get_pressure(void) const
Definition: AP_Baro.h:59
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static const struct AP_Param::GroupInfo var_info[]
float calculate_p_range(float baro_factor) const
float calculate_correction(float temp, float exponent) const
float sq(const T val)
Definition: AP_Math.h:170
AP_InertialSensor & ins()
AP_Baro & baro()
Definition: AP_Baro.cpp:737
#define AP_GROUPEND
Definition: AP_Param.h:121