diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 60eab93b84..439bd42657 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -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 }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 30bca34baf..d54d28e9c3 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -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