diff --git a/ArduCopter/control_guided.pde b/ArduCopter/control_guided.pde index f9294116fe..9f7944d191 100644 --- a/ArduCopter/control_guided.pde +++ b/ArduCopter/control_guided.pde @@ -313,7 +313,7 @@ static void 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(true, ekfNavVelGainScaler); + pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_AND_VEL, ekfNavVelGainScaler); pos_control.update_z_controller(); // call attitude controller