mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
SITL: remove unused MAG_ERROR and VICON_HSTLEN params
This commit is contained in:
parent
fd32dff45a
commit
bf9ee4ada8
@ -50,7 +50,6 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type[0], SITL::GPS_TYPE_UBLOX),
|
||||
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
|
||||
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
|
||||
AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
|
||||
AP_GROUPINFO("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
|
||||
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch[0], 0),
|
||||
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
|
||||
@ -117,7 +116,6 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||
AP_GROUPINFO("ARSPD2_FAIL", 11, SITL, arspd2_fail, 0),
|
||||
AP_GROUPINFO("ARSPD2_FAILP",12, SITL, arspd2_fail_pressure, 0),
|
||||
AP_GROUPINFO("ARSPD2_PITOT",13, SITL, arspd2_fail_pitot_pressure, 0),
|
||||
AP_GROUPINFO("VICON_HSTLEN",14, SITL, vicon_observation_history_length, 0),
|
||||
AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
|
||||
AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
|
||||
AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
|
||||
|
@ -148,10 +148,8 @@ public:
|
||||
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_Int8 vicon_observation_history_length; // frame delay for vicon messages
|
||||
|
||||
AP_Float mag_noise; // in mag units (earth field is 818)
|
||||
AP_Float mag_error; // in degrees
|
||||
AP_Vector3f mag_mot; // in mag units per amp
|
||||
AP_Vector3f mag_ofs; // in mag units
|
||||
AP_Vector3f mag_diag; // diagonal corrections
|
||||
|
Loading…
Reference in New Issue
Block a user