AP_HAL: added in_expected_delay()

allows for error message suppression when delays are expected
This commit is contained in:
Andrew Tridgell 2020-03-11 12:20:04 +11:00
parent 92c7c32853
commit 1f0465c7c8

View File

@ -36,7 +36,13 @@ public:
A value of zero cancels the previous expected delay
*/
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()
*/