APM:Libraries
AP_TempCalibration.h
Go to the documentation of this file.
1 #pragma once
2 /*
3  This program is free software: you can redistribute it and/or modify
4  it under the terms of the GNU General Public License as published by
5  the Free Software Foundation, either version 3 of the License, or
6  (at your option) any later version.
7 
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12 
13  You should have received a copy of the GNU General Public License
14  along with this program. If not, see <http://www.gnu.org/licenses/>.
15  */
16 /*
17  temperature calibration library. This monitors temperature changes
18  and opportunistically calibrates sensors when the vehicle is still
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Param/AP_Param.h>
23 #include <AP_Baro/AP_Baro.h>
25 
27 {
28 public:
29  // constructor. This remains because construction of Copter's g2
30  // object becomes problematic if we don't have at least one object
31  // to initialise
33 
34  // settable parameters
35  static const struct AP_Param::GroupInfo var_info[];
36 
37  void update(void);
38 
39  /* Do not allow copies */
40  AP_TempCalibration(const AP_TempCalibration &other) = delete;
42 
43  enum {
47  };
48 
49 private:
50 
51  AP_Int8 enabled;
52  AP_Int8 temp_min;
53  AP_Int8 temp_max;
54  AP_Float baro_exponent;
55 
57 
60  uint16_t learn_count;
61  uint16_t learn_i;
62  float *learn_values;
63  uint32_t last_learn_ms;
64 
65  // temperature at which baro correction starts
66  const float Tzero = 25;
67 
68  const float exp_limit_max = 2;
69  const float exp_limit_min = 0;
70  float learn_delta = 0.01;
71 
72  // require observation of at least 5 degrees of temp range to
73  // start learning
74  const float min_learn_temp_range = 7;
75 
76  void setup_learning(void);
77  void learn_calibration(void);
78  void apply_calibration(void);
79  void calculate_calibration();
80  float calculate_correction(float temp, float exponent) const;
81  float calculate_p_range(float baro_factor) const;
82 
83 };
const float min_learn_temp_range
A system for managing and storing variables that are of general interest to the system.
AP_TempCalibration & operator=(const AP_TempCalibration &)=delete
static const struct AP_Param::GroupInfo var_info[]
float calculate_p_range(float baro_factor) const
float calculate_correction(float temp, float exponent) const