mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_HAL_SITL: Periph: stop running SITL updates off main thread
the same code present in the normal HAL-SITL scheduler was not copied across when this method was created. Without it, if a non-main thread called delay we will attempt to do things like update the sitl_model (ie. SIM_Aircraft) object. We have no protections in place (nor should we have) for this happening when the main thread is in the middle of doing the SITL updates, so corruption is definitely going to happen at some stage!
This commit is contained in:
parent
fa04004a02
commit
d015618e70
@ -123,10 +123,15 @@ void SITL_State::init(int argc, char * const argv[]) {
|
||||
void SITL_State::wait_clock(uint64_t wait_time_usec)
|
||||
{
|
||||
while (AP_HAL::micros64() < wait_time_usec) {
|
||||
struct sitl_input input {};
|
||||
sitl_model->update(input); // delays up to 1 millisecond
|
||||
sim_update();
|
||||
update_voltage_current(input, 0);
|
||||
if (hal.scheduler->in_main_thread() ||
|
||||
Scheduler::from(hal.scheduler)->semaphore_wait_hack_required()) {
|
||||
struct sitl_input input {};
|
||||
sitl_model->update(input); // delays up to 1 millisecond
|
||||
sim_update();
|
||||
update_voltage_current(input, 0);
|
||||
} else {
|
||||
usleep(1000);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user