mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL: added in_expected_delay()
allows for error message suppression when delays are expected
This commit is contained in:
parent
06b62107c7
commit
58b4b523fd
@ -37,6 +37,12 @@ public:
|
||||
*/
|
||||
virtual void expect_delay_ms(uint32_t ms) { }
|
||||
|
||||
/*
|
||||
return true if we are in a period of expected delay. This can be
|
||||
used to suppress error messages
|
||||
*/
|
||||
virtual bool in_expected_delay(void) const { return false; }
|
||||
|
||||
/*
|
||||
end the priority boost from delay_microseconds_boost()
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user