mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Periph: always call airspeed init to allow param conversion
This commit is contained in:
parent
e4f3720e9b
commit
cb6891821e
@ -183,7 +183,6 @@ void AP_Periph_FW::init()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||||
if (airspeed.enabled()){
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
|
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
|
||||||
if (pins_enabled) {
|
if (pins_enabled) {
|
||||||
@ -199,7 +198,6 @@ void AP_Periph_FW::init()
|
|||||||
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
|
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
|
||||||
airspeed.init();
|
airspeed.init();
|
||||||
#endif
|
#endif
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2223,7 +2223,7 @@ void AP_Periph_FW::can_airspeed_update(void)
|
|||||||
static uint32_t last_probe_ms;
|
static uint32_t last_probe_ms;
|
||||||
if (now - last_probe_ms >= 1000) {
|
if (now - last_probe_ms >= 1000) {
|
||||||
last_probe_ms = now;
|
last_probe_ms = now;
|
||||||
airspeed.init();
|
airspeed.allocate();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user