From f9acc8a666e874ff113eee66863b27ebafaea6fd Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 27 Jun 2017 23:11:37 +0900 Subject: [PATCH] Copter: guided removes xy mode in calls to pos-con Also limit angle to hold altitude --- ArduCopter/mode_guided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 7e2dc697a5..2e4cea5e28 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -553,7 +553,7 @@ void Copter::ModeGuided::posvel_control_run() pos_control->set_desired_velocity_xy(guided_vel_target_cms.x, guided_vel_target_cms.y); // run position controller - pos_control->update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL_FF, ekfNavVelGainScaler, false); + pos_control->update_xy_controller(ekfNavVelGainScaler); } pos_control->update_z_controller();