SITL: Add GPS noise parameter

This commit is contained in:
Michael du Breuil 2017-01-30 12:04:10 -07:00 committed by Andrew Tridgell
parent f183a2618f
commit ef0c51da42
2 changed files with 2 additions and 0 deletions

View File

@ -88,6 +88,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0), AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0), AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0), AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -76,6 +76,7 @@ public:
AP_Vector3f accel2_bias; // in m/s/s AP_Vector3f accel2_bias; // in m/s/s
AP_Float arspd_noise; // in m/s AP_Float arspd_noise; // in m/s
AP_Float arspd_fail; // pitot tube failure AP_Float arspd_fail; // pitot tube failure
AP_Float gps_noise; // amplitude of the gps altitude error
AP_Float mag_noise; // in mag units (earth field is 818) AP_Float mag_noise; // in mag units (earth field is 818)
AP_Float mag_error; // in degrees AP_Float mag_error; // in degrees