From cb20325593c6b2f6825adc604a2aa2d9ce8e1e59 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 28 Aug 2015 18:33:48 -0700 Subject: [PATCH] AP_Mission: added flight stage FLIGHT_LAND_ABORT - add get_prev_nav_cmd_with_wp_index(). This is different than get_prev_nav_cmd_index() in that it only stores the index if there is a valid lat/lng (+1 squashed commits) - added mission item command to NAV_LAND which is the abort takeoff altitude. If 0 then use last takeoff if available, else use 50m --- libraries/AP_Mission/AP_Mission.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index d6314ab986..bf554fe9c8 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -528,6 +528,7 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP case MAV_CMD_NAV_LAND: // MAV ID: 21 copy_location = true; + cmd.p1 = packet.param1; // abort target altitude(m) (plane only) break; case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22 @@ -859,6 +860,7 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, case MAV_CMD_NAV_LAND: // MAV ID: 21 copy_location = true; + packet.param1 = cmd.p1; // abort target altitude(m) (plane only) break; case MAV_CMD_NAV_TAKEOFF: // MAV ID: 22