Browse Source

SITL: SITL of several airspeed sensors

mission-4.1.18
Eugene Shamaev 7 years ago committed by Tom Pittenger
parent
commit
6954a0035a
  1. 3
      libraries/SITL/SITL.cpp
  2. 9
      libraries/SITL/SITL.h

3
libraries/SITL/SITL.cpp

@ -109,6 +109,9 @@ const AP_Param::GroupInfo SITL::var_info2[] = { @@ -109,6 +109,9 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
AP_GROUPINFO("GPS_ALT_OFS", 8, SITL, gps_alt_offset, 0),
AP_GROUPINFO("ARSPD_SIGN", 9, SITL, arspd_signflip, 0),
AP_GROUPINFO("WIND_DIR_Z", 10, SITL, wind_dir_z, 0),
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_GROUPEND
};

9
libraries/SITL/SITL.h

@ -81,9 +81,12 @@ public: @@ -81,9 +81,12 @@ public:
AP_Vector3f accel_bias; // in m/s/s
AP_Vector3f accel2_bias; // in m/s/s
AP_Float arspd_noise; // in m/s
AP_Float arspd_fail; // pitot tube failure
AP_Float arspd_fail_pressure; // pitot tube failure pressure
AP_Float arspd_fail_pitot_pressure; // pitot tube failure pressure
AP_Float arspd_fail; // 1st pitot tube failure
AP_Float arspd2_fail; // 2nd pitot tube failure
AP_Float arspd_fail_pressure; // 1st pitot tube failure pressure
AP_Float arspd_fail_pitot_pressure; // 1st pitot tube failure pressure
AP_Float arspd2_fail_pressure; // 2nd pitot tube failure pressure
AP_Float arspd2_fail_pitot_pressure; // 2nd 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

Loading…
Cancel
Save