Browse Source

气压计温度校准测试,还原

celiu-4.0.17-rc8
zbr 4 years ago
parent
commit
79f8615601
  1. 18
      libraries/AP_TempCalibration/AP_TempCalibration.cpp
  2. 5
      libraries/AP_TempCalibration/AP_TempCalibration.h

18
libraries/AP_TempCalibration/AP_TempCalibration.cpp

@ -19,7 +19,6 @@ @@ -19,7 +19,6 @@
#include "AP_TempCalibration.h"
#include <stdio.h>
#include <AP_Baro/AP_Baro.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
@ -136,7 +135,6 @@ void AP_TempCalibration::calculate_calibration(void) @@ -136,7 +135,6 @@ 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);
static float last_err = 0;
if (test_err >= current_err) {
test_exponent = baro_exponent - learn_delta;
test_err = calculate_p_range(test_exponent);
@ -151,12 +149,6 @@ void AP_TempCalibration::calculate_calibration(void) @@ -151,12 +149,6 @@ void AP_TempCalibration::calculate_calibration(void)
}
temp_min.set_and_save_ifchanged(learn_temp_start);
temp_max.set_and_save_ifchanged(learn_temp_start + learn_i*learn_temp_step);
gcs().send_text(MAV_SEVERITY_INFO, "---CAL: %.2f, %.2f\n", test_exponent,baro_exponent);
}
if(fabs(last_err - current_err) > 0.01){
gcs().send_text(MAV_SEVERITY_INFO, "CAL: %.2f, %.2f,%d, %d,%.2f,%.2f\n", test_exponent,baro_exponent,temp_min,temp_max,current_err,test_err);
last_err = current_err;
}
}
@ -184,15 +176,7 @@ void AP_TempCalibration::learn_calibration(void) @@ -184,15 +176,7 @@ void AP_TempCalibration::learn_calibration(void)
}
float temp = baro.get_temperature(0);
float P = baro.get_pressure(0);
static float last_temp;
static uint16_t last_idx;
uint16_t idx = (temp - learn_temp_start) / learn_temp_step;
// gcs().send_text(MAV_SEVERITY_INFO, "learning %u %.2f at %.2f", idx, learn_values[idx], temp);
if((last_idx != idx || fabs(last_temp - temp)> 1.0) && !is_zero(learn_values[idx]) ){
gcs().send_text(MAV_SEVERITY_INFO, "learning, %u, %.2f, at, %.2f", idx, learn_values[idx], temp);
last_idx = idx;
last_temp = temp;
}
if (idx >= learn_count) {
// could change learn_temp_step here
return;
@ -207,7 +191,7 @@ void AP_TempCalibration::learn_calibration(void) @@ -207,7 +191,7 @@ void AP_TempCalibration::learn_calibration(void)
learn_i = MAX(learn_i, idx);
uint32_t now = AP_HAL::millis();
if (now - last_learn_ms > 500 &&
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;

5
libraries/AP_TempCalibration/AP_TempCalibration.h

@ -62,7 +62,7 @@ private: @@ -62,7 +62,7 @@ private:
uint32_t last_learn_ms;
// temperature at which baro correction starts
const float Tzero = 0;
const float Tzero = 25;
const float exp_limit_max = 2;
const float exp_limit_min = 0;
@ -70,8 +70,7 @@ private: @@ -70,8 +70,7 @@ private:
// require observation of at least 5 degrees of temp range to
// start learning
// const float min_learn_temp_range = 7;
const float min_learn_temp_range = 1;
const float min_learn_temp_range = 7;
void setup_learning(void);
void learn_calibration(void);

Loading…
Cancel
Save