diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index a9b2a8ad92..7bb04953ad 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -65,6 +65,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = { AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1), 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_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index da99268158..411d1721bb 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -90,6 +90,7 @@ public: AP_Float wind_speed; AP_Float wind_direction; AP_Float wind_turbulance; + AP_Float gps_drift_alt; void simstate_send(mavlink_channel_t chan);