mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added boost_end() method to Scheduler API
this allows for a better method of controlling main thread priority
This commit is contained in:
parent
0355b1a340
commit
84a4f9dc96
|
@ -29,6 +29,11 @@ public:
|
||||||
*/
|
*/
|
||||||
virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
|
virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
|
||||||
|
|
||||||
|
/*
|
||||||
|
end the priority boost from delay_microseconds_boost()
|
||||||
|
*/
|
||||||
|
virtual void boost_end(void) {}
|
||||||
|
|
||||||
virtual void register_delay_callback(AP_HAL::Proc,
|
virtual void register_delay_callback(AP_HAL::Proc,
|
||||||
uint16_t min_time_ms) = 0;
|
uint16_t min_time_ms) = 0;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue