Browse Source

Plane: Fly a planned abort sequence if available

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
e8885ee1a5
  1. 19
      ArduPlane/GCS_Mavlink.cpp

19
ArduPlane/GCS_Mavlink.cpp

@ -952,7 +952,22 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l @@ -952,7 +952,22 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
return MAV_RESULT_FAILED;
case MAV_CMD_DO_GO_AROUND:
if (plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
{
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
bool is_in_landing = (plane.flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) ||
(mission_id == MAV_CMD_NAV_LAND) ||
(mission_id == MAV_CMD_NAV_VTOL_LAND);
if (is_in_landing) {
// fly a user planned abort pattern if available
if (plane.mission.jump_to_abort_landing_sequence()) {
return MAV_RESULT_ACCEPTED;
}
// only fly a fixed wing abort if we aren't doing quadplane stuff, or potentially
// shooting a quadplane approach
if ((!plane.quadplane.available()) ||
((!plane.quadplane.in_vtol_auto()) &&
(!(plane.quadplane.options & QuadPlane::OPTION_MISSION_LAND_FW_APPROACH)))) {
// Initiate an aborted landing. This will trigger a pitch-up and
// climb-out to a safe altitude holding heading then one of the
// following actions will occur, check for in this order:
@ -969,6 +984,8 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l @@ -969,6 +984,8 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_long_packet(const mavlink_command_l
return MAV_RESULT_ACCEPTED;
}
}
}
}
return MAV_RESULT_FAILED;
case MAV_CMD_DO_FENCE_ENABLE:

Loading…
Cancel
Save