diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 0aae25494f..10699e1db0 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -159,7 +159,7 @@ void AC_Circle::update() } // run loiter's position to velocity step - _pos_control.update_xy_controller(false); + _pos_control.update_xy_controller(false, 1.0f); } // get_closest_point_on_circle - returns closest point on the circle diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 1a7419b6d5..1d6bb0b99e 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -297,7 +297,7 @@ int32_t AC_WPNav::get_loiter_bearing_to_target() const } /// update_loiter - run the loiter controller - should be called at 100hz -void AC_WPNav::update_loiter(float ekfGndSpdLimit) +void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler) { // calculate dt uint32_t now = hal.scheduler->millis(); @@ -317,7 +317,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit) _pos_control.trigger_xy(); }else{ // run horizontal position controller - _pos_control.update_xy_controller(true); + _pos_control.update_xy_controller(true, ekfNavVelGainScaler); } } @@ -627,7 +627,7 @@ void AC_WPNav::update_wpnav() _pos_control.freeze_ff_z(); }else{ // run horizontal position controller - _pos_control.update_xy_controller(false); + _pos_control.update_xy_controller(false, 1.0f); // check if leash lengths need updating check_wp_leash_length(); @@ -892,7 +892,7 @@ void AC_WPNav::update_spline() _pos_control.freeze_ff_z(); }else{ // run horizontal position controller - _pos_control.update_xy_controller(false); + _pos_control.update_xy_controller(false, 1.0f); } } diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 77474c7092..3a17046a99 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -95,7 +95,7 @@ public: int32_t get_loiter_bearing_to_target() const; /// update_loiter - run the loiter controller - should be called at 10hz - void update_loiter(float ekfGndSpdLimit); + void update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler); /// /// waypoint controller