mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AC_WPNav: rename for AHRS restructuring
This commit is contained in:
parent
63015e9e9a
commit
8396925ece
@ -209,7 +209,7 @@ void AC_Loiter::sanity_check_params()
|
|||||||
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, 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
|
// 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
Block a user