mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
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
This commit is contained in:
parent
25c7ee4d42
commit
7ade37bd4e
@ -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
|
||||
};
|
||||
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user