From 0eaf81541116c087a95b6f380b6bb527b54e6299 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 6 Sep 2015 21:25:09 +0900 Subject: [PATCH] Copter: guided mode vel controller integrates althold lean limit Note it does not yet actually limit the lean angles based on throttle --- ArduCopter/control_guided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_guided.cpp b/ArduCopter/control_guided.cpp index 6c24bf8f2c..203f22a99a 100644 --- a/ArduCopter/control_guided.cpp +++ b/ArduCopter/control_guided.cpp @@ -363,7 +363,7 @@ void Copter::guided_posvel_control_run() pos_control.set_desired_velocity_xy(posvel_vel_target_cms.x, posvel_vel_target_cms.y); // run position controller - pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler); + pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler, false); } pos_control.update_z_controller();