diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index f745794b40..8d8c14e4fe 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -342,6 +342,10 @@ const AP_Param::GroupInfo SITL::var_gps[] = { AP_GROUPINFO("GPS2_ACC", 43, SITL, gps_accuracy[1], 0.3), AP_GROUPINFO("GPS2_VERR", 44, SITL, gps_vel_err[1], 0), + AP_GROUPINFO("INIT_LAT_OFS", 45, SITL, gps_init_lat_ofs, 0), + AP_GROUPINFO("INIT_LON_OFS", 46, SITL, gps_init_lon_ofs, 0), + AP_GROUPINFO("INIT_ALT_OFS", 47, SITL, gps_init_alt_ofs, 0), + AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index dd2c3fee1b..63ab85e173 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -211,6 +211,11 @@ public: AP_Float gps_accuracy[2]; AP_Vector3f gps_vel_err[2]; // Velocity error offsets in NED (x = N, y = E, z = D) + // initial offset on GPS lat/lon, used to shift origin + AP_Float gps_init_lat_ofs; + AP_Float gps_init_lon_ofs; + AP_Float gps_init_alt_ofs; + AP_Float batt_voltage; // battery voltage base AP_Float batt_capacity_ah; // battery capacity in Ah AP_Int8 rc_fail; // fail RC input