mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
SITL: Add ARSP_FAIL param
This will allow testing pitot tube hardware failures
This commit is contained in:
parent
5cc7c456a7
commit
250dcd31a2
@ -70,6 +70,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0),
|
||||
AP_GROUPINFO("MAG_OFS", 41, SITL, mag_ofs, 0),
|
||||
AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
|
||||
AP_GROUPINFO("ARSP_FAIL", 43, SITL, aspd_fail, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -62,6 +62,8 @@ public:
|
||||
AP_Float accel2_noise; // in m/s/s
|
||||
AP_Vector3f accel_bias; // in m/s/s
|
||||
AP_Float aspd_noise; // in m/s
|
||||
AP_Int8 aspd_fail; // pitot tube failure
|
||||
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user