From 281fad53c2b1418c7bef06d663c59352f4dc0061 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Oct 2018 14:06:15 +1000 Subject: [PATCH] AP_NavEKF3: always set EKF control limits, even with no cores --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index e7041f07f3..197e368a00 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -940,6 +940,9 @@ void NavEKF3::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; } }