From 5ab2a19173da1f04c65e457a6f66d08a079fb281 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sun, 28 Jun 2015 16:17:17 +0900 Subject: [PATCH] AC_WPNav: loiter limits lean angle for alt loss --- libraries/AC_WPNav/AC_Circle.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 2249bd2713..05ab94f802 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -162,7 +162,7 @@ void AC_Circle::update() } // update position controller - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f); + _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f, false); } } diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 93bc9e200f..e0a9a8d8f8 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -328,7 +328,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler) dt = 0.0f; } calc_loiter_desired_velocity(dt,ekfGndSpdLimit); - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler); + _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler, true); } } @@ -363,7 +363,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,0); - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler); + _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_LIMITED_AND_VEL_FF, ekfNavVelGainScaler, false); } } @@ -675,7 +675,7 @@ void AC_WPNav::update_wpnav() } _pos_control.freeze_ff_z(); - _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f); + _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f, false); check_wp_leash_length(); _wp_last_update = hal.scheduler->millis(); @@ -890,7 +890,7 @@ void 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); + _pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f, false); _wp_last_update = hal.scheduler->millis(); }