From ce3fb290f106dc2bfc400bfcde1c75892afc11f9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 28 Aug 2013 22:35:07 +1000 Subject: [PATCH] AP_Airspeed: fixed initialisation of auto-calibration --- libraries/AP_Airspeed/AP_Airspeed.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index c7366e9995..65c4331320 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -90,6 +90,10 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = { void AP_Airspeed::init() { _last_pressure = 0; + _calibration.init(_ratio); + _last_saved_ratio = _ratio; + _counter = 0; + #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 if (_pin == 65) { _ets_fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); @@ -112,10 +116,6 @@ void AP_Airspeed::init() } #endif _source = hal.analogin->channel(_pin); - - _calibration.init(_ratio); - _last_saved_ratio = _ratio; - _counter = 0; } // read the airspeed sensor