mirror of https://github.com/ArduPilot/ardupilot
AP_InertialSensor: don't apply offsets in SITL backend
the offsets are applied in the rotate and correct methods
This commit is contained in:
parent
160ce436e3
commit
eab1d3af4f
|
@ -92,7 +92,7 @@ void AP_InertialSensor_SITL::generate_accel(uint8_t instance)
|
|||
zAccel = sitl->accel_fail;
|
||||
}
|
||||
|
||||
Vector3f accel = Vector3f(xAccel, yAccel, zAccel) + _imu.get_accel_offsets(instance);
|
||||
Vector3f accel = Vector3f(xAccel, yAccel, zAccel);
|
||||
|
||||
_rotate_and_correct_accel(accel_instance[instance], accel);
|
||||
|
||||
|
@ -120,7 +120,7 @@ void AP_InertialSensor_SITL::generate_gyro(uint8_t instance)
|
|||
q += gyro_noise * rand_float();
|
||||
r += gyro_noise * rand_float();
|
||||
|
||||
Vector3f gyro = Vector3f(p, q, r) + _imu.get_gyro_offsets(instance);
|
||||
Vector3f gyro = Vector3f(p, q, r);
|
||||
|
||||
// add in gyro scaling
|
||||
Vector3f scale = sitl->gyro_scale;
|
||||
|
|
Loading…
Reference in New Issue