mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Periph: fixed airspeed update rate
This commit is contained in:
parent
d0ff2089c4
commit
5b699fc65d
@ -1138,19 +1138,20 @@ void AP_Periph_FW::can_airspeed_update(void)
|
|||||||
{
|
{
|
||||||
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
||||||
if (!airspeed.healthy()) {
|
if (!airspeed.healthy()) {
|
||||||
static uint32_t last_probe_ms;
|
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
|
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.init();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
airspeed.update(false);
|
uint32_t now = AP_HAL::millis();
|
||||||
if (last_airspeed_update_ms == airspeed.last_update_ms()) {
|
if (now - last_airspeed_update_ms < 50) {
|
||||||
|
// max 20Hz data
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
last_airspeed_update_ms = now;
|
||||||
last_airspeed_update_ms = airspeed.last_update_ms();
|
airspeed.update(false);
|
||||||
if (!airspeed.healthy()) {
|
if (!airspeed.healthy()) {
|
||||||
// don't send any data
|
// don't send any data
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user