diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f32c8e189d..0a41b5551b 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3971,14 +3971,6 @@ bool QuadPlane::is_vtol_land(uint16_t id) const return false; } -/* - return true if we are in any kind of transition - */ -bool QuadPlane::in_transition(void) const -{ - return in_frwd_transition() || in_back_transition(); -} - /* return true if we are in a transition to fwd flight from hover */ @@ -3987,15 +3979,6 @@ bool QuadPlane::in_frwd_transition(void) const return available() && transition->active_frwd(); } -/* - return true if we are in a transition to hover from fwd flight - */ -bool QuadPlane::in_back_transition(void) const -{ - // By default the - return available() && transition->active_back(); -} - /* calculate current stopping distance for a quadplane in fixed wing flight */ @@ -4377,11 +4360,6 @@ bool SLT_Transition::active_frwd() const return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)); } -bool SLT_Transition::active_back() const -{ - return false; -} - /* limit VTOL roll/pitch in POSITION1, POSITION2 and waypoint controller. This serves three roles: 1) an expanding envelope limit on pitch to prevent sudden pitch at the start of a back transition diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 24f25c06e8..ea3bba8779 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -110,9 +110,7 @@ public: // abort landing, only valid when in a VTOL landing descent bool abort_landing(void); - bool in_transition(void) const; bool in_frwd_transition(void) const; - bool in_back_transition(void) const; bool handle_do_vtol_transition(enum MAV_VTOL_STATE state) const; diff --git a/ArduPlane/tailsitter.h b/ArduPlane/tailsitter.h index 422c9bd017..143c26cb9b 100644 --- a/ArduPlane/tailsitter.h +++ b/ArduPlane/tailsitter.h @@ -177,8 +177,6 @@ public: bool active_frwd() const override { return transition_state == TRANSITION_ANGLE_WAIT_FW; } - bool active_back() const override { return transition_state == TRANSITION_ANGLE_WAIT_VTOL; } - bool show_vtol_view() const override; void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd) override; diff --git a/ArduPlane/transition.h b/ArduPlane/transition.h index 75d33948e5..bf0e0dc502 100644 --- a/ArduPlane/transition.h +++ b/ArduPlane/transition.h @@ -38,8 +38,6 @@ public: virtual bool active_frwd() const = 0; - virtual bool active_back() const = 0; - virtual bool show_vtol_view() const = 0; virtual void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd) {}; @@ -89,8 +87,6 @@ public: bool active_frwd() const override; - bool active_back() const override; - bool show_vtol_view() const override; void set_FW_roll_pitch(int32_t& nav_pitch_cd, int32_t& nav_roll_cd) override;