From 7ade37bd4e10c59de04b85a738a4ff7f97c90c72 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Sep 2017 10:24:45 +1000 Subject: [PATCH] SITL: added SIM_GPS_ALT_OFS this is used to give a bad GPS height in SITL, which is very useful for testing origin vs home issues --- libraries/SITL/SITL.cpp | 1 + libraries/SITL/SITL.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 87ef7713f4..e35c7d3751 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -106,6 +106,7 @@ const AP_Param::GroupInfo SITL::var_info2[] = { AP_GROUPINFO("GPS_LOCKTIME", 5, SITL, gps_lock_time, 0), AP_GROUPINFO("ARSPD_FAIL_P", 6, SITL, arspd_fail_pressure, 0), AP_GROUPINFO("ARSPD_PITOT", 7, SITL, arspd_fail_pitot_pressure, 0), + AP_GROUPINFO("GPS_ALT_OFS", 8, SITL, gps_alt_offset, 0), AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 03dd577f61..fecabc5cba 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -86,6 +86,7 @@ public: AP_Float arspd_fail_pitot_pressure; // pitot tube failure pressure AP_Float gps_noise; // amplitude of the gps altitude error AP_Int16 gps_lock_time; // delay in seconds before GPS gets lock + AP_Int16 gps_alt_offset; // gps alt error AP_Float mag_noise; // in mag units (earth field is 818) AP_Float mag_error; // in degrees