Browse Source

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
apm_2208
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
fd666dc4f1
  1. 2
      libraries/AP_AHRS/AP_AHRS.cpp

2
libraries/AP_AHRS/AP_AHRS.cpp

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

Loading…
Cancel
Save