mirror of https://github.com/ArduPilot/ardupilot
QuadPlane: remove true from init of loiter
This commit is contained in:
parent
8faa1cce39
commit
e11c7c6069
|
@ -2081,7 +2081,7 @@ void QuadPlane::init_qrtl(void)
|
||||||
poscontrol.state = QPOS_POSITION1;
|
poscontrol.state = QPOS_POSITION1;
|
||||||
poscontrol.speed_scale = 0;
|
poscontrol.speed_scale = 0;
|
||||||
pos_control->set_desired_accel_xy(0.0f, 0.0f);
|
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.state = QPOS_POSITION1;
|
||||||
poscontrol.speed_scale = 0;
|
poscontrol.speed_scale = 0;
|
||||||
pos_control->set_desired_accel_xy(0.0f, 0.0f);
|
pos_control->set_desired_accel_xy(0.0f, 0.0f);
|
||||||
pos_control->init_xy_controller(true);
|
pos_control->init_xy_controller();
|
||||||
|
|
||||||
throttle_wait = false;
|
throttle_wait = false;
|
||||||
landing_detect.lower_limit_start_ms = 0;
|
landing_detect.lower_limit_start_ms = 0;
|
||||||
|
|
Loading…
Reference in New Issue