Plane: removed set_state to QPOS_POSITION1 in do_vtol_land

we are immediately replacing the state with QPOS_APPROACH, so the
set_state is not needed, and triggers a call to
attitude_control->reset_yaw_target_and_rate() which can badly impact
euler rates for tailsitters
This commit is contained in:
Andrew Tridgell 2021-09-27 11:54:35 +10:00
parent 93e6cfef35
commit 9d0b7f8efe

View File

@ -2802,11 +2802,10 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
return false;
}
attitude_control->reset_rate_controller_I_terms();
plane.set_next_WP(cmd.content.location);
// initially aim for current altitude
plane.next_WP_loc.alt = plane.current_loc.alt;
poscontrol.set_state(QPOS_POSITION1);
// initialise the position controller
pos_control->init_xy_controller();