mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Scheduler: update simulation state on embedded
This commit is contained in:
parent
e07ddf95b4
commit
26d6c2413b
@ -27,6 +27,7 @@
|
|||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
#include <AP_InternalError/AP_InternalError.h>
|
#include <AP_InternalError/AP_InternalError.h>
|
||||||
#include <AP_Common/ExpandingString.h>
|
#include <AP_Common/ExpandingString.h>
|
||||||
|
#include <AP_HAL/SIMState.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
#include <SITL/SITL.h>
|
#include <SITL/SITL.h>
|
||||||
@ -400,6 +401,10 @@ void AP_Scheduler::loop()
|
|||||||
perf_info.check_loop_time(sample_time_us - _loop_timer_start_us);
|
perf_info.check_loop_time(sample_time_us - _loop_timer_start_us);
|
||||||
|
|
||||||
_loop_timer_start_us = sample_time_us;
|
_loop_timer_start_us = sample_time_us;
|
||||||
|
|
||||||
|
#if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
||||||
|
hal.simstate->update();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Scheduler::update_logging()
|
void AP_Scheduler::update_logging()
|
||||||
|
Loading…
Reference in New Issue
Block a user