diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index 396935e47f..30f506529a 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -1,5 +1,6 @@ #include #include "AC_Loiter.h" +#include extern const AP_HAL::HAL& hal; @@ -274,6 +275,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) desired_vel.y = desired_vel.y * gnd_speed_limit_cms / horizSpdDem; } +#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane) if (avoidance_on) { // Limit the velocity to prevent fence violations // TODO: We need to also limit the _desired_accel @@ -284,6 +286,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt, bool avoidance_on) desired_vel = Vector2f{avoidance_vel_3d.x, avoidance_vel_3d.y}; } } +#endif // !APM_BUILD_ArduPlane // get loiters desired velocity from the position controller where it is being stored. Vector2p target_pos = _pos_control.get_pos_target_cm().xy();