From b36c1b2c3da5528b252cf717b07b7307a829d912 Mon Sep 17 00:00:00 2001
From: Michael Day <mday299@yahoo.com>
Date: Tue, 21 Oct 2014 13:45:24 -0700
Subject: [PATCH] AP_Mission: support for MAV_CMD_CONTINUE_AND_CHANGE_ALT

---
 libraries/AP_Mission/AP_Mission.cpp | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp
index 72bea649d..2703dbf16 100644
--- a/libraries/AP_Mission/AP_Mission.cpp
+++ b/libraries/AP_Mission/AP_Mission.cpp
@@ -512,6 +512,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
         cmd.p1 = packet.param1;                         // minimum pitch (plane only)
         break;
 
+    case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:           // MAV ID: 30
+        copy_location = true;                           // only using alt
+        break;
+
     case MAV_CMD_NAV_SPLINE_WAYPOINT:                   // MAV ID: 82
         copy_location = true;
         cmd.p1 = packet.param1;                         // delay at waypoint in seconds
@@ -777,6 +781,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
         packet.param1 = cmd.p1;                         // minimum pitch (plane only)
         break;
 
+    case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:           // MAV ID: 30
+        copy_location = true;                           //only using alt.
+        break;
+
     case MAV_CMD_NAV_SPLINE_WAYPOINT:                   // MAV ID: 82
         copy_location = true;
         packet.param1 = cmd.p1;                         // delay at waypoint in seconds
-- 
GitLab