mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
HAL_ChibiOS: end scheduler boost on expected delay
we want timer thread to be higher priority than main thread while in a long operation
This commit is contained in:
parent
9f26ae5e8c
commit
59669209fe
@ -498,6 +498,9 @@ void Scheduler::expect_delay_ms(uint32_t ms)
|
|||||||
} else {
|
} else {
|
||||||
expect_delay_start = AP_HAL::millis();
|
expect_delay_start = AP_HAL::millis();
|
||||||
expect_delay_length = ms;
|
expect_delay_length = ms;
|
||||||
|
|
||||||
|
// also put our priority below timer thread if we are boosted
|
||||||
|
boost_end();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user