mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: update variable name for consistency
This commit is contained in:
parent
285798446a
commit
973466856c
|
@ -208,8 +208,8 @@ void AC_Loiter::sanity_check_params()
|
||||||
/// updated velocity sent directly to position controller
|
/// updated velocity sent directly to position controller
|
||||||
void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on)
|
void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on)
|
||||||
{
|
{
|
||||||
float ekfGndSpdLimit, ekfNavVelGainScaler;
|
float ekfGndSpdLimit, ahrsControlScaleXY;
|
||||||
AP::ahrs().getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
AP::ahrs().getControlLimits(ekfGndSpdLimit, ahrsControlScaleXY);
|
||||||
|
|
||||||
// calculate a loiter speed limit which is the minimum of the value set by the LOITER_SPEED
|
// 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
|
// parameter and the value set by the EKF to observe optical flow limits
|
||||||
|
|
Loading…
Reference in New Issue