Browse Source

SITL: Add GPS noise parameter

mission-4.1.18
Michael du Breuil 8 years ago committed by Andrew Tridgell
parent
commit
ef0c51da42
  1. 1
      libraries/SITL/SITL.cpp
  2. 1
      libraries/SITL/SITL.h

1
libraries/SITL/SITL.cpp

@ -88,6 +88,7 @@ const AP_Param::GroupInfo SITL::var_info[] = { @@ -88,6 +88,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
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_GROUPEND
};

1
libraries/SITL/SITL.h

@ -76,6 +76,7 @@ public: @@ -76,6 +76,7 @@ public:
AP_Vector3f accel2_bias; // in m/s/s
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_Float mag_noise; // in mag units (earth field is 818)
AP_Float mag_error; // in degrees

Loading…
Cancel
Save