From 344d621a0868fc69d1401697ebceaa5b0bccbe79 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sat, 16 May 2020 11:45:06 +1000 Subject: [PATCH] AP_NavEKF3: Add missing fallback to baro for range beacon use case --- libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp index 53fbe9e11c..ddf08c150c 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_PosVelFusion.cpp @@ -1034,7 +1034,8 @@ void NavEKF3_core::selectHeightForFusion() bool lostRngHgt = ((activeHgtSource == HGT_SOURCE_RNG) && ((imuSampleTime_ms - rngValidMeaTime_ms) > 500)); bool lostGpsHgt = ((activeHgtSource == HGT_SOURCE_GPS) && ((imuSampleTime_ms - lastTimeGpsReceived_ms) > 2000)); bool lostExtNavHgt = ((activeHgtSource == HGT_SOURCE_EXTNAV) && ((imuSampleTime_ms - extNavMeasTime_ms) > 2000)); - if (lostRngHgt || lostGpsHgt || lostExtNavHgt) { + bool lostRngBcnHgt = ((activeHgtSource == HGT_SOURCE_BCN) && ((imuSampleTime_ms - rngBcnDataDelayed.time_ms) > 2000)); + if (lostRngHgt || lostGpsHgt || lostExtNavHgt || lostRngBcnHgt) { activeHgtSource = HGT_SOURCE_BARO; }