From a7967e00e4a1fab4d7129c6588cac7aaa7db4f97 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Jul 2017 15:00:46 +1000 Subject: [PATCH] SITL: added SIM_GPS_LOCKTIME parameter --- 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 8857e1e1ec..88f1cf0c34 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -103,6 +103,7 @@ const AP_Param::GroupInfo SITL::var_info2[] = { AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35), AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30), AP_GROUPINFO("TEMP_BFACTOR", 4, SITL, temp_baro_factor, 0), + AP_GROUPINFO("GPS_LOCKTIME", 5, SITL, gps_lock_time, 0), AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 27742c5736..4a62d85ffd 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -83,6 +83,7 @@ public: AP_Float arspd_noise; // in m/s AP_Float arspd_fail; // pitot tube failure AP_Float gps_noise; // amplitude of the gps altitude error + AP_Int16 gps_lock_time; // delay in seconds before GPS gets lock AP_Float mag_noise; // in mag units (earth field is 818) AP_Float mag_error; // in degrees