AP_AHRS: relax arming checks for inactive AHRS types

When using an EKF as ride-along we should not fail arming if it has
inconsistent yaw between its lanes. This is especially important when
using external yaw or GPS yaw with EKF3, where yaw is expected to be
bad with EKF2.

The check on DCM is based on the existance of an AHRS view. This is so
that tailsitters do not get arming failures due to the inability of
DCM to cope with being nose up
This commit is contained in:
Andrew Tridgell 2021-10-19 12:12:09 +11:00
parent 04a170d141
commit 01fb16b3b0
1 changed files with 38 additions and 34 deletions

View File

@ -2324,6 +2324,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_
#if HAL_NAVEKF2_AVAILABLE #if HAL_NAVEKF2_AVAILABLE
// check primary vs ekf2 // check primary vs ekf2
if (ekf_type() == EKFType::TWO || active_EKF_type() == EKFType::TWO) {
for (uint8_t i = 0; i < EKF2.activeCores(); i++) { for (uint8_t i = 0; i < EKF2.activeCores(); i++) {
Quaternion ekf2_quat; Quaternion ekf2_quat;
EKF2.getQuaternionBodyToNED(i, ekf2_quat); EKF2.getQuaternionBodyToNED(i, ekf2_quat);
@ -2345,10 +2346,12 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_
} }
} }
total_ekf_cores = EKF2.activeCores(); total_ekf_cores = EKF2.activeCores();
}
#endif #endif
#if HAL_NAVEKF3_AVAILABLE #if HAL_NAVEKF3_AVAILABLE
// check primary vs ekf3 // check primary vs ekf3
if (ekf_type() == EKFType::THREE || active_EKF_type() == EKFType::THREE) {
for (uint8_t i = 0; i < EKF3.activeCores(); i++) { for (uint8_t i = 0; i < EKF3.activeCores(); i++) {
Quaternion ekf3_quat; Quaternion ekf3_quat;
EKF3.getQuaternionBodyToNED(i, ekf3_quat); EKF3.getQuaternionBodyToNED(i, ekf3_quat);
@ -2370,6 +2373,7 @@ bool AP_AHRS::attitudes_consistent(char *failure_msg, const uint8_t failure_msg_
} }
} }
total_ekf_cores += EKF3.activeCores(); total_ekf_cores += EKF3.activeCores();
}
#endif #endif
// check primary vs dcm // check primary vs dcm