diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 95ef43c334..4fa14de2d5 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -87,6 +87,7 @@ const AP_Param::GroupInfo SITL::var_info[] = { AP_GROUPINFO("GPS_POS", 54, SITL, gps_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("ACC2_BIAS", 57, SITL, accel2_bias, 0), AP_GROUPEND }; diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index f46e19fe0e..58e21afb9d 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -73,6 +73,7 @@ public: AP_Float accel_noise; // in m/s/s AP_Float accel2_noise; // in m/s/s 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