mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: cope with calling delay_microseconds_boost() multiple times
needed for updated IMU wait code
This commit is contained in:
parent
053f0cb689
commit
898150e460
|
@ -163,12 +163,12 @@ void Scheduler::boost_end(void)
|
|||
*/
|
||||
void Scheduler::delay_microseconds_boost(uint16_t usec)
|
||||
{
|
||||
if (in_main_thread()) {
|
||||
if (!_priority_boosted && in_main_thread()) {
|
||||
set_high_priority();
|
||||
_priority_boosted = true;
|
||||
_called_boost = true;
|
||||
}
|
||||
delay_microseconds(usec); //Suspends Thread for desired microseconds
|
||||
_called_boost = true;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue