From 889190d46e2e48bb625fbe7689eb3b4a2893366b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Oct 2018 14:06:07 +1000 Subject: [PATCH] AP_NavEKF2: always set EKF control limits, even with no cores --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index a9e1381b45..5b4352b612 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -896,6 +896,9 @@ void NavEKF2::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainSca { if (core) { core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler); + } else { + ekfGndSpdLimit = 400.0f; //return 80% of max filter speed + ekfNavVelGainScaler = 1.0f; } }