Plane: support DO_VTOL_TRANSITION as a mission item

This commit is contained in:
Andrew Tridgell 2016-04-22 18:22:31 +10:00
parent 3a5e4c80ca
commit 76400a9959
4 changed files with 22 additions and 9 deletions

View File

@ -1626,7 +1626,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break; break;
case MAV_CMD_DO_VTOL_TRANSITION: case MAV_CMD_DO_VTOL_TRANSITION:
result = plane.quadplane.handle_do_vtol_transition(packet); if (!plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)packet.param1)) {
result = MAV_RESULT_FAILED;
} else {
result = MAV_RESULT_ACCEPTED;
}
break; break;
default: default:

View File

@ -218,6 +218,10 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
cmd.content.mount_control.yaw); cmd.content.mount_control.yaw);
break; break;
#endif #endif
case MAV_CMD_DO_VTOL_TRANSITION:
plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state);
break;
} }
return true; return true;

View File

@ -948,33 +948,38 @@ bool QuadPlane::init_mode(void)
/* /*
handle a MAVLink DO_VTOL_TRANSITION handle a MAVLink DO_VTOL_TRANSITION
*/ */
bool QuadPlane::handle_do_vtol_transition(const mavlink_command_long_t &packet) bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state)
{ {
if (!available()) { if (!available()) {
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "VTOL not available"); plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "VTOL not available");
return MAV_RESULT_FAILED; return false;
} }
if (plane.control_mode != AUTO) { if (plane.control_mode != AUTO) {
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "VTOL transition only in AUTO"); plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "VTOL transition only in AUTO");
return MAV_RESULT_FAILED; return false;
} }
switch ((uint8_t)packet.param1) { switch (state) {
case MAV_VTOL_STATE_MC: case MAV_VTOL_STATE_MC:
if (!plane.auto_state.vtol_mode) { if (!plane.auto_state.vtol_mode) {
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Entered VTOL mode"); plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Entered VTOL mode");
} }
plane.auto_state.vtol_mode = true; plane.auto_state.vtol_mode = true;
return MAV_RESULT_ACCEPTED; return true;
case MAV_VTOL_STATE_FW: case MAV_VTOL_STATE_FW:
if (plane.auto_state.vtol_mode) { if (plane.auto_state.vtol_mode) {
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Exited VTOL mode"); plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Exited VTOL mode");
} }
plane.auto_state.vtol_mode = false; plane.auto_state.vtol_mode = false;
return MAV_RESULT_ACCEPTED;
return true;
default:
break;
} }
plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Invalid VTOL mode"); plane.gcs_send_text_fmt(MAV_SEVERITY_NOTICE, "Invalid VTOL mode");
return MAV_RESULT_FAILED; return false;
} }
/* /*

View File

@ -42,7 +42,7 @@ public:
return available() && assisted_flight; return available() && assisted_flight;
} }
bool handle_do_vtol_transition(const mavlink_command_long_t &packet); bool handle_do_vtol_transition(enum MAV_VTOL_STATE state);
bool do_vtol_takeoff(const AP_Mission::Mission_Command& cmd); bool do_vtol_takeoff(const AP_Mission::Mission_Command& cmd);
bool do_vtol_land(const AP_Mission::Mission_Command& cmd); bool do_vtol_land(const AP_Mission::Mission_Command& cmd);