AP_HAL: added expect_delay_ms() to Scheduler

used to notify scheduler of long expected delay in main thread
This commit is contained in:
Andrew Tridgell 2019-04-11 21:11:10 +10:00
parent 8100c71a96
commit 88352b73bb
1 changed files with 8 additions and 0 deletions

View File

@ -29,6 +29,14 @@ public:
*/
virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
/*
inform the scheduler that we are calling an operation from the
main thread that may take an extended amount of time. This can
be used to prevent watchdog reset during expected long delays
A value of zero cancels the previous expected delay
*/
virtual void expect_delay_ms(uint32_t ms) { }
/*
end the priority boost from delay_microseconds_boost()
*/