QuadPlane: remove true from init of loiter

This commit is contained in:
Leonard Hall 2018-08-21 15:56:42 +09:30 committed by Randy Mackay
parent 60815d5e92
commit 47c5f14987
1 changed files with 2 additions and 2 deletions

View File

@ -2074,7 +2074,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();
}
/*
@ -2127,7 +2127,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;