From dca99a9643daeea3b2f46c7080e7e78f2d1154ee Mon Sep 17 00:00:00 2001
From: Michael Day <mday299@yahoo.com>
Date: Tue, 21 Oct 2014 13:44:09 -0700
Subject: [PATCH] GCS_MAVLink: code generation from XML for
 MAV_CMD_CONTINUE_AND_CHANGE_ALT.

---
 .../include/mavlink/v1.0/ardupilotmega/ardupilotmega.h          | 1 +
 .../GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h    | 2 +-
 libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h     | 2 +-
 3 files changed, 3 insertions(+), 2 deletions(-)

diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
index 229037b45..ef1290a50 100644
--- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
+++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
@@ -46,6 +46,7 @@ typedef enum MAV_CMD
 	MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|  */
 	MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|  */
 	MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude|  */
+	MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude.  When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters|  */
 	MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|  */
 	MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|  */
 	MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal|  */
diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
index e8d4ccdc2..d4fb4ecb1 100644
--- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
+++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Nov 18 11:13:07 2014"
+#define MAVLINK_BUILD_DATE "Tue Nov 25 10:42:23 2014"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  
diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h
index 85058be9f..71e71e1e6 100644
--- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h
+++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h
@@ -5,7 +5,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Nov 18 11:13:07 2014"
+#define MAVLINK_BUILD_DATE "Tue Nov 25 10:42:23 2014"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  
-- 
GitLab