mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
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:
parent
93e6cfef35
commit
9d0b7f8efe
@ -2806,7 +2806,6 @@ bool QuadPlane::do_vtol_land(const AP_Mission::Mission_Command& cmd)
|
||||
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();
|
||||
|
Loading…
Reference in New Issue
Block a user