mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: use airspeed.set_log_bit()
This commit is contained in:
parent
c056a7948d
commit
92aff3bded
@ -181,6 +181,7 @@ void AP_Periph_FW::init()
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||
if (airspeed.enabled()) {
|
||||
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit();
|
||||
airspeed.init();
|
||||
}
|
||||
#endif
|
||||
|
@ -2138,7 +2138,7 @@ void AP_Periph_FW::can_airspeed_update(void)
|
||||
return;
|
||||
}
|
||||
last_airspeed_update_ms = now;
|
||||
airspeed.update(false);
|
||||
airspeed.update();
|
||||
if (!airspeed.healthy()) {
|
||||
// don't send any data
|
||||
return;
|
||||
|
Loading…
Reference in New Issue
Block a user