AP_NavEKF2: always set EKF control limits, even with no cores
This commit is contained in:
parent
47b5cf98ea
commit
889190d46e
@ -896,6 +896,9 @@ void NavEKF2::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainSca
|
|||||||
{
|
{
|
||||||
if (core) {
|
if (core) {
|
||||||
core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
core[primary].getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||||
|
} else {
|
||||||
|
ekfGndSpdLimit = 400.0f; //return 80% of max filter speed
|
||||||
|
ekfNavVelGainScaler = 1.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user