Browse Source

AP_InertialSensor: fixed use of accel2_noise

thanks Francisco!
mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
112b22516a
  1. 2
      libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp

2
libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp

@ -57,7 +57,7 @@ void AP_InertialSensor_SITL::generate_accel(uint8_t instance) @@ -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

Loading…
Cancel
Save