From 6430b75224279cf59b32028feb6ceba301da62a2 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 28 Apr 2017 16:26:39 +0900 Subject: [PATCH] AC_WPNav: remove xy mode from brake, wp, spline --- libraries/AC_WPNav/AC_WPNav.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index d017b7b67c..65a1aa4d76 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -372,7 +372,7 @@ void AC_WPNav::update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler) // send adjusted feed forward velocity back to position controller _pos_control.set_desired_velocity_xy(0.0f, 0.0f); - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler, false); + _pos_control.update_xy_controller(ekfNavVelGainScaler); } } @@ -767,7 +767,7 @@ bool AC_WPNav::update_wpnav() } _pos_control.freeze_ff_z(); - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f, false); + _pos_control.update_xy_controller(1.0f); check_wp_leash_length(); _wp_last_update = AP_HAL::millis(); @@ -1060,7 +1060,7 @@ bool AC_WPNav::update_spline() _pos_control.freeze_ff_z(); // run horizontal position controller - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f, false); + _pos_control.update_xy_controller(1.0f); _wp_last_update = AP_HAL::millis(); }