diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index dd49aa8a82..c2be929994 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -66,6 +66,9 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10), AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0), AP_GROUPINFO("GPS_DRIFTALT", 37, SITL, gps_drift_alt, 0), + AP_GROUPINFO("BARO_DELAY", 38, SITL, baro_delay, 0), + AP_GROUPINFO("MAG_DELAY", 39, SITL, mag_delay, 0), + AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0), AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 411d1721bb..11f1de26bb 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -91,7 +91,11 @@ public: AP_Float wind_direction; AP_Float wind_turbulance; AP_Float gps_drift_alt; - + + AP_Int16 baro_delay; // barometer data delay in ms + AP_Int16 mag_delay; // magnetometer data delay in ms + AP_Int16 wind_delay; // windspeed data delay in ms + void simstate_send(mavlink_channel_t chan); void Log_Write_SIMSTATE(DataFlash_Class &dataflash);