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:
parent
2fb1bde457
commit
fd666dc4f1
@ -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…
Reference in New Issue
Block a user