Browse Source

AP_AHRS: take secondary attitude from EKF3 if it is configured

c415-sdk
Peter Barker 4 years ago committed by Andrew Tridgell
parent
commit
814aa4e5ec
  1. 17
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

17
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -608,13 +608,20 @@ bool AP_AHRS_NavEKF::get_secondary_attitude(Vector3f &eulers) const @@ -608,13 +608,20 @@ bool AP_AHRS_NavEKF::get_secondary_attitude(Vector3f &eulers) const
switch (active_EKF_type()) {
case EKFType::NONE:
// EKF is secondary
switch ((EKFType)_ekf_type.get()) {
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE:
EKF3.getEulerAngles(-1, eulers);
return _ekf3_started;
#endif
#if HAL_NAVEKF2_AVAILABLE
EKF2.getEulerAngles(-1, eulers);
return _ekf2_started;
#else
return false;
case EKFType::TWO:
EKF2.getEulerAngles(-1, eulers);
return _ekf2_started;
#endif
default:
return false;
}
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO:
#endif

Loading…
Cancel
Save