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
This commit is contained in:
Andrew Tridgell 2023-03-23 08:19:22 +11:00
parent 4ec74b1373
commit 19cd2a8fe6
1 changed files with 1 additions and 1 deletions

View File

@ -188,8 +188,8 @@ AP_Airspeed::AP_Airspeed()
// Setup defaults that only apply to first sensor // Setup defaults that only apply to first sensor
param[0].type.set_default(ARSPD_DEFAULT_TYPE); param[0].type.set_default(ARSPD_DEFAULT_TYPE);
param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT);
#ifndef HAL_BUILD_AP_PERIPH #ifndef HAL_BUILD_AP_PERIPH
param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT);
param[0].pin.set_default(ARSPD_DEFAULT_PIN); param[0].pin.set_default(ARSPD_DEFAULT_PIN);
#endif #endif