123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235 |
- #include "AP_TempCalibration.h"
- #include <stdio.h>
- #include <AP_Baro/AP_Baro.h>
- extern const AP_HAL::HAL& hal;
- #define TCAL_DEBUG 0
- #if TCAL_DEBUG
- # define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
- #else
- # define debug(fmt, args ...)
- #endif
- const AP_Param::GroupInfo AP_TempCalibration::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS("_ENABLED", 1, AP_TempCalibration, enabled, TC_DISABLED, AP_PARAM_FLAG_ENABLE),
-
-
-
-
-
-
-
- AP_GROUPINFO("_TEMP_MIN", 2, AP_TempCalibration, temp_min, 0),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("_TEMP_MAX", 4, AP_TempCalibration, temp_max, 0),
-
-
-
-
-
-
- AP_GROUPINFO("_BARO_EXP", 5, AP_TempCalibration, baro_exponent, 0),
-
- AP_GROUPEND
- };
- float AP_TempCalibration::calculate_correction(float temp, float exponent) const
- {
- return powf(MAX(temp - Tzero, 0), exponent);
- }
- void AP_TempCalibration::setup_learning(void)
- {
- learn_temp_start = AP::baro().get_temperature();
- learn_temp_step = 0.25;
- learn_count = 200;
- learn_i = 0;
- if (learn_values != nullptr) {
- delete [] learn_values;
- }
- learn_values = new float[learn_count];
- if (learn_values == nullptr) {
- return;
- }
- }
- float AP_TempCalibration::calculate_p_range(float baro_factor) const
- {
- float sum = 0;
- float P0 = learn_values[0] + calculate_correction(learn_temp_start, baro_factor);
- for (uint16_t i=0; i<learn_i; i++) {
- if (is_zero(learn_values[i])) {
-
- continue;
- }
- float temp = learn_temp_start + learn_temp_step*i;
- float correction = calculate_correction(temp, baro_factor);
- float P = learn_values[i] + correction;
- sum += sq(P - P0);
- }
- return sum / learn_i;
- }
- void AP_TempCalibration::calculate_calibration(void)
- {
- float current_err = calculate_p_range(baro_exponent);
- float test_exponent = baro_exponent + learn_delta;
- float test_err = calculate_p_range(test_exponent);
- if (test_err >= current_err) {
- test_exponent = baro_exponent - learn_delta;
- test_err = calculate_p_range(test_exponent);
- }
- if (test_exponent <= exp_limit_max &&
- test_exponent >= exp_limit_min &&
- test_err < current_err) {
-
- debug("CAL: %.2f\n", test_exponent);
- if (!is_equal(test_exponent, baro_exponent.get())) {
- baro_exponent.set_and_save(test_exponent);
- }
- temp_min.set_and_save_ifchanged(learn_temp_start);
- temp_max.set_and_save_ifchanged(learn_temp_start + learn_i*learn_temp_step);
- }
- }
- void AP_TempCalibration::learn_calibration(void)
- {
-
- const AP_Baro &baro = AP::baro();
- if (!baro.healthy(0) ||
- hal.util->get_soft_armed() ||
- baro.get_temperature(0) < Tzero) {
- return;
- }
-
- if (learn_values == nullptr ||
- !AP::ins().is_still()) {
- debug("learn reset\n");
- setup_learning();
- if (learn_values == nullptr) {
- return;
- }
- }
- float temp = baro.get_temperature(0);
- float P = baro.get_pressure(0);
- uint16_t idx = (temp - learn_temp_start) / learn_temp_step;
- if (idx >= learn_count) {
-
- return;
- }
- if (is_zero(learn_values[idx])) {
- learn_values[idx] = P;
- debug("learning %u %.2f at %.2f\n", idx, learn_values[idx], temp);
- } else {
-
- learn_values[idx] = 0.9 * learn_values[idx] + 0.1 * P;
- }
- learn_i = MAX(learn_i, idx);
-
- uint32_t now = AP_HAL::millis();
- if (now - last_learn_ms > 100 &&
- idx*learn_temp_step > min_learn_temp_range &&
- temp - learn_temp_start > temp_max - temp_min) {
- last_learn_ms = now;
-
- calculate_calibration();
- }
- }
- void AP_TempCalibration::apply_calibration(void)
- {
- AP_Baro &baro = AP::baro();
-
- if (!baro.healthy(0)) {
- return;
- }
- float temp = baro.get_temperature(0);
- float correction = calculate_correction(temp, baro_exponent);
- baro.set_pressure_correction(0, correction);
- }
- void AP_TempCalibration::update(void)
- {
- switch (enabled.get()) {
- case TC_DISABLED:
- break;
- case TC_ENABLE_LEARN:
- learn_calibration();
- FALLTHROUGH;
- case TC_ENABLE_USE:
- apply_calibration();
- break;
- }
- }
|