From 19cd2a8fe6362243bb3f0e4a8f9a9d6417e356d1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 23 Mar 2023 08:19:22 +1100 Subject: [PATCH] AP_Airspeed: fixed airspeed peripherals AP_Periph does not have the ARSPD_BUS parameter, and setting this default sets the bus to one that doesn't exist, plus it can't be fixed using user parameters --- libraries/AP_Airspeed/AP_Airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 3256b4f227..715a5261ca 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -188,8 +188,8 @@ AP_Airspeed::AP_Airspeed() // Setup defaults that only apply to first sensor param[0].type.set_default(ARSPD_DEFAULT_TYPE); - param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT); #ifndef HAL_BUILD_AP_PERIPH + param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT); param[0].pin.set_default(ARSPD_DEFAULT_PIN); #endif