AC_WPNav: rename for AHRS restructuring

This commit is contained in:
Peter Barker 2021-07-20 22:16:29 +10:00 committed by Peter Barker
parent 63015e9e9a
commit 8396925ece

View File

@ -209,7 +209,7 @@ void AC_Loiter::sanity_check_params()
void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on)
{
float ekfGndSpdLimit, ekfNavVelGainScaler;
AP::ahrs_navekf().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
AP::ahrs().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
// calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED
// parameter and the value set by the EKF to observe optical flow limits