AP_AHRS: subtract accel bias from correct ins accel instance

In the case that you have INS_USE indicating IMUs should be used, but
EK3_IMU_MASK leaving some IMUs unused, we subtract the bias from the
wrong INS data
This commit is contained in:
Peter Barker 2022-04-02 18:13:51 +11:00 committed by Randy Mackay
parent aeed2b1a9d
commit 45aebfdf74
1 changed files with 1 additions and 1 deletions

View File

@ -580,7 +580,7 @@ void AP_AHRS::update_EKF3(void)
// update _accel_ef_ekf // update _accel_ef_ekf
for (uint8_t i=0; i<_ins.get_accel_count(); i++) { for (uint8_t i=0; i<_ins.get_accel_count(); i++) {
Vector3f accel = _ins.get_accel(i); Vector3f accel = _ins.get_accel(i);
if (i==_ins.get_primary_accel()) { if (i == primary_imu) {
accel -= abias; accel -= abias;
} }
if (_ins.get_accel_health(i)) { if (_ins.get_accel_health(i)) {