From e11c7c6069edf98b69d41183c66394adf0e91bc3 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 21 Aug 2018 15:56:42 +0930 Subject: [PATCH] QuadPlane: remove true from init of loiter --- ArduPlane/quadplane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f9d317e8a6..5e2ea9369a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2081,7 +2081,7 @@ void QuadPlane::init_qrtl(void) poscontrol.state = QPOS_POSITION1; poscontrol.speed_scale = 0; pos_control->set_desired_accel_xy(0.0f, 0.0f); - pos_control->init_xy_controller(true); + pos_control->init_xy_controller(); } /* @@ -2134,7 +2134,7 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd) poscontrol.state = QPOS_POSITION1; poscontrol.speed_scale = 0; pos_control->set_desired_accel_xy(0.0f, 0.0f); - pos_control->init_xy_controller(true); + pos_control->init_xy_controller(); throttle_wait = false; landing_detect.lower_limit_start_ms = 0;