diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ce0f38990d..ed2dd092d8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1011,6 +1011,11 @@ void QuadPlane::update_transition(void) assisted_flight = false; } + // if rotors are fully forward then we are not transitioning + if (tiltrotor_fully_fwd()) { + transition_state = TRANSITION_DONE; + } + if (transition_state < TRANSITION_TIMER) { // set a single loop pitch limit in TECS if (plane.ahrs.groundspeed() < 3) { diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index ae166b6abb..89a6903695 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -323,6 +323,7 @@ private: void tiltrotor_continuous_update(void); void tiltrotor_binary_update(void); void tilt_compensate(float *thrust, uint8_t num_motors); + bool tiltrotor_fully_fwd(void); void afs_terminate(void); bool guided_mode_enabled(void); diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index 608334b5eb..ca286c7f09 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -229,3 +229,14 @@ void QuadPlane::tilt_compensate(float *thrust, uint8_t num_motors) } } } + +/* + return true if the rotors are fully tilted forward + */ +bool QuadPlane::tiltrotor_fully_fwd(void) +{ + if (tilt.tilt_mask <= 0) { + return false; + } + return (tilt.current_tilt >= 1); +}