mirror of https://github.com/ArduPilot/ardupilot
SITL: added SIM_TIME_JITTER parameter
for adding timing jitter in SITL
This commit is contained in:
parent
47df6f0ab6
commit
7039088c7b
|
@ -247,6 +247,8 @@ const AP_Param::GroupInfo SIM::var_info3[] = {
|
|||
AP_SUBGROUPINFO(baro[2], "BAR3_", 36, SIM, SIM::BaroParm),
|
||||
#endif
|
||||
|
||||
AP_GROUPINFO("TIME_JITTER", 37, SIM, loop_time_jitter_us, 0),
|
||||
|
||||
// user settable parameters for the 1st barometer
|
||||
// @Param: BARO_RND
|
||||
// @DisplayName: Baro Noise
|
||||
|
|
|
@ -230,6 +230,7 @@ public:
|
|||
AP_Int32 mag_devid[MAX_CONNECTED_MAGS]; // Mag devid
|
||||
AP_Float buoyancy; // submarine buoyancy in Newtons
|
||||
AP_Int16 loop_rate_hz;
|
||||
AP_Int16 loop_time_jitter_us;
|
||||
AP_Int32 on_hardware_output_enable_mask; // mask of output channels passed through to actual hardware
|
||||
|
||||
#ifdef SFML_JOYSTICK
|
||||
|
|
Loading…
Reference in New Issue