mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: implement in_expected_delay()
This commit is contained in:
parent
1f0465c7c8
commit
ab9330f04f
|
@ -321,15 +321,27 @@ 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
|
||||
void Scheduler::_monitor_thread(void *arg)
|
||||
{
|
||||
|
|
|
@ -105,6 +105,12 @@ public:
|
|||
*/
|
||||
void expect_delay_ms(uint32_t ms) override;
|
||||
|
||||
/*
|
||||
return true if we are in a period of expected delay. This can be
|
||||
used to suppress error messages
|
||||
*/
|
||||
bool in_expected_delay(void) const override;
|
||||
|
||||
/*
|
||||
disable interrupts and return a context that can be used to
|
||||
restore the interrupt state. This can be used to protect
|
||||
|
|
Loading…
Reference in New Issue