|
|
|
@ -3692,4 +3692,28 @@ bool SLT_Transition::active() const
@@ -3692,4 +3692,28 @@ bool SLT_Transition::active() const
|
|
|
|
|
return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const |
|
|
|
|
{ |
|
|
|
|
if (quadplane.in_vtol_mode()) { |
|
|
|
|
QuadPlane::position_control_state state = quadplane.poscontrol.get_state(); |
|
|
|
|
if ((state == QuadPlane::position_control_state::QPOS_AIRBRAKE) || (state == QuadPlane::position_control_state::QPOS_POSITION1)) { |
|
|
|
|
return MAV_VTOL_STATE_TRANSITION_TO_MC; |
|
|
|
|
} |
|
|
|
|
return MAV_VTOL_STATE_MC; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
switch (transition_state) { |
|
|
|
|
case TRANSITION_AIRSPEED_WAIT: |
|
|
|
|
case TRANSITION_TIMER: |
|
|
|
|
// we enter this state during assisted flight, not just
|
|
|
|
|
// during a forward transition.
|
|
|
|
|
return MAV_VTOL_STATE_TRANSITION_TO_FW; |
|
|
|
|
|
|
|
|
|
case TRANSITION_DONE: |
|
|
|
|
return MAV_VTOL_STATE_FW; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return MAV_VTOL_STATE_UNDEFINED; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#endif // HAL_QUADPLANE_ENABLED
|
|
|
|
|