AC_WPNav: update variable name for consistency

This commit is contained in:
Andrew Tridgell 2021-08-15 08:49:13 +10:00
parent 285798446a
commit 973466856c
1 changed files with 2 additions and 2 deletions

View File

@ -208,8 +208,8 @@ void AC_Loiter::sanity_check_params()
/// updated velocity sent directly to position controller
void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on)
{
float ekfGndSpdLimit, ekfNavVelGainScaler;
AP::ahrs().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
float ekfGndSpdLimit, ahrsControlScaleXY;
AP::ahrs().getControlLimits(ekfGndSpdLimit, ahrsControlScaleXY);
// 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