mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_ChibiOS: during setup() we expect delays
this may fix occasional internal errors on SPI during startup
This commit is contained in:
parent
ebc6272865
commit
2200dfefdb
@ -333,6 +333,10 @@ void Scheduler::_timer_thread(void *arg)
|
|||||||
*/
|
*/
|
||||||
bool Scheduler::in_expected_delay(void) const
|
bool Scheduler::in_expected_delay(void) const
|
||||||
{
|
{
|
||||||
|
if (!_initialized) {
|
||||||
|
// until setup() is complete we expect delays
|
||||||
|
return true;
|
||||||
|
}
|
||||||
if (expect_delay_start != 0) {
|
if (expect_delay_start != 0) {
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
if (now - expect_delay_start <= expect_delay_length) {
|
if (now - expect_delay_start <= expect_delay_length) {
|
||||||
|
Loading…
Reference in New Issue
Block a user