From cb6891821ed1deb8efb8d0a373d308ff29058045 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 30 Dec 2022 19:40:03 +0000 Subject: [PATCH] AP_Periph: always call airspeed init to allow param conversion --- Tools/AP_Periph/AP_Periph.cpp | 20 +++++++++----------- Tools/AP_Periph/can.cpp | 2 +- 2 files changed, 10 insertions(+), 12 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 434eaa7d7d..7a2e64e57d 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -183,23 +183,21 @@ void AP_Periph_FW::init() #endif #ifdef HAL_PERIPH_ENABLE_AIRSPEED - if (airspeed.enabled()){ #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01); - if (pins_enabled) { - ChibiOS::I2CBus::set_bus_to_floating(0); + const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01); + if (pins_enabled) { + ChibiOS::I2CBus::set_bus_to_floating(0); #ifdef HAL_GPIO_PIN_LED_CAN_I2C - palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1); + palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1); #endif - } else { - // Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here - airspeed.init(); - } -#else + } else { // Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here airspeed.init(); -#endif } +#else + // Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here + airspeed.init(); +#endif #endif diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 6bb4a0f981..934cf2d598 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -2223,7 +2223,7 @@ void AP_Periph_FW::can_airspeed_update(void) static uint32_t last_probe_ms; if (now - last_probe_ms >= 1000) { last_probe_ms = now; - airspeed.init(); + airspeed.allocate(); } } #endif