From e8802d1858fe1a982450b77fa697023d613dfb01 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 9 Oct 2022 17:30:58 +0100 Subject: [PATCH] AP_Airspeed: remove old param conversion --- libraries/AP_Airspeed/AP_Airspeed.cpp | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index b5d8491e0b..7369906ea6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -230,25 +230,6 @@ void AP_Airspeed::init() return; } -#ifndef HAL_BUILD_AP_PERIPH - // cope with upgrade from old system - if (param[0].pin.load() && param[0].pin.get() != 65) { - param[0].type.set_default(TYPE_ANALOG); - } - - // Switch to dedicated WIND_MAX param - // PARAMETER_CONVERSION - Added: Oct-2020 - const float ahrs_max_wind = AP::ahrs().get_max_wind(); - if (!_wind_max.configured() && is_positive(ahrs_max_wind)) { - _wind_max.set_and_save(ahrs_max_wind); - - // Turn off _options to override the new default - if (!_options.configured()) { - _options.set_and_save(0); - } - } -#endif - #ifdef HAL_AIRSPEED_PROBE_LIST // load sensors via a list from hwdef.dat HAL_AIRSPEED_PROBE_LIST;