Plane: Quadplane: always reset to QPOS_NONE on mode entry

This commit is contained in:
Iampete1 2022-06-21 00:14:45 +01:00 committed by Peter Barker
parent f4df4298a0
commit 0cd1f605f6
2 changed files with 1 additions and 3 deletions

View File

@ -14,9 +14,6 @@ bool ModeQRTL::_enter()
submode = SubMode::RTL;
plane.prev_WP_loc = plane.current_loc;
// clear QPOS state
quadplane.poscontrol.set_state(QuadPlane::QPOS_NONE);
const int32_t RTL_alt_abs_cm = plane.home.alt + quadplane.qrtl_alt*100UL;
if (quadplane.motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) {
// VTOL motors are active, either in VTOL flight or assisted flight

View File

@ -4137,6 +4137,7 @@ void QuadPlane::mode_enter(void)
poscontrol.xy_correction.zero();
poscontrol.velocity_match.zero();
poscontrol.last_velocity_match_ms = 0;
poscontrol.set_state(QuadPlane::QPOS_NONE);
// clear guided takeoff wait on any mode change, but remember the
// state for special behaviour