diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 60ea931218..c8d142bc62 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -726,6 +726,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item case MAV_CMD_NAV_VTOL_LAND: copy_location = true; break; + + case MAV_CMD_DO_VTOL_TRANSITION: + cmd.content.do_vtol_transition.target_state = packet.param1; + break; default: // unrecognised command @@ -1067,6 +1071,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, case MAV_CMD_NAV_VTOL_LAND: copy_location = true; break; + + case MAV_CMD_DO_VTOL_TRANSITION: + packet.param1 = cmd.content.do_vtol_transition.target_state; + break; default: // unrecognised command diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index ad6c9faf1f..51a4f16956 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -156,6 +156,11 @@ public: float horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit }; + // do VTOL transition + struct PACKED Do_VTOL_Transition { + uint8_t target_state; + }; + union PACKED Content { // jump structure Jump_Command jump; @@ -205,6 +210,9 @@ public: // cam trigg distance Altitude_Wait altitude_wait; + // do vtol transition + Do_VTOL_Transition do_vtol_transition; + // location Location location; // Waypoint location