Browse Source

AP_HAL: added in_expected_delay()

allows for error message suppression when delays are expected
copter407
Andrew Tridgell 5 years ago
parent
commit
aafc5be1c2
  1. 8
      libraries/AP_HAL/Scheduler.h

8
libraries/AP_HAL/Scheduler.h

@ -36,7 +36,13 @@ public: @@ -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()
*/

Loading…
Cancel
Save