mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
SITL: add GPS2_GLITCH parameter
This commit is contained in:
parent
8c64728ffd
commit
07ce7b8bd6
@ -89,6 +89,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||
AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
|
||||
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
|
||||
AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
|
||||
AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps2_glitch, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -97,7 +97,8 @@ public:
|
||||
AP_Int8 gps_type; // see enum GPSType
|
||||
AP_Float gps_byteloss;// byte loss as a percent
|
||||
AP_Int8 gps_numsats; // number of visible satellites
|
||||
AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
|
||||
AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
|
||||
AP_Vector3f gps2_glitch; // glitch offsets in lat, lon and altitude for 2nd GPS
|
||||
AP_Int8 gps_hertz; // GPS update rate in Hz
|
||||
AP_Float batt_voltage; // battery voltage base
|
||||
AP_Float accel_fail; // accelerometer failure value
|
||||
|
Loading…
Reference in New Issue
Block a user