2 This program is free software: you can redistribute it and/or modify
3 it under the terms of the GNU General Public License as published by
4 the Free Software Foundation, either version 3 of the License, or
5 (at your option) any later version.
7 This program is distributed in the hope that it will be useful,
8 but WITHOUT ANY WARRANTY; without even the implied warranty of
9 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10 GNU General Public License for more details.
12 You should have received a copy of the GNU General Public License
13 along with this program. If not, see <http://www.gnu.org/licenses/>.
16 #include <GCS_MAVLink/GCS_MAVLink.h>
19 class AP_MotorsMulticopter
;
20 // Transition empty base class
25 Transition(QuadPlane
& _quadplane
, AP_MotorsMulticopter
*& _motors
):quadplane(_quadplane
),motors(_motors
) {};
27 virtual void update() = 0;
29 virtual void VTOL_update() = 0;
31 virtual void force_transition_complete() = 0;
33 virtual bool complete() const = 0;
35 virtual void restart() = 0;
37 virtual uint8_t get_log_transition_state() const = 0;
39 virtual bool active_frwd() const = 0;
41 virtual bool show_vtol_view() const = 0;
43 virtual void set_FW_roll_pitch(int32_t& nav_pitch_cd
, int32_t& nav_roll_cd
) {};
45 virtual bool set_FW_roll_limit(int32_t& roll_limit_cd
) { return false; }
47 virtual bool allow_update_throttle_mix() const { return true; }
49 virtual bool update_yaw_target(float& yaw_target_cd
) { return false; }
51 virtual MAV_VTOL_STATE
get_mav_vtol_state() const = 0;
53 virtual bool set_VTOL_roll_pitch_limit(int32_t& nav_roll_cd
, int32_t& nav_pitch_cd
) { return false; }
55 virtual bool allow_weathervane() { return true; }
57 virtual void set_last_fw_pitch(void) {}
59 virtual bool allow_stick_mixing() const { return true; }
63 // refences for convenience
65 AP_MotorsMulticopter
*& motors
;
69 // Transition for separate left thrust quadplanes
70 class SLT_Transition
: public Transition
74 using Transition::Transition
;
76 void update() override
;
78 void VTOL_update() override
;
80 void force_transition_complete() override
;
82 bool complete() const override
{ return transition_state
== TRANSITION_DONE
; }
84 void restart() override
{ transition_state
= TRANSITION_AIRSPEED_WAIT
; }
86 uint8_t get_log_transition_state() const override
{ return static_cast<uint8_t>(transition_state
); }
88 bool active_frwd() const override
;
90 bool show_vtol_view() const override
;
92 void set_FW_roll_pitch(int32_t& nav_pitch_cd
, int32_t& nav_roll_cd
) override
;
94 bool set_FW_roll_limit(int32_t& roll_limit_cd
) override
;
96 bool allow_update_throttle_mix() const override
;
98 MAV_VTOL_STATE
get_mav_vtol_state() const override
;
100 bool set_VTOL_roll_pitch_limit(int32_t& nav_roll_cd
, int32_t& nav_pitch_cd
) override
;
102 void set_last_fw_pitch(void) override
;
107 TRANSITION_AIRSPEED_WAIT
,
112 // timer start for transition
113 uint32_t transition_start_ms
;
114 uint32_t transition_low_airspeed_ms
;
116 // last throttle value when active
119 // time and pitch angle whe last in a vtol or FW control mode
120 uint32_t last_fw_mode_ms
;
121 int32_t last_fw_nav_pitch_cd
;
123 // tiltrotor tilt angle when airspeed wait transition stage completes
124 float airspeed_reached_tilt
;
126 bool in_forced_transition
;