mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
SITL: added SIM_GPS_LOCKTIME parameter
This commit is contained in:
parent
807ba9d520
commit
a7967e00e4
@ -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
|
||||
};
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user