AP_NavEKF3: always set EKF control limits, even with no cores

This commit is contained in:
Peter Barker 2018-10-02 14:06:15 +10:00 committed by Andrew Tridgell
parent 889190d46e
commit 281fad53c2
1 changed files with 3 additions and 0 deletions

View File

@ -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;
}
}