|
|
|
@ -321,13 +321,25 @@ void Scheduler::_timer_thread(void *arg)
@@ -321,13 +321,25 @@ void Scheduler::_timer_thread(void *arg)
|
|
|
|
|
// process any pending RC output requests
|
|
|
|
|
hal.rcout->timer_tick(); |
|
|
|
|
|
|
|
|
|
if (sched->expect_delay_start != 0) { |
|
|
|
|
uint32_t now = AP_HAL::millis(); |
|
|
|
|
if (now - sched->expect_delay_start <= sched->expect_delay_length) { |
|
|
|
|
sched->watchdog_pat(); |
|
|
|
|
} |
|
|
|
|
if (sched->in_expected_delay()) { |
|
|
|
|
sched->watchdog_pat(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
return true if we are in a period of expected delay. This can be |
|
|
|
|
used to suppress error messages |
|
|
|
|
*/ |
|
|
|
|
bool Scheduler::in_expected_delay(void) const |
|
|
|
|
{ |
|
|
|
|
if (expect_delay_start != 0) { |
|
|
|
|
uint32_t now = AP_HAL::millis(); |
|
|
|
|
if (now - expect_delay_start <= expect_delay_length) { |
|
|
|
|
return true; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#ifndef HAL_NO_MONITOR_THREAD |
|
|
|
|