mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AHRS_NavEKF: fix blended accel to use primary accel
This commit is contained in:
parent
5f00ea77e8
commit
cdd64fc43d
@ -138,7 +138,7 @@ void AP_AHRS_NavEKF::update(void)
|
||||
EKF.getIMU1Weighting(IMU1_weighting);
|
||||
_accel_ef_ekf_blended = _accel_ef_ekf[0] * IMU1_weighting + _accel_ef_ekf[1] * (1.0f-IMU1_weighting);
|
||||
} else {
|
||||
_accel_ef_ekf_blended = _accel_ef_ekf[0];
|
||||
_accel_ef_ekf_blended = _accel_ef_ekf[_ins.get_primary_accel()];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user