mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX
This commit is contained in:
parent
c8813677b3
commit
06401fdcbf
|
@ -562,7 +562,7 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)
|
|||
// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind
|
||||
if (fixed_wing_parameters != nullptr) {
|
||||
float airspeed_min = fixed_wing_parameters->airspeed_min.get();
|
||||
// use percentage of ARSPD_FBW_MIN as criteria for max allowed change in offset
|
||||
// use percentage of AIRSPEED_MIN as criteria for max allowed change in offset
|
||||
float max_change = 0.5*(sq((1 + (max_speed_pcnt * 0.01))*airspeed_min) - sq(airspeed_min));
|
||||
if (max_speed_pcnt > 0 && (abs(calibrated_offset-param[i].offset) > max_change) && (abs(param[i].offset) > 0)) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Arspd %d offset change large;cover and recal", i +1);
|
||||
|
|
Loading…
Reference in New Issue