AP_InertialSensor: fixed use of accel2_noise

thanks Francisco!
This commit is contained in:
Andrew Tridgell 2017-05-02 08:24:50 +10:00
parent a3f4a523b2
commit 112b22516a

View File

@ -57,7 +57,7 @@ void AP_InertialSensor_SITL::generate_accel(uint8_t instance)
if (sitl->motors_on) {
// add extra noise when the motors are on
accel_noise += sitl->accel_noise;
accel_noise += instance==0?sitl->accel_noise:sitl->accel2_noise;
}
// add accel bias and noise