mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: always call airspeed init to allow param conversion
This commit is contained in:
parent
e4f3720e9b
commit
cb6891821e
@ -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
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user