From 689595080a5df3fc111eeee69e9f86290134bbc7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Jun 2016 10:52:59 +1000 Subject: [PATCH] AP_Airspeed: ensure we have at least 10 samples for airspeed cal thanks to Michael for pointing out this issue --- libraries/AP_Airspeed/AP_Airspeed.cpp | 10 +++++++++- libraries/AP_Airspeed/AP_Airspeed.h | 1 + 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 2e0b21e883..949c9db66a 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -186,11 +186,18 @@ void AP_Airspeed::calibrate(bool in_startup) _cal.start_ms = AP_HAL::millis(); _cal.count = 0; _cal.sum = 0; + _cal.read_count = 0; } +/* + update async airspeed calibration +*/ void AP_Airspeed::update_calibration(float raw_pressure) { - if (AP_HAL::millis() - _cal.start_ms >= 1000) { + // consider calibration complete when we have at least 10 samples + // over at least 1 second + if (AP_HAL::millis() - _cal.start_ms >= 1000 && + _cal.read_count > 10) { if (_cal.count == 0) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Airspeed sensor unhealthy"); } else { @@ -204,6 +211,7 @@ void AP_Airspeed::update_calibration(float raw_pressure) _cal.sum += raw_pressure; _cal.count++; } + _cal.read_count++; } // read the airspeed sensor diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index c26893b711..da3c4a2172 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -176,6 +176,7 @@ private: uint32_t start_ms; uint16_t count; float sum; + uint16_t read_count; } _cal; Airspeed_Calibration _calibration;