mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: added ACC2_BIAS
This commit is contained in:
parent
7d4a50f483
commit
65c3d0e060
@ -87,6 +87,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
|||||||
AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset, 0),
|
AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset, 0),
|
||||||
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_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("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
|
||||||
|
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -73,6 +73,7 @@ public:
|
|||||||
AP_Float accel_noise; // in m/s/s
|
AP_Float accel_noise; // in m/s/s
|
||||||
AP_Float accel2_noise; // in m/s/s
|
AP_Float accel2_noise; // in m/s/s
|
||||||
AP_Vector3f accel_bias; // 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_noise; // in m/s
|
||||||
AP_Float arspd_fail; // pitot tube failure
|
AP_Float arspd_fail; // pitot tube failure
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user