mirror of https://github.com/ArduPilot/ardupilot
Plane: QuadPlane: Clear pilot corrections on mode change to avoid getting stuck in QLand
This commit is contained in:
parent
81a30e8d10
commit
ce0babc8f1
|
@ -9,7 +9,6 @@ bool ModeQLand::_enter()
|
||||||
quadplane.throttle_wait = false;
|
quadplane.throttle_wait = false;
|
||||||
quadplane.setup_target_position();
|
quadplane.setup_target_position();
|
||||||
poscontrol.set_state(QuadPlane::QPOS_LAND_DESCEND);
|
poscontrol.set_state(QuadPlane::QPOS_LAND_DESCEND);
|
||||||
poscontrol.pilot_correction_done = false;
|
|
||||||
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
quadplane.last_land_final_agl = plane.relative_ground_altitude(plane.g.rangefinder_landing);
|
||||||
quadplane.landing_detect.lower_limit_start_ms = 0;
|
quadplane.landing_detect.lower_limit_start_ms = 0;
|
||||||
quadplane.landing_detect.land_start_ms = 0;
|
quadplane.landing_detect.land_start_ms = 0;
|
||||||
|
|
|
@ -4596,6 +4596,11 @@ void QuadPlane::mode_enter(void)
|
||||||
poscontrol.last_velocity_match_ms = 0;
|
poscontrol.last_velocity_match_ms = 0;
|
||||||
poscontrol.set_state(QuadPlane::QPOS_NONE);
|
poscontrol.set_state(QuadPlane::QPOS_NONE);
|
||||||
|
|
||||||
|
// Clear any pilot corrections
|
||||||
|
poscontrol.pilot_correction_done = false;
|
||||||
|
poscontrol.pilot_correction_active = false;
|
||||||
|
poscontrol.target_vel_cms.zero();
|
||||||
|
|
||||||
// clear guided takeoff wait on any mode change, but remember the
|
// clear guided takeoff wait on any mode change, but remember the
|
||||||
// state for special behaviour
|
// state for special behaviour
|
||||||
guided_wait_takeoff_on_mode_enter = guided_wait_takeoff;
|
guided_wait_takeoff_on_mode_enter = guided_wait_takeoff;
|
||||||
|
|
Loading…
Reference in New Issue