mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: don't use timer_event() that is static from the _scheduler instance
This commit is contained in:
parent
0d3b1d90b0
commit
c91c570814
@ -171,7 +171,7 @@ void SITL_State::_fdm_input_step(void)
|
||||
|
||||
if (_update_count == 0 && _sitl != nullptr) {
|
||||
_update_gps(0, 0, 0, 0, 0, 0, 0, false);
|
||||
_scheduler->timer_event();
|
||||
HALSITL::Scheduler::timer_event();
|
||||
_scheduler->sitl_end_atomic();
|
||||
return;
|
||||
}
|
||||
@ -195,7 +195,7 @@ void SITL_State::_fdm_input_step(void)
|
||||
}
|
||||
|
||||
// trigger all APM timers.
|
||||
_scheduler->timer_event();
|
||||
HALSITL::Scheduler::timer_event();
|
||||
_scheduler->sitl_end_atomic();
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user