AP_TempCalibration.h 2.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  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. 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. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. /*
  15. temperature calibration library. This monitors temperature changes
  16. and opportunistically calibrates sensors when the vehicle is still
  17. */
  18. #include <AP_HAL/AP_HAL.h>
  19. #include <AP_Param/AP_Param.h>
  20. #include <AP_InertialSensor/AP_InertialSensor.h>
  21. class AP_TempCalibration
  22. {
  23. public:
  24. // constructor. This remains because construction of Copter's g2
  25. // object becomes problematic if we don't have at least one object
  26. // to initialise
  27. AP_TempCalibration() {}
  28. // settable parameters
  29. static const struct AP_Param::GroupInfo var_info[];
  30. void update(void);
  31. /* Do not allow copies */
  32. AP_TempCalibration(const AP_TempCalibration &other) = delete;
  33. AP_TempCalibration &operator=(const AP_TempCalibration&) = delete;
  34. enum {
  35. TC_DISABLED = 0,
  36. TC_ENABLE_USE = 1,
  37. TC_ENABLE_LEARN = 2,
  38. };
  39. private:
  40. AP_Int8 enabled;
  41. AP_Int8 temp_min;
  42. AP_Int8 temp_max;
  43. AP_Float baro_exponent;
  44. Vector3f last_accels;
  45. float learn_temp_start;
  46. float learn_temp_step;
  47. uint16_t learn_count;
  48. uint16_t learn_i;
  49. float *learn_values;
  50. uint32_t last_learn_ms;
  51. // temperature at which baro correction starts
  52. const float Tzero = 25;
  53. const float exp_limit_max = 2;
  54. const float exp_limit_min = 0;
  55. float learn_delta = 0.01f;
  56. // require observation of at least 5 degrees of temp range to
  57. // start learning
  58. const float min_learn_temp_range = 7;
  59. void setup_learning(void);
  60. void learn_calibration(void);
  61. void apply_calibration(void);
  62. void calculate_calibration();
  63. float calculate_correction(float temp, float exponent) const;
  64. float calculate_p_range(float baro_factor) const;
  65. };