mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
SITL: added SIM_ACCEL_FAIL option
used to test accelerometer failure in flight
This commit is contained in:
parent
9d7f24f754
commit
428479b9d5
@ -111,6 +111,12 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative
|
||||
yAccel += accel_noise * _rand_float();
|
||||
zAccel += accel_noise * _rand_float();
|
||||
|
||||
if (fabs(_sitl->accel_fail) > 1.0e-6) {
|
||||
xAccel = _sitl->accel_fail;
|
||||
yAccel = _sitl->accel_fail;
|
||||
zAccel = _sitl->accel_fail;
|
||||
}
|
||||
|
||||
p += gyro_noise * _rand_float();
|
||||
q += gyro_noise * _rand_float();
|
||||
r += gyro_noise * _rand_float();
|
||||
|
@ -46,6 +46,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
||||
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
|
||||
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
|
||||
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
||||
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -65,6 +65,7 @@ public:
|
||||
AP_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
|
||||
AP_Int8 gps_hertz; // GPS update rate in Hz
|
||||
AP_Float batt_voltage; // battery voltage base
|
||||
AP_Float accel_fail; // accelerometer failure value
|
||||
|
||||
// wind control
|
||||
AP_Float wind_speed;
|
||||
|
Loading…
Reference in New Issue
Block a user