mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: reduce Rx latency by reading while sitting in delay
This commit is contained in:
parent
e9faab288c
commit
bb65ab83be
@ -395,7 +395,7 @@ void AP_Periph_FW::update()
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
can_update();
|
can_update();
|
||||||
hal.scheduler->delay(1);
|
|
||||||
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
||||||
update_rainbow();
|
update_rainbow();
|
||||||
#endif
|
#endif
|
||||||
|
@ -1552,8 +1552,12 @@ void AP_Periph_FW::can_update()
|
|||||||
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
||||||
rcout_update();
|
rcout_update();
|
||||||
#endif
|
#endif
|
||||||
processTx();
|
const uint32_t now_us = AP_HAL::micros();
|
||||||
processRx();
|
while ((AP_HAL::micros() - now_us) < 1000) {
|
||||||
|
hal.scheduler->delay_microseconds(64);
|
||||||
|
processTx();
|
||||||
|
processRx();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user