From be3a49938efc154aa05b0a8e19f455d4c3bbd362 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 21 Nov 2024 19:08:49 +0900 Subject: [PATCH] AP_NavEKF3: align visodom yaw if using optflow and no yaw src --- libraries/AP_NavEKF/AP_NavEKF_Source.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp index 679215d296581..1146f57f16240 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp @@ -293,7 +293,8 @@ void AP_NavEKF_Source::align_inactive_sources() if ((getYawSource() == SourceYaw::COMPASS) || (getYawSource() == SourceYaw::GPS) || (getYawSource() == SourceYaw::GPS_COMPASS_FALLBACK) || - (getYawSource() == SourceYaw::GSF)) { + (getYawSource() == SourceYaw::GSF) || + ((getYawSource() == SourceYaw::NONE) && option_is_set(SourceOptions::ALIGN_EXTNAV_POS_WHEN_USING_OPTFLOW))) { for (uint8_t i=0; i