aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorilya <ilja@Ilyas-MacBook-Pro.local>2014-10-26 17:14:41 +0200
committerilya <ilja@Ilyas-MacBook-Pro.local>2014-10-26 17:14:41 +0200
commit1f58df364ac415b7f5325efa771c6200494e3615 (patch)
tree1a8b07cbbc82da4b8b03b1d820ef0c3d113501aa
parent1f88f5d5bf3fa73f66907be8e654f9a8a06f88e8 (diff)
downloadpx4-firmware-1f58df364ac415b7f5325efa771c6200494e3615.tar.gz
px4-firmware-1f58df364ac415b7f5325efa771c6200494e3615.tar.bz2
px4-firmware-1f58df364ac415b7f5325efa771c6200494e3615.zip
Mavlink merge phase 1
-rw-r--r--src/include/mavlink/custom/common.xml532
-rw-r--r--src/include/mavlink/custom/headers/airdog/airdog.h16
-rw-r--r--src/include/mavlink/custom/headers/airdog/mavlink.h2
-rw-r--r--src/include/mavlink/custom/headers/airdog/testsuite.h13
-rw-r--r--src/include/mavlink/custom/headers/airdog/version.h4
-rw-r--r--src/include/mavlink/custom/headers/common/common.h123
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink.h2
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion.h40
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion_cov.h322
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_attitude_target.h345
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_autopilot_version.h249
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_battery_status.h284
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_command_int.h497
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_file_transfer_protocol.h273
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int.h10
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int_cov.h441
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_hil_state_quaternion.h10
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_local_position_ned_cov.h417
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_mission_item_int.h521
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_position_target_global_int.h521
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_position_target_local_ned.h521
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_set_attitude_target.h393
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_global_int.h569
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_local_ned.h569
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_sim_state.h40
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_terrain_check.h233
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_terrain_data.h297
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_terrain_report.h353
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_terrain_request.h281
-rw-r--r--src/include/mavlink/custom/headers/common/mavlink_msg_v2_extension.h297
-rw-r--r--src/include/mavlink/custom/headers/common/testsuite.h2043
-rw-r--r--src/include/mavlink/custom/headers/common/version.h4
-rw-r--r--src/include/mavlink/custom/headers/mavlink_conversions.h50
-rw-r--r--src/include/mavlink/custom/headers/mavlink_helpers.h15
-rw-r--r--src/include/mavlink/custom/headers/mavlink_types.h41
-rw-r--r--src/include/mavlink/custom/headers/protocol.h79
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp19
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp13
38 files changed, 9173 insertions, 1266 deletions
diff --git a/src/include/mavlink/custom/common.xml b/src/include/mavlink/custom/common.xml
index 08f782948..655a8de43 100644
--- a/src/include/mavlink/custom/common.xml
+++ b/src/include/mavlink/custom/common.xml
@@ -114,7 +114,14 @@
<entry value="18" name="MAV_TYPE_ONBOARD_CONTROLLER">
<description>Onboard companion controller</description>
</entry>
- </enum>
+ <entry value="19" name="MAV_TYPE_VTOL_DUOROTOR">
+ <description>Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter.</description>
+ </entry>
+ <entry value="20" name="MAV_TYPE_VTOL_QUADROTOR">
+ <description>Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter.</description>
+ </entry>
+ <!-- Entries up to 25 reserved for other VTOL airframes -->
+ </enum>
<!-- WARNING: MAV_ACTION Enum is no longer supported - has been removed. Please use MAV_CMD -->
<enum name="MAV_MODE_FLAG">
<description>These flags encode the MAV mode.</description>
@@ -396,6 +403,9 @@
<entry value="2097152" name="MAV_SYS_STATUS_AHRS">
<description>0x200000 AHRS subsystem health</description>
</entry>
+ <entry value="4194304" name="MAV_SYS_STATUS_TERRAIN">
+ <description>0x400000 Terrain subsystem health</description>
+ </entry>
</enum>
<enum name="MAV_FRAME">
<entry value="0" name="MAV_FRAME_GLOBAL">
@@ -428,6 +438,9 @@
<entry value="9" name="MAV_FRAME_BODY_OFFSET_NED">
<description>Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east.</description>
</entry>
+ <entry value="10" name="MAV_FRAME_GLOBAL_TERRAIN_ALT">
+ <description>Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model.</description>
+ </entry>
</enum>
<enum name="MAVLINK_DATA_STREAM_TYPE">
<entry name="MAVLINK_DATA_STREAM_IMG_JPEG">
@@ -590,26 +603,12 @@
<param index="6">Longitude/Y of goal</param>
<param index="7">Altitude/Z of goal</param>
</entry>
- <entry value="90" name="MAV_CMD_NAV_GUIDED_LIMITS">
- <description>set limits for external control</description>
- <param index="1">timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout</param>
- <param index="2">absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit</param>
- <param index="3">absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit</param>
- <param index="4">horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit</param>
- <param index="5">Empty</param>
- <param index="6">Empty</param>
- <param index="7">Empty</param>
- </entry>
- <entry value="91" name="MAV_CMD_NAV_GUIDED_MASTER">
- <description>set id of master controller</description>
- <param index="1">System ID</param>
- <param index="2">Component ID</param>
- <param index="3">Empty</param>
- <param index="4">Empty</param>
- <param index="5">Empty</param>
- <param index="6">Empty</param>
- <param index="7">Empty</param>
- </entry>
+
+ <!-- IDs 90 and 91 are reserved until the end of 2014,
+ as they were used in some conflicting proposals
+ between PX4 and ardupilot and need to be kept
+ unused to prevent errors -->
+
<entry value="92" name="MAV_CMD_NAV_GUIDED_ENABLE">
<description>hand control over to an external controller</description>
<param index="1">On / Off (> 0.5f on)</param>
@@ -779,7 +778,17 @@
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
- </entry>
+ </entry>
+ <entry value="189" name="MAV_CMD_DO_LAND_START">
+ <description>Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence.</description>
+ <param index="1">Empty</param>
+ <param index="2">Empty</param>
+ <param index="3">Empty</param>
+ <param index="4">Empty</param>
+ <param index="5">Latitude</param>
+ <param index="6">Longitude</param>
+ <param index="7">Empty</param>
+ </entry>
<entry value="190" name="MAV_CMD_DO_RALLY_LAND">
<description>Mission command to perform a landing from a rally point.</description>
<param index="1">Break altitude (meters)</param>
@@ -913,15 +922,37 @@
<entry value="220" name="MAV_CMD_DO_MOUNT_CONTROL_QUAT">
<description>Mission command to control a camera or antenna mount, using a quaternion as reference.</description>
- <param index="1">q1 - quaternion param #1</param>
- <param index="2">q2 - quaternion param #2</param>
- <param index="3">q3 - quaternion param #3</param>
- <param index="4">q4 - quaternion param #4</param>
+ <param index="1">q1 - quaternion param #1, w (1 in null-rotation)</param>
+ <param index="2">q2 - quaternion param #2, x (0 in null-rotation)</param>
+ <param index="3">q3 - quaternion param #3, y (0 in null-rotation)</param>
+ <param index="4">q4 - quaternion param #4, z (0 in null-rotation)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
+ <entry value="221" name="MAV_CMD_DO_GUIDED_MASTER">
+ <description>set id of master controller</description>
+ <param index="1">System ID</param>
+ <param index="2">Component ID</param>
+ <param index="3">Empty</param>
+ <param index="4">Empty</param>
+ <param index="5">Empty</param>
+ <param index="6">Empty</param>
+ <param index="7">Empty</param>
+ </entry>
+
+ <entry value="222" name="MAV_CMD_DO_GUIDED_LIMITS">
+ <description>set limits for external control</description>
+ <param index="1">timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout</param>
+ <param index="2">absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit</param>
+ <param index="3">absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit</param>
+ <param index="4">horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit</param>
+ <param index="5">Empty</param>
+ <param index="6">Empty</param>
+ <param index="7">Empty</param>
+ </entry>
+
<entry value="240" name="MAV_CMD_DO_LAST">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<param index="1">Empty</param>
@@ -944,7 +975,7 @@
</entry>
<entry value="242" name="MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS">
<description>Set sensor offsets. This command will be only accepted if in pre-flight mode.</description>
- <param index="1">Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow</param>
+ <param index="1">Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer</param>
<param index="2">X axis offset (or generic dimension 1), in the sensor's raw units</param>
<param index="3">Y axis offset (or generic dimension 2), in the sensor's raw units</param>
<param index="4">Z axis offset (or generic dimension 3), in the sensor's raw units</param>
@@ -996,6 +1027,64 @@
<param index="1">0:Spektrum</param>
<param index="2">0:Spektrum DSM2, 1:Spektrum DSMX</param>
</entry>
+ <entry value="2000" name="MAV_CMD_IMAGE_START_CAPTURE">
+ <description>Start image capture sequence</description>
+ <param index="1">Duration between two consecutive pictures (in seconds)</param>
+ <param index="2">Number of images to capture total - 0 for unlimited capture</param>
+ <param index="3">Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)</param>
+ </entry>
+
+ <entry value="2001" name="MAV_CMD_IMAGE_STOP_CAPTURE">
+ <description>Stop image capture sequence</description>
+ <param index="1">Reserved</param>
+ <param index="2">Reserved</param>
+ </entry>
+
+ <entry value="2500" name="MAV_CMD_VIDEO_START_CAPTURE">
+ <description>Starts video capture</description>
+ <param index="1">Camera ID (0 for all cameras), 1 for first, 2 for second, etc.</param>
+ <param index="2">Frames per second</param>
+ <param index="3">Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)</param>
+ </entry>
+
+ <entry value="2501" name="MAV_CMD_VIDEO_STOP_CAPTURE">
+ <description>Stop the current video capture</description>
+ <param index="1">Reserved</param>
+ <param index="2">Reserved</param>
+ </entry>
+
+ <entry value="2800" name="MAV_CMD_PANORAMA_CREATE">
+ <description>Create a panorama at the current position</description>
+ <param index="1">Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)</param>
+ <param index="2">Viewing angle vertical of panorama (in degrees)</param>
+ <param index="3">Speed of the horizontal rotation (in degrees per second)</param>
+ <param index="4">Speed of the vertical rotation (in degrees per second)</param>
+ </entry>
+
+ <!-- VALUES FROM 0-40000 are reserved for the common message set. Values from 40000 to UINT16_MAX are available for dialects -->
+
+ <!-- BEGIN of payload range (30000 to 30999) -->
+ <entry value="30001" name="MAV_CMD_PAYLOAD_PREPARE_DEPLOY">
+ <description>Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity.</description>
+ <param index="1">Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.</param>
+ <param index="2">Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.</param>
+ <param index="3">Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.</param>
+ <param index="4">Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.</param>
+ <param index="5">Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT</param>
+ <param index="6">Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT</param>
+ <param index="7">Altitude, in meters WGS84</param>
+ </entry>
+ <entry value="30002" name="MAV_CMD_PAYLOAD_CONTROL_DEPLOY">
+ <description>Control the payload deployment.</description>
+ <param index="1">Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.</param>
+ <param index="2">Reserved</param>
+ <param index="3">Reserved</param>
+ <param index="4">Reserved</param>
+ <param index="5">Reserved</param>
+ <param index="6">Reserved</param>
+ <param index="7">Reserved</param>
+ </entry>
+ <!-- END of payload range (30000 to 30999) -->
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
@@ -1268,6 +1357,93 @@
<description>Ultrasound altimeter, e.g. MaxBotix units</description>
</entry>
</enum>
+ <enum name="MAV_PROTOCOL_CAPABILITY">
+ <description>Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability.</description>
+ <entry value="1" name="MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT">
+ <description>Autopilot supports MISSION float message type.</description>
+ </entry>
+ <entry value="2" name="MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT">
+ <description>Autopilot supports the new param float message type.</description>
+ </entry>
+ <entry value="4" name="MAV_PROTOCOL_CAPABILITY_MISSION_INT">
+ <description>Autopilot supports MISSION_INT scaled integer message type.</description>
+ </entry>
+ <entry value="8" name="MAV_PROTOCOL_CAPABILITY_COMMAND_INT">
+ <description>Autopilot supports COMMAND_INT scaled integer message type.</description>
+ </entry>
+ <entry value="16" name="MAV_PROTOCOL_CAPABILITY_PARAM_UNION">
+ <description>Autopilot supports the new param union message type.</description>
+ </entry>
+ <entry value="32" name="MAV_PROTOCOL_CAPABILITY_FTP">
+ <description>Autopilot supports the new param union message type.</description>
+ </entry>
+ <entry value="64" name="MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET">
+ <description>Autopilot supports commanding attitude offboard.</description>
+ </entry>
+ <entry value="128" name="MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED">
+ <description>Autopilot supports commanding position and velocity targets in local NED frame.</description>
+ </entry>
+ <entry value="256" name="MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT">
+ <description>Autopilot supports commanding position and velocity targets in global scaled integers.</description>
+ </entry>
+ <entry value="512" name="MAV_PROTOCOL_CAPABILITY_TERRAIN">
+ <description>Autopilot supports terrain protocol / data handling.</description>
+ </entry>
+ </enum>
+ <enum name="MAV_ESTIMATOR_TYPE">
+ <description>Enumeration of estimator types</description>
+ <entry value="1" name="MAV_ESTIMATOR_TYPE_NAIVE">
+ <description>This is a naive estimator without any real covariance feedback.</description>
+ </entry>
+ <entry value="2" name="MAV_ESTIMATOR_TYPE_VISION">
+ <description>Computer vision based estimate. Might be up to scale.</description>
+ </entry>
+ <entry value="3" name="MAV_ESTIMATOR_TYPE_VIO">
+ <description>Visual-inertial estimate.</description>
+ </entry>
+ <entry value="4" name="MAV_ESTIMATOR_TYPE_GPS">
+ <description>Plain GPS estimate.</description>
+ </entry>
+ <entry value="5" name="MAV_ESTIMATOR_TYPE_GPS_INS">
+ <description>Estimator integrating GPS and inertial sensing.</description>
+ </entry>
+ </enum>
+ <enum name="MAV_BATTERY_TYPE">
+ <description>Enumeration of battery types</description>
+ <entry value="0" name="MAV_BATTERY_TYPE_UNKNOWN">
+ <description>Not specified.</description>
+ </entry>
+ <entry value="1" name="MAV_BATTERY_TYPE_LIPO">
+ <description>Lithium polymere battery</description>
+ </entry>
+ <entry value="2" name="MAV_BATTERY_TYPE_LIFE">
+ <description>Lithium ferrite battery</description>
+ </entry>
+ <entry value="3" name="MAV_BATTERY_TYPE_LION">
+ <description>Lithium-ION battery</description>
+ </entry>
+ <entry value="4" name="MAV_BATTERY_TYPE_NIMH">
+ <description>Nickel metal hydride battery</description>
+ </entry>
+ </enum>
+ <enum name="MAV_BATTERY_FUNCTION">
+ <description>Enumeration of battery functions</description>
+ <entry value="0" name="MAV_BATTERY_FUNCTION_UNKNOWN">
+ <description>Lithium polymere battery</description>
+ </entry>
+ <entry value="1" name="MAV_BATTERY_FUNCTION_ALL">
+ <description>Battery supports all flight systems</description>
+ </entry>
+ <entry value="2" name="MAV_BATTERY_FUNCTION_PROPULSION">
+ <description>Battery for the propulsion system</description>
+ </entry>
+ <entry value="3" name="MAV_BATTERY_FUNCTION_AVIONICS">
+ <description>Avionics battery</description>
+ </entry>
+ <entry value="4" name="MAV_BATTERY_TYPE_PAYLOAD">
+ <description>Payload battery</description>
+ </entry>
+ </enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
@@ -1331,6 +1507,7 @@
<field type="uint8_t" name="base_mode" enum="MAV_MODE">The new base mode</field>
<field type="uint32_t" name="custom_mode">The new autopilot-specific mode. This field can be ignored by an autopilot.</field>
</message>
+ <!-- reserved for PARAM_VALUE_UNION -->
<message id="20" name="PARAM_REQUEST_READ">
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<field type="uint8_t" name="target_system">System ID</field>
@@ -1434,12 +1611,12 @@
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
</message>
<message id="31" name="ATTITUDE_QUATERNION">
- <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion.</description>
+ <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
- <field type="float" name="q1">Quaternion component 1</field>
- <field type="float" name="q2">Quaternion component 2</field>
- <field type="float" name="q3">Quaternion component 3</field>
- <field type="float" name="q4">Quaternion component 4</field>
+ <field type="float" name="q1">Quaternion component 1, w (1 in null-rotation)</field>
+ <field type="float" name="q2">Quaternion component 2, x (0 in null-rotation)</field>
+ <field type="float" name="q3">Quaternion component 3, y (0 in null-rotation)</field>
+ <field type="float" name="q4">Quaternion component 4, z (0 in null-rotation)</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
@@ -1460,7 +1637,7 @@
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
- <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
+ <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)</field>
<field type="int32_t" name="relative_alt">Altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
@@ -1797,6 +1974,24 @@
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.</field>
</message>
+ <message id="73" name="MISSION_ITEM_INT">
+ <description>Message encoding a mission item. This message is emitted to announce
+ the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See alsohttp://qgroundcontrol.org/mavlink/waypoint_protocol.</description>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint16_t" name="seq">Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).</field>
+ <field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
+ <field type="uint16_t" name="command">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
+ <field type="uint8_t" name="current">false:0, true:1</field>
+ <field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
+ <field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
+ <field type="float" name="param2">PARAM2, see MAV_CMD enum</field>
+ <field type="float" name="param3">PARAM3, see MAV_CMD enum</field>
+ <field type="float" name="param4">PARAM4, see MAV_CMD enum</field>
+ <field type="int32_t" name="x">PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7</field>
+ <field type="int32_t" name="y">PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7</field>
+ <field type="float" name="z">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.</field>
+ </message>
<message id="74" name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
<field type="float" name="airspeed">Current airspeed in m/s</field>
@@ -1806,6 +2001,22 @@
<field type="float" name="alt">Current altitude (MSL), in meters</field>
<field type="float" name="climb">Current climb rate in meters/second</field>
</message>
+ <message id="75" name="COMMAND_INT">
+ <description>Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value.</description>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint8_t" name="frame">The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h</field>
+ <field type="uint16_t" name="command">The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs</field>
+ <field type="uint8_t" name="current">false:0, true:1</field>
+ <field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
+ <field type="float" name="param1">PARAM1, see MAV_CMD enum</field>
+ <field type="float" name="param2">PARAM2, see MAV_CMD enum</field>
+ <field type="float" name="param3">PARAM3, see MAV_CMD enum</field>
+ <field type="float" name="param4">PARAM4, see MAV_CMD enum</field>
+ <field type="int32_t" name="x">PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7</field>
+ <field type="int32_t" name="y">PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7</field>
+ <field type="float" name="z">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.</field>
+ </message>
<message id="76" name="COMMAND_LONG">
<description>Send a command with up to seven parameters to the MAV</description>
<field type="uint8_t" name="target_system">System which should execute the command</field>
@@ -2041,10 +2252,10 @@
<message name="SIM_STATE" id="108">
<description>Status of simulation environment, if used</description>
- <field type="float" name="q1">True attitude quaternion component 1</field>
- <field type="float" name="q2">True attitude quaternion component 2</field>
- <field type="float" name="q3">True attitude quaternion component 3</field>
- <field type="float" name="q4">True attitude quaternion component 4</field>
+ <field type="float" name="q1">True attitude quaternion component 1, w (1 in null-rotation)</field>
+ <field type="float" name="q2">True attitude quaternion component 2, x (0 in null-rotation)</field>
+ <field type="float" name="q3">True attitude quaternion component 3, y (0 in null-rotation)</field>
+ <field type="float" name="q4">True attitude quaternion component 4, z (0 in null-rotation)</field>
<field type="float" name="roll">Attitude roll expressed as Euler angles, not recommended except for human-readable outputs</field>
<field type="float" name="pitch">Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs</field>
<field type="float" name="yaw">Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs</field>
@@ -2125,7 +2336,7 @@
<message id="115" name="HIL_STATE_QUATERNION">
<description>Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
- <field type="float[4]" name="attitude_quaternion">Vehicle attitude expressed as normalized quaternion</field>
+ <field type="float[4]" name="attitude_quaternion">Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)</field>
<field type="float" name="rollspeed">Body frame roll / phi angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Body frame pitch / theta angular speed (rad/s)</field>
<field type="float" name="yawspeed">Body frame yaw / psi angular speed (rad/s)</field>
@@ -2194,7 +2405,7 @@
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
- <message name="GPS_INJECT_DATA" id="123">
+ <message name="GPS_INJECT_DATA" id="123">
<description>data for injecting into the onboard GPS (used for DGPS)</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
@@ -2262,20 +2473,20 @@
<field type="int32_t" name="baseline_c_mm">Current baseline in ECEF z or NED down component in mm.</field>
<field type="uint32_t" name="accuracy">Current estimate of baseline accuracy.</field>
<field type="int32_t" name="iar_num_hypotheses">Current number of integer ambiguity hypotheses.</field>
- </message>
- <message id="130" name="DATA_TRANSMISSION_HANDSHAKE">
- <field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
- <field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>
- <field type="uint16_t" name="width">Width of a matrix or image</field>
- <field type="uint16_t" name="height">Height of a matrix or image</field>
- <field type="uint16_t" name="packets">number of packets beeing sent (set on ACK only)</field>
- <field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
- <field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field>
- </message>
- <message id="131" name="ENCAPSULATED_DATA">
- <field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field>
- <field type="uint8_t[253]" name="data">image data bytes</field>
- </message>
+ </message>
+ <message id="130" name="DATA_TRANSMISSION_HANDSHAKE">
+ <field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
+ <field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>
+ <field type="uint16_t" name="width">Width of a matrix or image</field>
+ <field type="uint16_t" name="height">Height of a matrix or image</field>
+ <field type="uint16_t" name="packets">number of packets beeing sent (set on ACK only)</field>
+ <field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
+ <field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field>
+ </message>
+ <message id="131" name="ENCAPSULATED_DATA">
+ <field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field>
+ <field type="uint8_t[253]" name="data">image data bytes</field>
+ </message>
<message id="132" name="DISTANCE_SENSOR">
<field type="uint32_t" name="time_boot_ms">Time since system boot</field>
<field type="uint16_t" name="min_distance">Minimum distance the sensor can measure in centimeters</field>
@@ -2286,20 +2497,48 @@
<field type="uint8_t" name="orientation">Direction the sensor faces from FIXME enum.</field>
<field type="uint8_t" name="covariance">Measurement covariance in centimeters, 0 for unknown / invalid readings</field>
</message>
- <message id="147" name="BATTERY_STATUS">
- <description>Transmitte battery informations for a accu pack.</description>
- <field type="uint8_t" name="accu_id">Accupack ID</field>
- <field type="uint16_t" name="voltage_cell_1">Battery voltage of cell 1, in millivolts (1 = 1 millivolt)</field>
- <field type="uint16_t" name="voltage_cell_2">Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell</field>
- <field type="uint16_t" name="voltage_cell_3">Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell</field>
- <field type="uint16_t" name="voltage_cell_4">Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell</field>
- <field type="uint16_t" name="voltage_cell_5">Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell</field>
- <field type="uint16_t" name="voltage_cell_6">Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell</field>
- <field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
- <field type="int32_t" name="current_consumed">Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate</field>
- <field type="int32_t" name="energy_consumed">Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate</field>
- <field type="int8_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery</field>
- </message>
+ <message id="133" name="TERRAIN_REQUEST">
+ <description>Request for terrain data and terrain status</description>
+ <field type="int32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
+ <field type="int32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
+ <field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
+ <field type="uint64_t" name="mask" print_format="0x%07x">Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)</field>
+ </message>
+ <message id="134" name="TERRAIN_DATA">
+ <description>Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST</description>
+ <field type="int32_t" name="lat">Latitude of SW corner of first grid (degrees *10^7)</field>
+ <field type="int32_t" name="lon">Longitude of SW corner of first grid (in degrees *10^7)</field>
+ <field type="uint16_t" name="grid_spacing">Grid spacing in meters</field>
+ <field type="uint8_t" name="gridbit">bit within the terrain request mask</field>
+ <field type="int16_t[16]" name="data">Terrain data in meters AMSL</field>
+ </message>
+ <message id="135" name="TERRAIN_CHECK">
+ <description>Request that the vehicle report terrain height at the given location. Used by GCS to check if vehicle has all terrain data needed for a mission.</description>
+ <field type="int32_t" name="lat">Latitude (degrees *10^7)</field>
+ <field type="int32_t" name="lon">Longitude (degrees *10^7)</field>
+ </message>
+ <message id="136" name="TERRAIN_REPORT">
+ <description>Response from a TERRAIN_CHECK request</description>
+ <field type="int32_t" name="lat">Latitude (degrees *10^7)</field>
+ <field type="int32_t" name="lon">Longitude (degrees *10^7)</field>
+ <field type="uint16_t" name="spacing">grid spacing (zero if terrain at this location unavailable)</field>
+ <field type="float" name="terrain_height">Terrain height in meters AMSL</field>
+ <field type="float" name="current_height">Current vehicle height above lat/lon terrain height (meters)</field>
+ <field type="uint16_t" name="pending">Number of 4x4 terrain blocks waiting to be received or read from disk</field>
+ <field type="uint16_t" name="loaded">Number of 4x4 terrain blocks in memory</field>
+ </message>
+ <message id="147" name="BATTERY_STATUS">
+ <description>Battery information</description>
+ <field type="uint8_t" name="id">Battery ID</field>
+ <field type="uint8_t" name="battery_function" enum="MAV_BATTERY_FUNCTION">Function of the battery</field>
+ <field type="uint8_t" name="type" enum="MAV_BATTERY_TYPE">Type (chemistry) of the battery</field>
+ <field type="int16_t" name="temperature">Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.</field>
+ <field type="uint16_t[10]" name="voltages">Battery voltage of cells, in millivolts (1 = 1 millivolt)</field>
+ <field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
+ <field type="int32_t" name="current_consumed">Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate</field>
+ <field type="int32_t" name="energy_consumed">Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate</field>
+ <field type="int8_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery</field>
+ </message>
<message id="148" name="SETPOINT_8DOF">
<description>Set the 8 DOF setpoint for a controller.</description>
<field type="uint8_t" name="target_system">System ID</field>
@@ -2322,8 +2561,163 @@
<field type="float" name="rot_y">Rotational Component in y</field>
<field type="float" name="rot_z">Rotational Component in z</field>
</message>
- <!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
- <message id="249" name="MEMORY_VECT">
+
+ <message id="150" name="AUTOPILOT_VERSION">
+ <description>Version and capability of autopilot software</description>
+ <field type="uint64_t" name="capabilities">bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)</field>
+ <field type="uint32_t" name="version">Firmware version number</field>
+ <field type="uint8_t[8]" name="custom_version">Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.</field>
+ </message>
+
+ <message id="151" name="ATTITUDE_QUATERNION_COV">
+ <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0).</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
+ <field type="float[4]" name="q">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)</field>
+ <field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
+ <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
+ <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
+ <field type="float[9]" name="covariance">Attitude covariance</field>
+ </message>
+
+ <message id="152" name="V2_EXTENSION">
+ <description>Message implementing parts of the V2 payload specs in V1 frames for transitional support.</description>
+ <field type="uint8_t" name="target_network">Network ID (0 for broadcast)</field>
+ <field type="uint8_t" name="target_system">System ID (0 for broadcast)</field>
+ <field type="uint8_t" name="target_component">Component ID (0 for broadcast)</field>
+ <field type="uint16_t" name="message_type">A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.</field>
+ <field type="uint8_t[249]" name="payload">Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.</field>
+ </message>
+ <message id="153" name="GLOBAL_POSITION_INT_COV">
+ <description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
+ <field type="uint64_t" name="time_utc">Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.</field>
+ <field type="uint8_t" name="estimator_type" enum="MAV_ESTIMATOR_TYPE">Class id of the estimator this estimate originated from.</field>
+ <field type="int32_t" name="lat">Latitude, expressed as degrees * 1E7</field>
+ <field type="int32_t" name="lon">Longitude, expressed as degrees * 1E7</field>
+ <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
+ <field type="int32_t" name="relative_alt">Altitude above ground in meters, expressed as * 1000 (millimeters)</field>
+ <field type="float" name="vx">Ground X Speed (Latitude), expressed as m/s</field>
+ <field type="float" name="vy">Ground Y Speed (Longitude), expressed as m/s</field>
+ <field type="float" name="vz">Ground Z Speed (Altitude), expressed as m/s</field>
+ <field type="float[36]" name="covariance">Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)</field>
+ </message>
+ <message id="154" name="LOCAL_POSITION_NED_COV">
+ <description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
+ <field type="uint64_t" name="time_utc">Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.</field>
+ <field type="uint8_t" name="estimator_type" enum="MAV_ESTIMATOR_TYPE">Class id of the estimator this estimate originated from.</field>
+ <field type="float" name="x">X Position</field>
+ <field type="float" name="y">Y Position</field>
+ <field type="float" name="z">Z Position</field>
+ <field type="float" name="vx">X Speed</field>
+ <field type="float" name="vy">Y Speed</field>
+ <field type="float" name="vz">Z Speed</field>
+ <field type="float[36]" name="covariance">Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)</field>
+ </message>
+ <message id="155" name="SET_ATTITUDE_TARGET">
+ <description>Set the vehicle attitude and body angular rates.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint8_t" name="type_mask">Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude</field>
+ <field type="float[4]" name="q">Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
+ <field type="float" name="body_roll_rate">Body roll rate in radians per second</field>
+ <field type="float" name="body_pitch_rate">Body roll rate in radians per second</field>
+ <field type="float" name="body_yaw_rate">Body roll rate in radians per second</field>
+ <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)</field>
+ </message>
+ <message id="156" name="ATTITUDE_TARGET">
+ <description>Set the vehicle attitude and body angular rates.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
+ <field type="uint8_t" name="type_mask">Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude</field>
+ <field type="float[4]" name="q">Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
+ <field type="float" name="body_roll_rate">Body roll rate in radians per second</field>
+ <field type="float" name="body_pitch_rate">Body roll rate in radians per second</field>
+ <field type="float" name="body_yaw_rate">Body roll rate in radians per second</field>
+ <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)</field>
+ </message>
+ <message id="157" name="SET_POSITION_TARGET_LOCAL_NED">
+ <description>Set vehicle position, velocity and acceleration setpoint in local frame.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9</field>
+ <field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
+ <field type="float" name="x">X Position in NED frame in meters</field>
+ <field type="float" name="y">Y Position in NED frame in meters</field>
+ <field type="float" name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
+ <field type="float" name="vx">X velocity in NED frame in meter / s</field>
+ <field type="float" name="vy">Y velocity in NED frame in meter / s</field>
+ <field type="float" name="vz">Z velocity in NED frame in meter / s</field>
+ <field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="yaw">yaw setpoint in rad</field>
+ <field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
+ </message>
+ <message id="158" name="POSITION_TARGET_LOCAL_NED">
+ <description>Set vehicle position, velocity and acceleration setpoint in local frame.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
+ <field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9</field>
+ <field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
+ <field type="float" name="x">X Position in NED frame in meters</field>
+ <field type="float" name="y">Y Position in NED frame in meters</field>
+ <field type="float" name="z">Z Position in NED frame in meters (note, altitude is negative in NED)</field>
+ <field type="float" name="vx">X velocity in NED frame in meter / s</field>
+ <field type="float" name="vy">Y velocity in NED frame in meter / s</field>
+ <field type="float" name="vz">Z velocity in NED frame in meter / s</field>
+ <field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="yaw">yaw setpoint in rad</field>
+ <field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
+ </message>
+ <message id="159" name="SET_POSITION_TARGET_GLOBAL_INT">
+ <description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
+ <field type="uint8_t" name="target_system">System ID</field>
+ <field type="uint8_t" name="target_component">Component ID</field>
+ <field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
+ <field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
+ <field type="int32_t" name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
+ <field type="int32_t" name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
+ <field type="float" name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
+ <field type="float" name="vx">X velocity in NED frame in meter / s</field>
+ <field type="float" name="vy">Y velocity in NED frame in meter / s</field>
+ <field type="float" name="vz">Z velocity in NED frame in meter / s</field>
+ <field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="yaw">yaw setpoint in rad</field>
+ <field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
+ </message>
+ <message id="160" name="POSITION_TARGET_GLOBAL_INT">
+ <description>Set vehicle position, velocity and acceleration setpoint in the WGS84 coordinate system.</description>
+ <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.</field>
+ <field type="uint8_t" name="coordinate_frame" enum="MAV_FRAME">Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11</field>
+ <field type="uint16_t" name="type_mask">Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate</field>
+ <field type="int32_t" name="lat_int">X Position in WGS84 frame in 1e7 * meters</field>
+ <field type="int32_t" name="lon_int">Y Position in WGS84 frame in 1e7 * meters</field>
+ <field type="float" name="alt">Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT</field>
+ <field type="float" name="vx">X velocity in NED frame in meter / s</field>
+ <field type="float" name="vy">Y velocity in NED frame in meter / s</field>
+ <field type="float" name="vz">Z velocity in NED frame in meter / s</field>
+ <field type="float" name="afx">X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afy">Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="afz">Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N</field>
+ <field type="float" name="yaw">yaw setpoint in rad</field>
+ <field type="float" name="yaw_rate">yaw rate setpoint in rad/s</field>
+ </message>
+ <message id="161" name="FILE_TRANSFER_PROTOCOL">
+ <description>File transfer message</description>
+ <field type="uint8_t" name="target_network">Network ID (0 for broadcast)</field>
+ <field type="uint8_t" name="target_system">System ID (0 for broadcast)</field>
+ <field type="uint8_t" name="target_component">Component ID (0 for broadcast)</field>
+ <field type="uint8_t[251]" name="payload">Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.</field>
+ </message>
+<!-- MESSAGE IDs 162 - 240: Space for custom messages in individual projectname_messages.xml files -->
+
+ <message id="249" name="MEMORY_VECT">
<description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="uint16_t" name="address">Starting address of the debug variables</field>
<field type="uint8_t" name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field>
diff --git a/src/include/mavlink/custom/headers/airdog/airdog.h b/src/include/mavlink/custom/headers/airdog/airdog.h
index 641322573..7b55c5204 100644
--- a/src/include/mavlink/custom/headers/airdog/airdog.h
+++ b/src/include/mavlink/custom/headers/airdog/airdog.h
@@ -1,12 +1,12 @@
/** @file
* @brief MAVLink comm protocol generated from airdog.xml
- * @see http://qgroundcontrol.org/mavlink/
+ * @see http://mavlink.org
*/
-#ifndef AIRDOG_H
-#define AIRDOG_H
+#ifndef MAVLINK_AIRDOG_H
+#define MAVLINK_AIRDOG_H
#ifndef MAVLINK_H
- #error Wrong include order: AIRDOG.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
+ #error Wrong include order: MAVLINK_AIRDOG.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
#endif
#ifdef __cplusplus
@@ -16,15 +16,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 32, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 68, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 32, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 68, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 33, 25, 20, 68, 254, 185, 181, 39, 37, 53, 51, 53, 51, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 29, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 79, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 147, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 101, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 86, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 79, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 127, 106, 147, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 101, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 241, 15, 49, 153, 8, 51, 82, 49, 22, 143, 140, 5, 150, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 86, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_TRAJECTORY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_TRAJECTORY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -54,4 +54,4 @@ extern "C" {
#ifdef __cplusplus
}
#endif // __cplusplus
-#endif // AIRDOG_H
+#endif // MAVLINK_AIRDOG_H
diff --git a/src/include/mavlink/custom/headers/airdog/mavlink.h b/src/include/mavlink/custom/headers/airdog/mavlink.h
index ce5fa8bd6..c247cc4b1 100644
--- a/src/include/mavlink/custom/headers/airdog/mavlink.h
+++ b/src/include/mavlink/custom/headers/airdog/mavlink.h
@@ -1,6 +1,6 @@
/** @file
* @brief MAVLink comm protocol built from airdog.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
+ * @see http://mavlink.org
*/
#ifndef MAVLINK_H
#define MAVLINK_H
diff --git a/src/include/mavlink/custom/headers/airdog/testsuite.h b/src/include/mavlink/custom/headers/airdog/testsuite.h
index 042db97f4..4bb957be6 100644
--- a/src/include/mavlink/custom/headers/airdog/testsuite.h
+++ b/src/include/mavlink/custom/headers/airdog/testsuite.h
@@ -30,17 +30,8 @@ static void mavlink_test_trajectory(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_trajectory_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }963498088,
- }963498296,
- }18275,
- }18379,
- }18483,
- }18587,
- }89,
- };
+ 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587,89
+ };
mavlink_trajectory_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
diff --git a/src/include/mavlink/custom/headers/airdog/version.h b/src/include/mavlink/custom/headers/airdog/version.h
index 9cd6be1e3..62a238c5e 100644
--- a/src/include/mavlink/custom/headers/airdog/version.h
+++ b/src/include/mavlink/custom/headers/airdog/version.h
@@ -1,11 +1,11 @@
/** @file
* @brief MAVLink comm protocol built from airdog.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
+ * @see http://mavlink.org
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Oct 21 18:04:04 2014"
+#define MAVLINK_BUILD_DATE "Sun Oct 26 16:00:37 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/src/include/mavlink/custom/headers/common/common.h b/src/include/mavlink/custom/headers/common/common.h
index e75640d16..eaa612740 100644
--- a/src/include/mavlink/custom/headers/common/common.h
+++ b/src/include/mavlink/custom/headers/common/common.h
@@ -1,12 +1,12 @@
/** @file
* @brief MAVLink comm protocol generated from common.xml
- * @see http://qgroundcontrol.org/mavlink/
+ * @see http://mavlink.org
*/
-#ifndef COMMON_H
-#define COMMON_H
+#ifndef MAVLINK_COMMON_H
+#define MAVLINK_COMMON_H
#ifndef MAVLINK_H
- #error Wrong include order: COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
+ #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
#endif
#ifdef __cplusplus
@@ -16,15 +16,15 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 32, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 68, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
+#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 32, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 68, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 33, 25, 20, 68, 254, 185, 181, 39, 37, 53, 51, 53, 51, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 79, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 147, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 101, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
+#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 79, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 127, 106, 147, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 101, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 241, 15, 49, 153, 8, 51, 82, 49, 22, 143, 140, 5, 150, 84, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
+#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
#include "../protocol.h"
@@ -84,7 +84,9 @@ typedef enum MAV_TYPE
MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
MAV_TYPE_KITE=17, /* Flapping wing | */
MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
- MAV_TYPE_ENUM_END=19, /* | */
+ MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */
+ MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */
+ MAV_TYPE_ENUM_END=21, /* | */
} MAV_TYPE;
#endif
@@ -235,7 +237,8 @@ typedef enum MAV_SYS_STATUS_SENSOR
MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */
MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */
MAV_SYS_STATUS_AHRS=2097152, /* 0x200000 AHRS subsystem health | */
- MAV_SYS_STATUS_SENSOR_ENUM_END=2097153, /* | */
+ MAV_SYS_STATUS_TERRAIN=4194304, /* 0x400000 Terrain subsystem health | */
+ MAV_SYS_STATUS_SENSOR_ENUM_END=4194305, /* | */
} MAV_SYS_STATUS_SENSOR;
#endif
@@ -254,7 +257,8 @@ typedef enum MAV_FRAME
MAV_FRAME_LOCAL_OFFSET_NED=7, /* Offset to the current local frame. Anything expressed in this frame should be added to the current local frame position. | */
MAV_FRAME_BODY_NED=8, /* Setpoint in body NED frame. This makes sense if all position control is externalized - e.g. useful to command 2 m/s^2 acceleration to the right. | */
MAV_FRAME_BODY_OFFSET_NED=9, /* Offset in body NED frame. This makes sense if adding setpoints to the current flight path, to avoid an obstacle - e.g. useful to command 2 m/s^2 acceleration to the east. | */
- MAV_FRAME_ENUM_END=10, /* | */
+ MAV_FRAME_GLOBAL_TERRAIN_ALT=10, /* Global coordinate frame with above terrain level altitude. WGS84 coordinate system, relative altitude over terrain with respect to the waypoint coordinate. First value / x: latitude in degrees, second value / y: longitude in degrees, third value / z: positive altitude in meters with 0 being at ground level in terrain model. | */
+ MAV_FRAME_ENUM_END=11, /* | */
} MAV_FRAME;
#endif
@@ -328,8 +332,6 @@ typedef enum MAV_CMD
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| */
- MAV_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
- MAV_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
@@ -347,6 +349,7 @@ typedef enum MAV_CMD
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */
MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
@@ -359,17 +362,26 @@ typedef enum MAV_CMD
MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */
+ MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */
- MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
+ MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- MAV_CMD_ENUM_END=501, /* | */
+ MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */
+ MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */
+ MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */
+ MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */
+ MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */
+ MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters WGS84| */
+ MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
+ MAV_CMD_ENUM_END=30003, /* | */
} MAV_CMD;
#endif
@@ -554,6 +566,67 @@ typedef enum MAV_DISTANCE_SENSOR
} MAV_DISTANCE_SENSOR;
#endif
+/** @brief Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability. */
+#ifndef HAVE_ENUM_MAV_PROTOCOL_CAPABILITY
+#define HAVE_ENUM_MAV_PROTOCOL_CAPABILITY
+typedef enum MAV_PROTOCOL_CAPABILITY
+{
+ MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT=1, /* Autopilot supports MISSION float message type. | */
+ MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT=2, /* Autopilot supports the new param float message type. | */
+ MAV_PROTOCOL_CAPABILITY_MISSION_INT=4, /* Autopilot supports MISSION_INT scaled integer message type. | */
+ MAV_PROTOCOL_CAPABILITY_COMMAND_INT=8, /* Autopilot supports COMMAND_INT scaled integer message type. | */
+ MAV_PROTOCOL_CAPABILITY_PARAM_UNION=16, /* Autopilot supports the new param union message type. | */
+ MAV_PROTOCOL_CAPABILITY_FTP=32, /* Autopilot supports the new param union message type. | */
+ MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET=64, /* Autopilot supports commanding attitude offboard. | */
+ MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED=128, /* Autopilot supports commanding position and velocity targets in local NED frame. | */
+ MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT=256, /* Autopilot supports commanding position and velocity targets in global scaled integers. | */
+ MAV_PROTOCOL_CAPABILITY_TERRAIN=512, /* Autopilot supports terrain protocol / data handling. | */
+ MAV_PROTOCOL_CAPABILITY_ENUM_END=513, /* | */
+} MAV_PROTOCOL_CAPABILITY;
+#endif
+
+/** @brief Enumeration of estimator types */
+#ifndef HAVE_ENUM_MAV_ESTIMATOR_TYPE
+#define HAVE_ENUM_MAV_ESTIMATOR_TYPE
+typedef enum MAV_ESTIMATOR_TYPE
+{
+ MAV_ESTIMATOR_TYPE_NAIVE=1, /* This is a naive estimator without any real covariance feedback. | */
+ MAV_ESTIMATOR_TYPE_VISION=2, /* Computer vision based estimate. Might be up to scale. | */
+ MAV_ESTIMATOR_TYPE_VIO=3, /* Visual-inertial estimate. | */
+ MAV_ESTIMATOR_TYPE_GPS=4, /* Plain GPS estimate. | */
+ MAV_ESTIMATOR_TYPE_GPS_INS=5, /* Estimator integrating GPS and inertial sensing. | */
+ MAV_ESTIMATOR_TYPE_ENUM_END=6, /* | */
+} MAV_ESTIMATOR_TYPE;
+#endif
+
+/** @brief Enumeration of battery types */
+#ifndef HAVE_ENUM_MAV_BATTERY_TYPE
+#define HAVE_ENUM_MAV_BATTERY_TYPE
+typedef enum MAV_BATTERY_TYPE
+{
+ MAV_BATTERY_TYPE_UNKNOWN=0, /* Not specified. | */
+ MAV_BATTERY_TYPE_LIPO=1, /* Lithium polymere battery | */
+ MAV_BATTERY_TYPE_LIFE=2, /* Lithium ferrite battery | */
+ MAV_BATTERY_TYPE_LION=3, /* Lithium-ION battery | */
+ MAV_BATTERY_TYPE_NIMH=4, /* Nickel metal hydride battery | */
+ MAV_BATTERY_TYPE_ENUM_END=5, /* | */
+} MAV_BATTERY_TYPE;
+#endif
+
+/** @brief Enumeration of battery functions */
+#ifndef HAVE_ENUM_MAV_BATTERY_FUNCTION
+#define HAVE_ENUM_MAV_BATTERY_FUNCTION
+typedef enum MAV_BATTERY_FUNCTION
+{
+ MAV_BATTERY_FUNCTION_UNKNOWN=0, /* Lithium polymere battery | */
+ MAV_BATTERY_FUNCTION_ALL=1, /* Battery supports all flight systems | */
+ MAV_BATTERY_FUNCTION_PROPULSION=2, /* Battery for the propulsion system | */
+ MAV_BATTERY_FUNCTION_AVIONICS=3, /* Avionics battery | */
+ MAV_BATTERY_TYPE_PAYLOAD=4, /* Payload battery | */
+ MAV_BATTERY_FUNCTION_ENUM_END=5, /* | */
+} MAV_BATTERY_FUNCTION;
+#endif
+
// MAVLINK VERSION
@@ -626,7 +699,9 @@ typedef enum MAV_DISTANCE_SENSOR
#include "./mavlink_msg_data_stream.h"
#include "./mavlink_msg_manual_control.h"
#include "./mavlink_msg_rc_channels_override.h"
+#include "./mavlink_msg_mission_item_int.h"
#include "./mavlink_msg_vfr_hud.h"
+#include "./mavlink_msg_command_int.h"
#include "./mavlink_msg_command_long.h"
#include "./mavlink_msg_command_ack.h"
#include "./mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h"
@@ -670,9 +745,25 @@ typedef enum MAV_DISTANCE_SENSOR
#include "./mavlink_msg_data_transmission_handshake.h"
#include "./mavlink_msg_encapsulated_data.h"
#include "./mavlink_msg_distance_sensor.h"
+#include "./mavlink_msg_terrain_request.h"
+#include "./mavlink_msg_terrain_data.h"
+#include "./mavlink_msg_terrain_check.h"
+#include "./mavlink_msg_terrain_report.h"
#include "./mavlink_msg_battery_status.h"
#include "./mavlink_msg_setpoint_8dof.h"
#include "./mavlink_msg_setpoint_6dof.h"
+#include "./mavlink_msg_autopilot_version.h"
+#include "./mavlink_msg_attitude_quaternion_cov.h"
+#include "./mavlink_msg_v2_extension.h"
+#include "./mavlink_msg_global_position_int_cov.h"
+#include "./mavlink_msg_local_position_ned_cov.h"
+#include "./mavlink_msg_set_attitude_target.h"
+#include "./mavlink_msg_attitude_target.h"
+#include "./mavlink_msg_set_position_target_local_ned.h"
+#include "./mavlink_msg_position_target_local_ned.h"
+#include "./mavlink_msg_set_position_target_global_int.h"
+#include "./mavlink_msg_position_target_global_int.h"
+#include "./mavlink_msg_file_transfer_protocol.h"
#include "./mavlink_msg_memory_vect.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_named_value_float.h"
@@ -683,4 +774,4 @@ typedef enum MAV_DISTANCE_SENSOR
#ifdef __cplusplus
}
#endif // __cplusplus
-#endif // COMMON_H
+#endif // MAVLINK_COMMON_H
diff --git a/src/include/mavlink/custom/headers/common/mavlink.h b/src/include/mavlink/custom/headers/common/mavlink.h
index 17b732970..f92b2b2db 100644
--- a/src/include/mavlink/custom/headers/common/mavlink.h
+++ b/src/include/mavlink/custom/headers/common/mavlink.h
@@ -1,6 +1,6 @@
/** @file
* @brief MAVLink comm protocol built from common.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
+ * @see http://mavlink.org
*/
#ifndef MAVLINK_H
#define MAVLINK_H
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion.h b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion.h
index 3b97b40d0..35170a71a 100644
--- a/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion.h
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion.h
@@ -5,10 +5,10 @@
typedef struct __mavlink_attitude_quaternion_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
- float q1; ///< Quaternion component 1
- float q2; ///< Quaternion component 2
- float q3; ///< Quaternion component 3
- float q4; ///< Quaternion component 4
+ float q1; ///< Quaternion component 1, w (1 in null-rotation)
+ float q2; ///< Quaternion component 2, x (0 in null-rotation)
+ float q3; ///< Quaternion component 3, y (0 in null-rotation)
+ float q4; ///< Quaternion component 4, z (0 in null-rotation)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
@@ -44,10 +44,10 @@ typedef struct __mavlink_attitude_quaternion_t
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
- * @param q1 Quaternion component 1
- * @param q2 Quaternion component 2
- * @param q3 Quaternion component 3
- * @param q4 Quaternion component 4
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@@ -97,10 +97,10 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
- * @param q1 Quaternion component 1
- * @param q2 Quaternion component 2
- * @param q3 Quaternion component 3
- * @param q4 Quaternion component 4
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@@ -176,10 +176,10 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t syste
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
- * @param q1 Quaternion component 1
- * @param q2 Quaternion component 2
- * @param q3 Quaternion component 3
- * @param q4 Quaternion component 4
+ * @param q1 Quaternion component 1, w (1 in null-rotation)
+ * @param q2 Quaternion component 2, x (0 in null-rotation)
+ * @param q3 Quaternion component 3, y (0 in null-rotation)
+ * @param q4 Quaternion component 4, z (0 in null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
@@ -287,7 +287,7 @@ static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const ma
/**
* @brief Get field q1 from attitude_quaternion message
*
- * @return Quaternion component 1
+ * @return Quaternion component 1, w (1 in null-rotation)
*/
static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
{
@@ -297,7 +297,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message
/**
* @brief Get field q2 from attitude_quaternion message
*
- * @return Quaternion component 2
+ * @return Quaternion component 2, x (0 in null-rotation)
*/
static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
{
@@ -307,7 +307,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message
/**
* @brief Get field q3 from attitude_quaternion message
*
- * @return Quaternion component 3
+ * @return Quaternion component 3, y (0 in null-rotation)
*/
static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
{
@@ -317,7 +317,7 @@ static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message
/**
* @brief Get field q4 from attitude_quaternion message
*
- * @return Quaternion component 4
+ * @return Quaternion component 4, z (0 in null-rotation)
*/
static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
{
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion_cov.h b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion_cov.h
new file mode 100644
index 000000000..52df7836a
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_quaternion_cov.h
@@ -0,0 +1,322 @@
+// MESSAGE ATTITUDE_QUATERNION_COV PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 151
+
+typedef struct __mavlink_attitude_quaternion_cov_t
+{
+ uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
+ float q[4]; ///< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
+ float rollspeed; ///< Roll angular speed (rad/s)
+ float pitchspeed; ///< Pitch angular speed (rad/s)
+ float yawspeed; ///< Yaw angular speed (rad/s)
+ float covariance[9]; ///< Attitude covariance
+} mavlink_attitude_quaternion_cov_t;
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68
+#define MAVLINK_MSG_ID_151_LEN 68
+
+#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153
+#define MAVLINK_MSG_ID_151_CRC 153
+
+#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
+#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
+
+#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
+ "ATTITUDE_QUATERNION_COV", \
+ 6, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
+ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
+ { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
+ { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
+ { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
+ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a attitude_quaternion_cov message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param covariance Attitude covariance
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+ _mav_put_float_array(buf, 4, q, 4);
+ _mav_put_float_array(buf, 32, covariance, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#else
+ mavlink_attitude_quaternion_cov_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.rollspeed = rollspeed;
+ packet.pitchspeed = pitchspeed;
+ packet.yawspeed = yawspeed;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a attitude_quaternion_cov message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param covariance Attitude covariance
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+ _mav_put_float_array(buf, 4, q, 4);
+ _mav_put_float_array(buf, 32, covariance, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#else
+ mavlink_attitude_quaternion_cov_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.rollspeed = rollspeed;
+ packet.pitchspeed = pitchspeed;
+ packet.yawspeed = yawspeed;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a attitude_quaternion_cov struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_quaternion_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
+{
+ return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
+}
+
+/**
+ * @brief Encode a attitude_quaternion_cov struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_quaternion_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
+{
+ return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
+}
+
+/**
+ * @brief Send a attitude_quaternion_cov message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
+ * @param rollspeed Roll angular speed (rad/s)
+ * @param pitchspeed Pitch angular speed (rad/s)
+ * @param yawspeed Yaw angular speed (rad/s)
+ * @param covariance Attitude covariance
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+ _mav_put_float_array(buf, 4, q, 4);
+ _mav_put_float_array(buf, 32, covariance, 9);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+#else
+ mavlink_attitude_quaternion_cov_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.rollspeed = rollspeed;
+ packet.pitchspeed = pitchspeed;
+ packet.yawspeed = yawspeed;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, rollspeed);
+ _mav_put_float(buf, 24, pitchspeed);
+ _mav_put_float(buf, 28, yawspeed);
+ _mav_put_float_array(buf, 4, q, 4);
+ _mav_put_float_array(buf, 32, covariance, 9);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+#else
+ mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->rollspeed = rollspeed;
+ packet->pitchspeed = pitchspeed;
+ packet->yawspeed = yawspeed;
+ mav_array_memcpy(packet->q, q, sizeof(float)*4);
+ mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from attitude_quaternion_cov message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field q from attitude_quaternion_cov message
+ *
+ * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q)
+{
+ return _MAV_RETURN_float_array(msg, q, 4, 4);
+}
+
+/**
+ * @brief Get field rollspeed from attitude_quaternion_cov message
+ *
+ * @return Roll angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field pitchspeed from attitude_quaternion_cov message
+ *
+ * @return Pitch angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field yawspeed from attitude_quaternion_cov message
+ *
+ * @return Yaw angular speed (rad/s)
+ */
+static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field covariance from attitude_quaternion_cov message
+ *
+ * @return Attitude covariance
+ */
+static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
+{
+ return _MAV_RETURN_float_array(msg, covariance, 9, 32);
+}
+
+/**
+ * @brief Decode a attitude_quaternion_cov message into a struct
+ *
+ * @param msg The message to decode
+ * @param attitude_quaternion_cov C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg);
+ mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q);
+ attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg);
+ attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg);
+ attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg);
+ mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance);
+#else
+ memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_target.h b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_target.h
new file mode 100644
index 000000000..b7912515d
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_attitude_target.h
@@ -0,0 +1,345 @@
+// MESSAGE ATTITUDE_TARGET PACKING
+
+#define MAVLINK_MSG_ID_ATTITUDE_TARGET 156
+
+typedef struct __mavlink_attitude_target_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
+ float q[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ float body_roll_rate; ///< Body roll rate in radians per second
+ float body_pitch_rate; ///< Body roll rate in radians per second
+ float body_yaw_rate; ///< Body roll rate in radians per second
+ float thrust; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ uint8_t type_mask; ///< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
+} mavlink_attitude_target_t;
+
+#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
+#define MAVLINK_MSG_ID_156_LEN 37
+
+#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22
+#define MAVLINK_MSG_ID_156_CRC 22
+
+#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4
+
+#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
+ "ATTITUDE_TARGET", \
+ 7, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
+ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
+ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
+ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
+ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
+ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a attitude_target message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#else
+ mavlink_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a attitude_target message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#else
+ mavlink_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a attitude_target struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_target C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
+{
+ return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
+}
+
+/**
+ * @brief Encode a attitude_target struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param attitude_target C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
+{
+ return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
+}
+
+/**
+ * @brief Send a attitude_target message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+#else
+ mavlink_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+#else
+ mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->body_roll_rate = body_roll_rate;
+ packet->body_pitch_rate = body_pitch_rate;
+ packet->body_yaw_rate = body_yaw_rate;
+ packet->thrust = thrust;
+ packet->type_mask = type_mask;
+ mav_array_memcpy(packet->q, q, sizeof(float)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ATTITUDE_TARGET UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from attitude_target message
+ *
+ * @return Timestamp in milliseconds since system boot
+ */
+static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field type_mask from attitude_target message
+ *
+ * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
+ */
+static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field q from attitude_target message
+ *
+ * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ */
+static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q)
+{
+ return _MAV_RETURN_float_array(msg, q, 4, 4);
+}
+
+/**
+ * @brief Get field body_roll_rate from attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field body_pitch_rate from attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field body_yaw_rate from attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field thrust from attitude_target message
+ *
+ * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ */
+static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Decode a attitude_target message into a struct
+ *
+ * @param msg The message to decode
+ * @param attitude_target C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg);
+ mavlink_msg_attitude_target_get_q(msg, attitude_target->q);
+ attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg);
+ attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg);
+ attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg);
+ attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg);
+ attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg);
+#else
+ memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_autopilot_version.h b/src/include/mavlink/custom/headers/common/mavlink_msg_autopilot_version.h
new file mode 100644
index 000000000..257cfb06f
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_autopilot_version.h
@@ -0,0 +1,249 @@
+// MESSAGE AUTOPILOT_VERSION PACKING
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 150
+
+typedef struct __mavlink_autopilot_version_t
+{
+ uint64_t capabilities; ///< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
+ uint32_t version; ///< Firmware version number
+ uint8_t custom_version[8]; ///< Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
+} mavlink_autopilot_version_t;
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 20
+#define MAVLINK_MSG_ID_150_LEN 20
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 49
+#define MAVLINK_MSG_ID_150_CRC 49
+
+#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_CUSTOM_VERSION_LEN 8
+
+#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
+ "AUTOPILOT_VERSION", \
+ 3, \
+ { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
+ { "version", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_autopilot_version_t, version) }, \
+ { "custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 12, offsetof(mavlink_autopilot_version_t, custom_version) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a autopilot_version message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
+ * @param version Firmware version number
+ * @param custom_version Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t capabilities, uint32_t version, const uint8_t *custom_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
+ _mav_put_uint64_t(buf, 0, capabilities);
+ _mav_put_uint32_t(buf, 8, version);
+ _mav_put_uint8_t_array(buf, 12, custom_version, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#else
+ mavlink_autopilot_version_t packet;
+ packet.capabilities = capabilities;
+ packet.version = version;
+ mav_array_memcpy(packet.custom_version, custom_version, sizeof(uint8_t)*8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a autopilot_version message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
+ * @param version Firmware version number
+ * @param custom_version Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t capabilities,uint32_t version,const uint8_t *custom_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
+ _mav_put_uint64_t(buf, 0, capabilities);
+ _mav_put_uint32_t(buf, 8, version);
+ _mav_put_uint8_t_array(buf, 12, custom_version, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#else
+ mavlink_autopilot_version_t packet;
+ packet.capabilities = capabilities;
+ packet.version = version;
+ mav_array_memcpy(packet.custom_version, custom_version, sizeof(uint8_t)*8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a autopilot_version struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param autopilot_version C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
+{
+ return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->version, autopilot_version->custom_version);
+}
+
+/**
+ * @brief Encode a autopilot_version struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param autopilot_version C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
+{
+ return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->version, autopilot_version->custom_version);
+}
+
+/**
+ * @brief Send a autopilot_version message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
+ * @param version Firmware version number
+ * @param custom_version Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t version, const uint8_t *custom_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
+ _mav_put_uint64_t(buf, 0, capabilities);
+ _mav_put_uint32_t(buf, 8, version);
+ _mav_put_uint8_t_array(buf, 12, custom_version, 8);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+#else
+ mavlink_autopilot_version_t packet;
+ packet.capabilities = capabilities;
+ packet.version = version;
+ mav_array_memcpy(packet.custom_version, custom_version, sizeof(uint8_t)*8);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t version, const uint8_t *custom_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, capabilities);
+ _mav_put_uint32_t(buf, 8, version);
+ _mav_put_uint8_t_array(buf, 12, custom_version, 8);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+#else
+ mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
+ packet->capabilities = capabilities;
+ packet->version = version;
+ mav_array_memcpy(packet->custom_version, custom_version, sizeof(uint8_t)*8);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AUTOPILOT_VERSION UNPACKING
+
+
+/**
+ * @brief Get field capabilities from autopilot_version message
+ *
+ * @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
+ */
+static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field version from autopilot_version message
+ *
+ * @return Firmware version number
+ */
+static inline uint32_t mavlink_msg_autopilot_version_get_version(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field custom_version from autopilot_version message
+ *
+ * @return Custom version field, commonly the first 8 bytes (16 characters) of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
+ */
+static inline uint16_t mavlink_msg_autopilot_version_get_custom_version(const mavlink_message_t* msg, uint8_t *custom_version)
+{
+ return _MAV_RETURN_uint8_t_array(msg, custom_version, 8, 12);
+}
+
+/**
+ * @brief Decode a autopilot_version message into a struct
+ *
+ * @param msg The message to decode
+ * @param autopilot_version C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
+ autopilot_version->version = mavlink_msg_autopilot_version_get_version(msg);
+ mavlink_msg_autopilot_version_get_custom_version(msg, autopilot_version->custom_version);
+#else
+ memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_battery_status.h b/src/include/mavlink/custom/headers/common/mavlink_msg_battery_status.h
index faaabf9f7..12371e69f 100644
--- a/src/include/mavlink/custom/headers/common/mavlink_msg_battery_status.h
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_battery_status.h
@@ -6,39 +6,35 @@ typedef struct __mavlink_battery_status_t
{
int32_t current_consumed; ///< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
int32_t energy_consumed; ///< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
- uint16_t voltage_cell_1; ///< Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
- uint16_t voltage_cell_2; ///< Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
- uint16_t voltage_cell_3; ///< Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
- uint16_t voltage_cell_4; ///< Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
- uint16_t voltage_cell_5; ///< Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
- uint16_t voltage_cell_6; ///< Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
+ int16_t temperature; ///< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
+ uint16_t voltages[10]; ///< Battery voltage of cells, in millivolts (1 = 1 millivolt)
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- uint8_t accu_id; ///< Accupack ID
+ uint8_t id; ///< Battery ID
+ uint8_t battery_function; ///< Function of the battery
+ uint8_t type; ///< Type (chemistry) of the battery
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
} mavlink_battery_status_t;
-#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 24
-#define MAVLINK_MSG_ID_147_LEN 24
-
-#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 177
-#define MAVLINK_MSG_ID_147_CRC 177
+#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
+#define MAVLINK_MSG_ID_147_LEN 36
+#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
+#define MAVLINK_MSG_ID_147_CRC 154
+#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
"BATTERY_STATUS", \
- 11, \
+ 9, \
{ { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
- { "voltage_cell_1", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_battery_status_t, voltage_cell_1) }, \
- { "voltage_cell_2", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_battery_status_t, voltage_cell_2) }, \
- { "voltage_cell_3", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_battery_status_t, voltage_cell_3) }, \
- { "voltage_cell_4", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_battery_status_t, voltage_cell_4) }, \
- { "voltage_cell_5", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_battery_status_t, voltage_cell_5) }, \
- { "voltage_cell_6", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_battery_status_t, voltage_cell_6) }, \
- { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_battery_status_t, current_battery) }, \
- { "accu_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_battery_status_t, accu_id) }, \
- { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 23, offsetof(mavlink_battery_status_t, battery_remaining) }, \
+ { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
+ { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
+ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
+ { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
+ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
+ { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
} \
}
@@ -49,13 +45,11 @@ typedef struct __mavlink_battery_status_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param accu_id Accupack ID
- * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
- * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
+ * @param id Battery ID
+ * @param battery_function Function of the battery
+ * @param type Type (chemistry) of the battery
+ * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
+ * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
@@ -63,37 +57,31 @@ typedef struct __mavlink_battery_status_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
+ uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
- _mav_put_uint16_t(buf, 8, voltage_cell_1);
- _mav_put_uint16_t(buf, 10, voltage_cell_2);
- _mav_put_uint16_t(buf, 12, voltage_cell_3);
- _mav_put_uint16_t(buf, 14, voltage_cell_4);
- _mav_put_uint16_t(buf, 16, voltage_cell_5);
- _mav_put_uint16_t(buf, 18, voltage_cell_6);
- _mav_put_int16_t(buf, 20, current_battery);
- _mav_put_uint8_t(buf, 22, accu_id);
- _mav_put_int8_t(buf, 23, battery_remaining);
-
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_int16_t(buf, 30, current_battery);
+ _mav_put_uint8_t(buf, 32, id);
+ _mav_put_uint8_t(buf, 33, battery_function);
+ _mav_put_uint8_t(buf, 34, type);
+ _mav_put_int8_t(buf, 35, battery_remaining);
+ _mav_put_uint16_t_array(buf, 10, voltages, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
- packet.voltage_cell_1 = voltage_cell_1;
- packet.voltage_cell_2 = voltage_cell_2;
- packet.voltage_cell_3 = voltage_cell_3;
- packet.voltage_cell_4 = voltage_cell_4;
- packet.voltage_cell_5 = voltage_cell_5;
- packet.voltage_cell_6 = voltage_cell_6;
+ packet.temperature = temperature;
packet.current_battery = current_battery;
- packet.accu_id = accu_id;
+ packet.id = id;
+ packet.battery_function = battery_function;
+ packet.type = type;
packet.battery_remaining = battery_remaining;
-
+ mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
@@ -111,13 +99,11 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
- * @param accu_id Accupack ID
- * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
- * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
+ * @param id Battery ID
+ * @param battery_function Function of the battery
+ * @param type Type (chemistry) of the battery
+ * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
+ * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
@@ -126,37 +112,31 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
- uint8_t accu_id,uint16_t voltage_cell_1,uint16_t voltage_cell_2,uint16_t voltage_cell_3,uint16_t voltage_cell_4,uint16_t voltage_cell_5,uint16_t voltage_cell_6,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
+ uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
- _mav_put_uint16_t(buf, 8, voltage_cell_1);
- _mav_put_uint16_t(buf, 10, voltage_cell_2);
- _mav_put_uint16_t(buf, 12, voltage_cell_3);
- _mav_put_uint16_t(buf, 14, voltage_cell_4);
- _mav_put_uint16_t(buf, 16, voltage_cell_5);
- _mav_put_uint16_t(buf, 18, voltage_cell_6);
- _mav_put_int16_t(buf, 20, current_battery);
- _mav_put_uint8_t(buf, 22, accu_id);
- _mav_put_int8_t(buf, 23, battery_remaining);
-
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_int16_t(buf, 30, current_battery);
+ _mav_put_uint8_t(buf, 32, id);
+ _mav_put_uint8_t(buf, 33, battery_function);
+ _mav_put_uint8_t(buf, 34, type);
+ _mav_put_int8_t(buf, 35, battery_remaining);
+ _mav_put_uint16_t_array(buf, 10, voltages, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
- packet.voltage_cell_1 = voltage_cell_1;
- packet.voltage_cell_2 = voltage_cell_2;
- packet.voltage_cell_3 = voltage_cell_3;
- packet.voltage_cell_4 = voltage_cell_4;
- packet.voltage_cell_5 = voltage_cell_5;
- packet.voltage_cell_6 = voltage_cell_6;
+ packet.temperature = temperature;
packet.current_battery = current_battery;
- packet.accu_id = accu_id;
+ packet.id = id;
+ packet.battery_function = battery_function;
+ packet.type = type;
packet.battery_remaining = battery_remaining;
-
+ mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
@@ -178,7 +158,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
*/
static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
- return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
+ return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
@@ -192,20 +172,18 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint
*/
static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
- return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
+ return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
* @brief Send a battery_status message
* @param chan MAVLink channel to send the message
*
- * @param accu_id Accupack ID
- * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
- * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
- * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
+ * @param id Battery ID
+ * @param battery_function Function of the battery
+ * @param type Type (chemistry) of the battery
+ * @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
+ * @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
@@ -213,22 +191,19 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id,
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
+static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
- _mav_put_uint16_t(buf, 8, voltage_cell_1);
- _mav_put_uint16_t(buf, 10, voltage_cell_2);
- _mav_put_uint16_t(buf, 12, voltage_cell_3);
- _mav_put_uint16_t(buf, 14, voltage_cell_4);
- _mav_put_uint16_t(buf, 16, voltage_cell_5);
- _mav_put_uint16_t(buf, 18, voltage_cell_6);
- _mav_put_int16_t(buf, 20, current_battery);
- _mav_put_uint8_t(buf, 22, accu_id);
- _mav_put_int8_t(buf, 23, battery_remaining);
-
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_int16_t(buf, 30, current_battery);
+ _mav_put_uint8_t(buf, 32, id);
+ _mav_put_uint8_t(buf, 33, battery_function);
+ _mav_put_uint8_t(buf, 34, type);
+ _mav_put_int8_t(buf, 35, battery_remaining);
+ _mav_put_uint16_t_array(buf, 10, voltages, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
@@ -238,16 +213,13 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
- packet.voltage_cell_1 = voltage_cell_1;
- packet.voltage_cell_2 = voltage_cell_2;
- packet.voltage_cell_3 = voltage_cell_3;
- packet.voltage_cell_4 = voltage_cell_4;
- packet.voltage_cell_5 = voltage_cell_5;
- packet.voltage_cell_6 = voltage_cell_6;
+ packet.temperature = temperature;
packet.current_battery = current_battery;
- packet.accu_id = accu_id;
+ packet.id = id;
+ packet.battery_function = battery_function;
+ packet.type = type;
packet.battery_remaining = battery_remaining;
-
+ mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
@@ -264,22 +236,19 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
-static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
+static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
- _mav_put_uint16_t(buf, 8, voltage_cell_1);
- _mav_put_uint16_t(buf, 10, voltage_cell_2);
- _mav_put_uint16_t(buf, 12, voltage_cell_3);
- _mav_put_uint16_t(buf, 14, voltage_cell_4);
- _mav_put_uint16_t(buf, 16, voltage_cell_5);
- _mav_put_uint16_t(buf, 18, voltage_cell_6);
- _mav_put_int16_t(buf, 20, current_battery);
- _mav_put_uint8_t(buf, 22, accu_id);
- _mav_put_int8_t(buf, 23, battery_remaining);
-
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_int16_t(buf, 30, current_battery);
+ _mav_put_uint8_t(buf, 32, id);
+ _mav_put_uint8_t(buf, 33, battery_function);
+ _mav_put_uint8_t(buf, 34, type);
+ _mav_put_int8_t(buf, 35, battery_remaining);
+ _mav_put_uint16_t_array(buf, 10, voltages, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
@@ -289,16 +258,13 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf;
packet->current_consumed = current_consumed;
packet->energy_consumed = energy_consumed;
- packet->voltage_cell_1 = voltage_cell_1;
- packet->voltage_cell_2 = voltage_cell_2;
- packet->voltage_cell_3 = voltage_cell_3;
- packet->voltage_cell_4 = voltage_cell_4;
- packet->voltage_cell_5 = voltage_cell_5;
- packet->voltage_cell_6 = voltage_cell_6;
+ packet->temperature = temperature;
packet->current_battery = current_battery;
- packet->accu_id = accu_id;
+ packet->id = id;
+ packet->battery_function = battery_function;
+ packet->type = type;
packet->battery_remaining = battery_remaining;
-
+ mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
@@ -314,73 +280,53 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
/**
- * @brief Get field accu_id from battery_status message
- *
- * @return Accupack ID
- */
-static inline uint8_t mavlink_msg_battery_status_get_accu_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 22);
-}
-
-/**
- * @brief Get field voltage_cell_1 from battery_status message
- *
- * @return Battery voltage of cell 1, in millivolts (1 = 1 millivolt)
- */
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 8);
-}
-
-/**
- * @brief Get field voltage_cell_2 from battery_status message
+ * @brief Get field id from battery_status message
*
- * @return Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell
+ * @return Battery ID
*/
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_2(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 10);
+ return _MAV_RETURN_uint8_t(msg, 32);
}
/**
- * @brief Get field voltage_cell_3 from battery_status message
+ * @brief Get field battery_function from battery_status message
*
- * @return Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell
+ * @return Function of the battery
*/
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_3(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 12);
+ return _MAV_RETURN_uint8_t(msg, 33);
}
/**
- * @brief Get field voltage_cell_4 from battery_status message
+ * @brief Get field type from battery_status message
*
- * @return Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell
+ * @return Type (chemistry) of the battery
*/
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_4(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 14);
+ return _MAV_RETURN_uint8_t(msg, 34);
}
/**
- * @brief Get field voltage_cell_5 from battery_status message
+ * @brief Get field temperature from battery_status message
*
- * @return Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell
+ * @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
*/
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_5(const mavlink_message_t* msg)
+static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg)
{
- return _MAV_RETURN_uint16_t(msg, 16);
+ return _MAV_RETURN_int16_t(msg, 8);
}
/**
- * @brief Get field voltage_cell_6 from battery_status message
+ * @brief Get field voltages from battery_status message
*
- * @return Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell
+ * @return Battery voltage of cells, in millivolts (1 = 1 millivolt)
*/
-static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavlink_message_t* msg)
+static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages)
{
- return _MAV_RETURN_uint16_t(msg, 18);
+ return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10);
}
/**
@@ -390,7 +336,7 @@ static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavli
*/
static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg)
{
- return _MAV_RETURN_int16_t(msg, 20);
+ return _MAV_RETURN_int16_t(msg, 30);
}
/**
@@ -420,7 +366,7 @@ static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavli
*/
static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg)
{
- return _MAV_RETURN_int8_t(msg, 23);
+ return _MAV_RETURN_int8_t(msg, 35);
}
/**
@@ -434,14 +380,12 @@ static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* ms
#if MAVLINK_NEED_BYTE_SWAP
battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg);
battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg);
- battery_status->voltage_cell_1 = mavlink_msg_battery_status_get_voltage_cell_1(msg);
- battery_status->voltage_cell_2 = mavlink_msg_battery_status_get_voltage_cell_2(msg);
- battery_status->voltage_cell_3 = mavlink_msg_battery_status_get_voltage_cell_3(msg);
- battery_status->voltage_cell_4 = mavlink_msg_battery_status_get_voltage_cell_4(msg);
- battery_status->voltage_cell_5 = mavlink_msg_battery_status_get_voltage_cell_5(msg);
- battery_status->voltage_cell_6 = mavlink_msg_battery_status_get_voltage_cell_6(msg);
+ battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg);
+ mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages);
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
- battery_status->accu_id = mavlink_msg_battery_status_get_accu_id(msg);
+ battery_status->id = mavlink_msg_battery_status_get_id(msg);
+ battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg);
+ battery_status->type = mavlink_msg_battery_status_get_type(msg);
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
#else
memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_command_int.h b/src/include/mavlink/custom/headers/common/mavlink_msg_command_int.h
new file mode 100644
index 000000000..4713d01e1
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_command_int.h
@@ -0,0 +1,497 @@
+// MESSAGE COMMAND_INT PACKING
+
+#define MAVLINK_MSG_ID_COMMAND_INT 75
+
+typedef struct __mavlink_command_int_t
+{
+ float param1; ///< PARAM1, see MAV_CMD enum
+ float param2; ///< PARAM2, see MAV_CMD enum
+ float param3; ///< PARAM3, see MAV_CMD enum
+ float param4; ///< PARAM4, see MAV_CMD enum
+ int32_t x; ///< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ int32_t y; ///< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
+ float z; ///< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ uint16_t command; ///< The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
+ uint8_t target_system; ///< System ID
+ uint8_t target_component; ///< Component ID
+ uint8_t frame; ///< The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
+ uint8_t current; ///< false:0, true:1
+ uint8_t autocontinue; ///< autocontinue to next wp
+} mavlink_command_int_t;
+
+#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
+#define MAVLINK_MSG_ID_75_LEN 35
+
+#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158
+#define MAVLINK_MSG_ID_75_CRC 158
+
+
+
+#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \
+ "COMMAND_INT", \
+ 13, \
+ { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
+ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
+ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
+ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
+ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
+ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
+ { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a command_int message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, command);
+ _mav_put_uint8_t(buf, 30, target_system);
+ _mav_put_uint8_t(buf, 31, target_component);
+ _mav_put_uint8_t(buf, 32, frame);
+ _mav_put_uint8_t(buf, 33, current);
+ _mav_put_uint8_t(buf, 34, autocontinue);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#else
+ mavlink_command_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMMAND_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a command_int message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_command_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, command);
+ _mav_put_uint8_t(buf, 30, target_system);
+ _mav_put_uint8_t(buf, 31, target_component);
+ _mav_put_uint8_t(buf, 32, frame);
+ _mav_put_uint8_t(buf, 33, current);
+ _mav_put_uint8_t(buf, 34, autocontinue);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#else
+ mavlink_command_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMMAND_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a command_int struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param command_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int)
+{
+ return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z);
+}
+
+/**
+ * @brief Encode a command_int struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param command_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int)
+{
+ return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z);
+}
+
+/**
+ * @brief Send a command_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, command);
+ _mav_put_uint8_t(buf, 30, target_system);
+ _mav_put_uint8_t(buf, 31, target_component);
+ _mav_put_uint8_t(buf, 32, frame);
+ _mav_put_uint8_t(buf, 33, current);
+ _mav_put_uint8_t(buf, 34, autocontinue);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+#else
+ mavlink_command_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, command);
+ _mav_put_uint8_t(buf, 30, target_system);
+ _mav_put_uint8_t(buf, 31, target_component);
+ _mav_put_uint8_t(buf, 32, frame);
+ _mav_put_uint8_t(buf, 33, current);
+ _mav_put_uint8_t(buf, 34, autocontinue);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+#else
+ mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf;
+ packet->param1 = param1;
+ packet->param2 = param2;
+ packet->param3 = param3;
+ packet->param4 = param4;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->command = command;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->frame = frame;
+ packet->current = current;
+ packet->autocontinue = autocontinue;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE COMMAND_INT UNPACKING
+
+
+/**
+ * @brief Get field target_system from command_int message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 30);
+}
+
+/**
+ * @brief Get field target_component from command_int message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 31);
+}
+
+/**
+ * @brief Get field frame from command_int message
+ *
+ * @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
+ */
+static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 32);
+}
+
+/**
+ * @brief Get field command from command_int message
+ *
+ * @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
+ */
+static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 28);
+}
+
+/**
+ * @brief Get field current from command_int message
+ *
+ * @return false:0, true:1
+ */
+static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 33);
+}
+
+/**
+ * @brief Get field autocontinue from command_int message
+ *
+ * @return autocontinue to next wp
+ */
+static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 34);
+}
+
+/**
+ * @brief Get field param1 from command_int message
+ *
+ * @return PARAM1, see MAV_CMD enum
+ */
+static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field param2 from command_int message
+ *
+ * @return PARAM2, see MAV_CMD enum
+ */
+static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field param3 from command_int message
+ *
+ * @return PARAM3, see MAV_CMD enum
+ */
+static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field param4 from command_int message
+ *
+ * @return PARAM4, see MAV_CMD enum
+ */
+static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field x from command_int message
+ *
+ * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ */
+static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field y from command_int message
+ *
+ * @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
+ */
+static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field z from command_int message
+ *
+ * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ */
+static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Decode a command_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param command_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ command_int->param1 = mavlink_msg_command_int_get_param1(msg);
+ command_int->param2 = mavlink_msg_command_int_get_param2(msg);
+ command_int->param3 = mavlink_msg_command_int_get_param3(msg);
+ command_int->param4 = mavlink_msg_command_int_get_param4(msg);
+ command_int->x = mavlink_msg_command_int_get_x(msg);
+ command_int->y = mavlink_msg_command_int_get_y(msg);
+ command_int->z = mavlink_msg_command_int_get_z(msg);
+ command_int->command = mavlink_msg_command_int_get_command(msg);
+ command_int->target_system = mavlink_msg_command_int_get_target_system(msg);
+ command_int->target_component = mavlink_msg_command_int_get_target_component(msg);
+ command_int->frame = mavlink_msg_command_int_get_frame(msg);
+ command_int->current = mavlink_msg_command_int_get_current(msg);
+ command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg);
+#else
+ memcpy(command_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_INT_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_file_transfer_protocol.h b/src/include/mavlink/custom/headers/common/mavlink_msg_file_transfer_protocol.h
new file mode 100644
index 000000000..91e7e501e
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_file_transfer_protocol.h
@@ -0,0 +1,273 @@
+// MESSAGE FILE_TRANSFER_PROTOCOL PACKING
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 161
+
+typedef struct __mavlink_file_transfer_protocol_t
+{
+ uint8_t target_network; ///< Network ID (0 for broadcast)
+ uint8_t target_system; ///< System ID (0 for broadcast)
+ uint8_t target_component; ///< Component ID (0 for broadcast)
+ uint8_t payload[251]; ///< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+} mavlink_file_transfer_protocol_t;
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
+#define MAVLINK_MSG_ID_161_LEN 254
+
+#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84
+#define MAVLINK_MSG_ID_161_CRC 84
+
+#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251
+
+#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \
+ "FILE_TRANSFER_PROTOCOL", \
+ 4, \
+ { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \
+ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a file_transfer_protocol message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
+ _mav_put_uint8_t(buf, 0, target_network);
+ _mav_put_uint8_t(buf, 1, target_system);
+ _mav_put_uint8_t(buf, 2, target_component);
+ _mav_put_uint8_t_array(buf, 3, payload, 251);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#else
+ mavlink_file_transfer_protocol_t packet;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a file_transfer_protocol message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
+ _mav_put_uint8_t(buf, 0, target_network);
+ _mav_put_uint8_t(buf, 1, target_system);
+ _mav_put_uint8_t(buf, 2, target_component);
+ _mav_put_uint8_t_array(buf, 3, payload, 251);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#else
+ mavlink_file_transfer_protocol_t packet;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a file_transfer_protocol struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param file_transfer_protocol C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
+{
+ return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
+}
+
+/**
+ * @brief Encode a file_transfer_protocol struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param file_transfer_protocol C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
+{
+ return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
+}
+
+/**
+ * @brief Send a file_transfer_protocol message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
+ _mav_put_uint8_t(buf, 0, target_network);
+ _mav_put_uint8_t(buf, 1, target_system);
+ _mav_put_uint8_t(buf, 2, target_component);
+ _mav_put_uint8_t_array(buf, 3, payload, 251);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+#else
+ mavlink_file_transfer_protocol_t packet;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_network);
+ _mav_put_uint8_t(buf, 1, target_system);
+ _mav_put_uint8_t(buf, 2, target_component);
+ _mav_put_uint8_t_array(buf, 3, payload, 251);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+#else
+ mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf;
+ packet->target_network = target_network;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING
+
+
+/**
+ * @brief Get field target_network from file_transfer_protocol message
+ *
+ * @return Network ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from file_transfer_protocol message
+ *
+ * @return System ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field target_component from file_transfer_protocol message
+ *
+ * @return Component ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field payload from file_transfer_protocol message
+ *
+ * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ */
+static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload)
+{
+ return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3);
+}
+
+/**
+ * @brief Decode a file_transfer_protocol message into a struct
+ *
+ * @param msg The message to decode
+ * @param file_transfer_protocol C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg);
+ file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg);
+ file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg);
+ mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload);
+#else
+ memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int.h b/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int.h
index 6f06c9d4e..e426e5136 100644
--- a/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int.h
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int.h
@@ -7,7 +7,7 @@ typedef struct __mavlink_global_position_int_t
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
- int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
@@ -52,7 +52,7 @@ typedef struct __mavlink_global_position_int_t
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
- * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -114,7 +114,7 @@ static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, u
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
- * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -202,7 +202,7 @@ static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t syste
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
- * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
@@ -346,7 +346,7 @@ static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_mess
/**
* @brief Get field alt from global_position_int message
*
- * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @return Altitude in meters, expressed as * 1000 (millimeters), WGS84 (not AMSL)
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int_cov.h b/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int_cov.h
new file mode 100644
index 000000000..d2df9b953
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_global_position_int_cov.h
@@ -0,0 +1,441 @@
+// MESSAGE GLOBAL_POSITION_INT_COV PACKING
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 153
+
+typedef struct __mavlink_global_position_int_cov_t
+{
+ uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
+ int32_t lat; ///< Latitude, expressed as degrees * 1E7
+ int32_t lon; ///< Longitude, expressed as degrees * 1E7
+ int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
+ float vx; ///< Ground X Speed (Latitude), expressed as m/s
+ float vy; ///< Ground Y Speed (Longitude), expressed as m/s
+ float vz; ///< Ground Z Speed (Altitude), expressed as m/s
+ float covariance[36]; ///< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ uint8_t estimator_type; ///< Class id of the estimator this estimate originated from.
+} mavlink_global_position_int_cov_t;
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185
+#define MAVLINK_MSG_ID_153_LEN 185
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51
+#define MAVLINK_MSG_ID_153_CRC 51
+
+#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
+
+#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
+ "GLOBAL_POSITION_INT_COV", \
+ 11, \
+ { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
+ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
+ { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
+ { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
+ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
+ { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a global_position_int_cov message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param lat Latitude, expressed as degrees * 1E7
+ * @param lon Longitude, expressed as degrees * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s
+ * @param vy Ground Y Speed (Longitude), expressed as m/s
+ * @param vz Ground Z Speed (Altitude), expressed as m/s
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_int32_t(buf, 20, alt);
+ _mav_put_int32_t(buf, 24, relative_alt);
+ _mav_put_float(buf, 28, vx);
+ _mav_put_float(buf, 32, vy);
+ _mav_put_float(buf, 36, vz);
+ _mav_put_uint8_t(buf, 184, estimator_type);
+ _mav_put_float_array(buf, 40, covariance, 36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#else
+ mavlink_global_position_int_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt = alt;
+ packet.relative_alt = relative_alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a global_position_int_cov message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param lat Latitude, expressed as degrees * 1E7
+ * @param lon Longitude, expressed as degrees * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s
+ * @param vy Ground Y Speed (Longitude), expressed as m/s
+ * @param vz Ground Z Speed (Altitude), expressed as m/s
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_int32_t(buf, 20, alt);
+ _mav_put_int32_t(buf, 24, relative_alt);
+ _mav_put_float(buf, 28, vx);
+ _mav_put_float(buf, 32, vy);
+ _mav_put_float(buf, 36, vz);
+ _mav_put_uint8_t(buf, 184, estimator_type);
+ _mav_put_float_array(buf, 40, covariance, 36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#else
+ mavlink_global_position_int_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt = alt;
+ packet.relative_alt = relative_alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a global_position_int_cov struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param global_position_int_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
+{
+ return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
+}
+
+/**
+ * @brief Encode a global_position_int_cov struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param global_position_int_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
+{
+ return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
+}
+
+/**
+ * @brief Send a global_position_int_cov message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param lat Latitude, expressed as degrees * 1E7
+ * @param lon Longitude, expressed as degrees * 1E7
+ * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
+ * @param vx Ground X Speed (Latitude), expressed as m/s
+ * @param vy Ground Y Speed (Longitude), expressed as m/s
+ * @param vz Ground Z Speed (Altitude), expressed as m/s
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_int32_t(buf, 20, alt);
+ _mav_put_int32_t(buf, 24, relative_alt);
+ _mav_put_float(buf, 28, vx);
+ _mav_put_float(buf, 32, vy);
+ _mav_put_float(buf, 36, vz);
+ _mav_put_uint8_t(buf, 184, estimator_type);
+ _mav_put_float_array(buf, 40, covariance, 36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+#else
+ mavlink_global_position_int_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt = alt;
+ packet.relative_alt = relative_alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_int32_t(buf, 20, alt);
+ _mav_put_int32_t(buf, 24, relative_alt);
+ _mav_put_float(buf, 28, vx);
+ _mav_put_float(buf, 32, vy);
+ _mav_put_float(buf, 36, vz);
+ _mav_put_uint8_t(buf, 184, estimator_type);
+ _mav_put_float_array(buf, 40, covariance, 36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+#else
+ mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf;
+ packet->time_utc = time_utc;
+ packet->time_boot_ms = time_boot_ms;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt = alt;
+ packet->relative_alt = relative_alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->estimator_type = estimator_type;
+ mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from global_position_int_cov message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field time_utc from global_position_int_cov message
+ *
+ * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ */
+static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field estimator_type from global_position_int_cov message
+ *
+ * @return Class id of the estimator this estimate originated from.
+ */
+static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 184);
+}
+
+/**
+ * @brief Get field lat from global_position_int_cov message
+ *
+ * @return Latitude, expressed as degrees * 1E7
+ */
+static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field lon from global_position_int_cov message
+ *
+ * @return Longitude, expressed as degrees * 1E7
+ */
+static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field alt from global_position_int_cov message
+ *
+ * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
+ */
+static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field relative_alt from global_position_int_cov message
+ *
+ * @return Altitude above ground in meters, expressed as * 1000 (millimeters)
+ */
+static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 24);
+}
+
+/**
+ * @brief Get field vx from global_position_int_cov message
+ *
+ * @return Ground X Speed (Latitude), expressed as m/s
+ */
+static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field vy from global_position_int_cov message
+ *
+ * @return Ground Y Speed (Longitude), expressed as m/s
+ */
+static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field vz from global_position_int_cov message
+ *
+ * @return Ground Z Speed (Altitude), expressed as m/s
+ */
+static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field covariance from global_position_int_cov message
+ *
+ * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ */
+static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
+{
+ return _MAV_RETURN_float_array(msg, covariance, 36, 40);
+}
+
+/**
+ * @brief Decode a global_position_int_cov message into a struct
+ *
+ * @param msg The message to decode
+ * @param global_position_int_cov C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg);
+ global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg);
+ global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg);
+ global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg);
+ global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg);
+ global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg);
+ global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg);
+ global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg);
+ global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg);
+ mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance);
+ global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg);
+#else
+ memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_hil_state_quaternion.h b/src/include/mavlink/custom/headers/common/mavlink_msg_hil_state_quaternion.h
index 1a028bdf9..344a19e18 100644
--- a/src/include/mavlink/custom/headers/common/mavlink_msg_hil_state_quaternion.h
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_hil_state_quaternion.h
@@ -5,7 +5,7 @@
typedef struct __mavlink_hil_state_quaternion_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- float attitude_quaternion[4]; ///< Vehicle attitude expressed as normalized quaternion
+ float attitude_quaternion[4]; ///< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
float rollspeed; ///< Body frame roll / phi angular speed (rad/s)
float pitchspeed; ///< Body frame pitch / theta angular speed (rad/s)
float yawspeed; ///< Body frame yaw / psi angular speed (rad/s)
@@ -60,7 +60,7 @@ typedef struct __mavlink_hil_state_quaternion_t
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion
+ * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
@@ -135,7 +135,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id,
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion
+ * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
@@ -236,7 +236,7 @@ static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t syst
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion
+ * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi angular speed (rad/s)
@@ -383,7 +383,7 @@ static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavl
/**
* @brief Get field attitude_quaternion from hil_state_quaternion message
*
- * @return Vehicle attitude expressed as normalized quaternion
+ * @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion)
{
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_local_position_ned_cov.h b/src/include/mavlink/custom/headers/common/mavlink_msg_local_position_ned_cov.h
new file mode 100644
index 000000000..e04e0bda5
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_local_position_ned_cov.h
@@ -0,0 +1,417 @@
+// MESSAGE LOCAL_POSITION_NED_COV PACKING
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 154
+
+typedef struct __mavlink_local_position_ned_cov_t
+{
+ uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
+ float x; ///< X Position
+ float y; ///< Y Position
+ float z; ///< Z Position
+ float vx; ///< X Speed
+ float vy; ///< Y Speed
+ float vz; ///< Z Speed
+ float covariance[36]; ///< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ uint8_t estimator_type; ///< Class id of the estimator this estimate originated from.
+} mavlink_local_position_ned_cov_t;
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 181
+#define MAVLINK_MSG_ID_154_LEN 181
+
+#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 82
+#define MAVLINK_MSG_ID_154_CRC 82
+
+#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 36
+
+#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
+ "LOCAL_POSITION_NED_COV", \
+ 10, \
+ { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
+ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
+ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
+ { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
+ { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a local_position_ned_cov message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_float(buf, 12, x);
+ _mav_put_float(buf, 16, y);
+ _mav_put_float(buf, 20, z);
+ _mav_put_float(buf, 24, vx);
+ _mav_put_float(buf, 28, vy);
+ _mav_put_float(buf, 32, vz);
+ _mav_put_uint8_t(buf, 180, estimator_type);
+ _mav_put_float_array(buf, 36, covariance, 36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#else
+ mavlink_local_position_ned_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a local_position_ned_cov message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_float(buf, 12, x);
+ _mav_put_float(buf, 16, y);
+ _mav_put_float(buf, 20, z);
+ _mav_put_float(buf, 24, vx);
+ _mav_put_float(buf, 28, vy);
+ _mav_put_float(buf, 32, vz);
+ _mav_put_uint8_t(buf, 180, estimator_type);
+ _mav_put_float_array(buf, 36, covariance, 36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#else
+ mavlink_local_position_ned_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a local_position_ned_cov struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param local_position_ned_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
+{
+ return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->covariance);
+}
+
+/**
+ * @brief Encode a local_position_ned_cov struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param local_position_ned_cov C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
+{
+ return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->covariance);
+}
+
+/**
+ * @brief Send a local_position_ned_cov message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp (milliseconds since system boot)
+ * @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ * @param estimator_type Class id of the estimator this estimate originated from.
+ * @param x X Position
+ * @param y Y Position
+ * @param z Z Position
+ * @param vx X Speed
+ * @param vy Y Speed
+ * @param vz Z Speed
+ * @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_float(buf, 12, x);
+ _mav_put_float(buf, 16, y);
+ _mav_put_float(buf, 20, z);
+ _mav_put_float(buf, 24, vx);
+ _mav_put_float(buf, 28, vy);
+ _mav_put_float(buf, 32, vz);
+ _mav_put_uint8_t(buf, 180, estimator_type);
+ _mav_put_float_array(buf, 36, covariance, 36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+#else
+ mavlink_local_position_ned_cov_t packet;
+ packet.time_utc = time_utc;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.estimator_type = estimator_type;
+ mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, const float *covariance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_utc);
+ _mav_put_uint32_t(buf, 8, time_boot_ms);
+ _mav_put_float(buf, 12, x);
+ _mav_put_float(buf, 16, y);
+ _mav_put_float(buf, 20, z);
+ _mav_put_float(buf, 24, vx);
+ _mav_put_float(buf, 28, vy);
+ _mav_put_float(buf, 32, vz);
+ _mav_put_uint8_t(buf, 180, estimator_type);
+ _mav_put_float_array(buf, 36, covariance, 36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+#else
+ mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
+ packet->time_utc = time_utc;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->estimator_type = estimator_type;
+ mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE LOCAL_POSITION_NED_COV UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from local_position_ned_cov message
+ *
+ * @return Timestamp (milliseconds since system boot)
+ */
+static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field time_utc from local_position_ned_cov message
+ *
+ * @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
+ */
+static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field estimator_type from local_position_ned_cov message
+ *
+ * @return Class id of the estimator this estimate originated from.
+ */
+static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 180);
+}
+
+/**
+ * @brief Get field x from local_position_ned_cov message
+ *
+ * @return X Position
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field y from local_position_ned_cov message
+ *
+ * @return Y Position
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field z from local_position_ned_cov message
+ *
+ * @return Z Position
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field vx from local_position_ned_cov message
+ *
+ * @return X Speed
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field vy from local_position_ned_cov message
+ *
+ * @return Y Speed
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field vz from local_position_ned_cov message
+ *
+ * @return Z Speed
+ */
+static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field covariance from local_position_ned_cov message
+ *
+ * @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
+ */
+static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
+{
+ return _MAV_RETURN_float_array(msg, covariance, 36, 36);
+}
+
+/**
+ * @brief Decode a local_position_ned_cov message into a struct
+ *
+ * @param msg The message to decode
+ * @param local_position_ned_cov C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg);
+ local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg);
+ local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg);
+ local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg);
+ local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg);
+ local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg);
+ local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg);
+ local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg);
+ mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance);
+ local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg);
+#else
+ memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_mission_item_int.h b/src/include/mavlink/custom/headers/common/mavlink_msg_mission_item_int.h
new file mode 100644
index 000000000..58d102e7b
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_mission_item_int.h
@@ -0,0 +1,521 @@
+// MESSAGE MISSION_ITEM_INT PACKING
+
+#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73
+
+typedef struct __mavlink_mission_item_int_t
+{
+ float param1; ///< PARAM1, see MAV_CMD enum
+ float param2; ///< PARAM2, see MAV_CMD enum
+ float param3; ///< PARAM3, see MAV_CMD enum
+ float param4; ///< PARAM4, see MAV_CMD enum
+ int32_t x; ///< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ int32_t y; ///< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
+ float z; ///< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ uint16_t seq; ///< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
+ uint16_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ uint8_t target_system; ///< System ID
+ uint8_t target_component; ///< Component ID
+ uint8_t frame; ///< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ uint8_t current; ///< false:0, true:1
+ uint8_t autocontinue; ///< autocontinue to next wp
+} mavlink_mission_item_int_t;
+
+#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37
+#define MAVLINK_MSG_ID_73_LEN 37
+
+#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38
+#define MAVLINK_MSG_ID_73_CRC 38
+
+
+
+#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
+ "MISSION_ITEM_INT", \
+ 14, \
+ { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
+ { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
+ { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
+ { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
+ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
+ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
+ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
+ { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a mission_item_int message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
+ * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, seq);
+ _mav_put_uint16_t(buf, 30, command);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, frame);
+ _mav_put_uint8_t(buf, 35, current);
+ _mav_put_uint8_t(buf, 36, autocontinue);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#else
+ mavlink_mission_item_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.seq = seq;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mission_item_int message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
+ * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, seq);
+ _mav_put_uint16_t(buf, 30, command);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, frame);
+ _mav_put_uint8_t(buf, 35, current);
+ _mav_put_uint8_t(buf, 36, autocontinue);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#else
+ mavlink_mission_item_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.seq = seq;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a mission_item_int struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param mission_item_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
+{
+ return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
+}
+
+/**
+ * @brief Encode a mission_item_int struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param mission_item_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
+{
+ return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
+}
+
+/**
+ * @brief Send a mission_item_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
+ * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ * @param current false:0, true:1
+ * @param autocontinue autocontinue to next wp
+ * @param param1 PARAM1, see MAV_CMD enum
+ * @param param2 PARAM2, see MAV_CMD enum
+ * @param param3 PARAM3, see MAV_CMD enum
+ * @param param4 PARAM4, see MAV_CMD enum
+ * @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ * @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
+ * @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, seq);
+ _mav_put_uint16_t(buf, 30, command);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, frame);
+ _mav_put_uint8_t(buf, 35, current);
+ _mav_put_uint8_t(buf, 36, autocontinue);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+#else
+ mavlink_mission_item_int_t packet;
+ packet.param1 = param1;
+ packet.param2 = param2;
+ packet.param3 = param3;
+ packet.param4 = param4;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.seq = seq;
+ packet.command = command;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.frame = frame;
+ packet.current = current;
+ packet.autocontinue = autocontinue;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, param1);
+ _mav_put_float(buf, 4, param2);
+ _mav_put_float(buf, 8, param3);
+ _mav_put_float(buf, 12, param4);
+ _mav_put_int32_t(buf, 16, x);
+ _mav_put_int32_t(buf, 20, y);
+ _mav_put_float(buf, 24, z);
+ _mav_put_uint16_t(buf, 28, seq);
+ _mav_put_uint16_t(buf, 30, command);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, frame);
+ _mav_put_uint8_t(buf, 35, current);
+ _mav_put_uint8_t(buf, 36, autocontinue);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+#else
+ mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf;
+ packet->param1 = param1;
+ packet->param2 = param2;
+ packet->param3 = param3;
+ packet->param4 = param4;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->seq = seq;
+ packet->command = command;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->frame = frame;
+ packet->current = current;
+ packet->autocontinue = autocontinue;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MISSION_ITEM_INT UNPACKING
+
+
+/**
+ * @brief Get field target_system from mission_item_int message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 32);
+}
+
+/**
+ * @brief Get field target_component from mission_item_int message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 33);
+}
+
+/**
+ * @brief Get field seq from mission_item_int message
+ *
+ * @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
+ */
+static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 28);
+}
+
+/**
+ * @brief Get field frame from mission_item_int message
+ *
+ * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
+ */
+static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 34);
+}
+
+/**
+ * @brief Get field command from mission_item_int message
+ *
+ * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
+ */
+static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 30);
+}
+
+/**
+ * @brief Get field current from mission_item_int message
+ *
+ * @return false:0, true:1
+ */
+static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 35);
+}
+
+/**
+ * @brief Get field autocontinue from mission_item_int message
+ *
+ * @return autocontinue to next wp
+ */
+static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field param1 from mission_item_int message
+ *
+ * @return PARAM1, see MAV_CMD enum
+ */
+static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field param2 from mission_item_int message
+ *
+ * @return PARAM2, see MAV_CMD enum
+ */
+static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field param3 from mission_item_int message
+ *
+ * @return PARAM3, see MAV_CMD enum
+ */
+static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field param4 from mission_item_int message
+ *
+ * @return PARAM4, see MAV_CMD enum
+ */
+static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field x from mission_item_int message
+ *
+ * @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
+ */
+static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field y from mission_item_int message
+ *
+ * @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
+ */
+static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field z from mission_item_int message
+ *
+ * @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
+ */
+static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Decode a mission_item_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param mission_item_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg);
+ mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg);
+ mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg);
+ mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg);
+ mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg);
+ mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg);
+ mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg);
+ mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg);
+ mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg);
+ mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg);
+ mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg);
+ mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg);
+ mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg);
+ mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg);
+#else
+ memcpy(mission_item_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_global_int.h b/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_global_int.h
new file mode 100644
index 000000000..b51f45835
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_global_int.h
@@ -0,0 +1,521 @@
+// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 160
+
+typedef struct __mavlink_position_target_global_int_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ int32_t lat_int; ///< X Position in WGS84 frame in 1e7 * meters
+ int32_t lon_int; ///< Y Position in WGS84 frame in 1e7 * meters
+ float alt; ///< Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ float vx; ///< X velocity in NED frame in meter / s
+ float vy; ///< Y velocity in NED frame in meter / s
+ float vz; ///< Z velocity in NED frame in meter / s
+ float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float yaw; ///< yaw setpoint in rad
+ float yaw_rate; ///< yaw rate setpoint in rad/s
+ uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+} mavlink_position_target_global_int_t;
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
+#define MAVLINK_MSG_ID_160_LEN 51
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150
+#define MAVLINK_MSG_ID_160_CRC 150
+
+
+
+#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
+ "POSITION_TARGET_GLOBAL_INT", \
+ 14, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
+ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
+ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \
+ { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \
+ { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \
+ { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
+ { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a position_target_global_int message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#else
+ mavlink_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a position_target_global_int message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#else
+ mavlink_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a position_target_global_int struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param position_target_global_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
+{
+ return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
+}
+
+/**
+ * @brief Encode a position_target_global_int struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param position_target_global_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
+{
+ return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
+}
+
+/**
+ * @brief Send a position_target_global_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#else
+ mavlink_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#else
+ mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->lat_int = lat_int;
+ packet->lon_int = lon_int;
+ packet->alt = alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->afx = afx;
+ packet->afy = afy;
+ packet->afz = afz;
+ packet->yaw = yaw;
+ packet->yaw_rate = yaw_rate;
+ packet->type_mask = type_mask;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from position_target_global_int message
+ *
+ * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ */
+static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field coordinate_frame from position_target_global_int message
+ *
+ * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ */
+static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field type_mask from position_target_global_int message
+ *
+ * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ */
+static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 48);
+}
+
+/**
+ * @brief Get field lat_int from position_target_global_int message
+ *
+ * @return X Position in WGS84 frame in 1e7 * meters
+ */
+static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field lon_int from position_target_global_int message
+ *
+ * @return Y Position in WGS84 frame in 1e7 * meters
+ */
+static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field alt from position_target_global_int message
+ *
+ * @return Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ */
+static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field vx from position_target_global_int message
+ *
+ * @return X velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field vy from position_target_global_int message
+ *
+ * @return Y velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field vz from position_target_global_int message
+ *
+ * @return Z velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field afx from position_target_global_int message
+ *
+ * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field afy from position_target_global_int message
+ *
+ * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field afz from position_target_global_int message
+ *
+ * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field yaw from position_target_global_int message
+ *
+ * @return yaw setpoint in rad
+ */
+static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field yaw_rate from position_target_global_int message
+ *
+ * @return yaw rate setpoint in rad/s
+ */
+static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a position_target_global_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_target_global_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg);
+ position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg);
+ position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg);
+ position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg);
+ position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg);
+ position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg);
+ position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg);
+ position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg);
+ position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg);
+ position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg);
+ position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg);
+ position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg);
+ position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg);
+ position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg);
+#else
+ memcpy(position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_local_ned.h b/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_local_ned.h
new file mode 100644
index 000000000..5f21f0d76
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_position_target_local_ned.h
@@ -0,0 +1,521 @@
+// MESSAGE POSITION_TARGET_LOCAL_NED PACKING
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 158
+
+typedef struct __mavlink_position_target_local_ned_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
+ float x; ///< X Position in NED frame in meters
+ float y; ///< Y Position in NED frame in meters
+ float z; ///< Z Position in NED frame in meters (note, altitude is negative in NED)
+ float vx; ///< X velocity in NED frame in meter / s
+ float vy; ///< Y velocity in NED frame in meter / s
+ float vz; ///< Z velocity in NED frame in meter / s
+ float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float yaw; ///< yaw setpoint in rad
+ float yaw_rate; ///< yaw rate setpoint in rad/s
+ uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+} mavlink_position_target_local_ned_t;
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
+#define MAVLINK_MSG_ID_158_LEN 51
+
+#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
+#define MAVLINK_MSG_ID_158_CRC 140
+
+
+
+#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
+ "POSITION_TARGET_LOCAL_NED", \
+ 14, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
+ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \
+ { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
+ { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
+ { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
+ { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a position_target_local_ned message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#else
+ mavlink_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a position_target_local_ned message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#else
+ mavlink_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a position_target_local_ned struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param position_target_local_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
+{
+ return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
+}
+
+/**
+ * @brief Encode a position_target_local_ned struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param position_target_local_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
+{
+ return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
+}
+
+/**
+ * @brief Send a position_target_local_ned message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#else
+ mavlink_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#else
+ mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->afx = afx;
+ packet->afy = afy;
+ packet->afz = afz;
+ packet->yaw = yaw;
+ packet->yaw_rate = yaw_rate;
+ packet->type_mask = type_mask;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from position_target_local_ned message
+ *
+ * @return Timestamp in milliseconds since system boot
+ */
+static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field coordinate_frame from position_target_local_ned message
+ *
+ * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ */
+static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field type_mask from position_target_local_ned message
+ *
+ * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ */
+static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 48);
+}
+
+/**
+ * @brief Get field x from position_target_local_ned message
+ *
+ * @return X Position in NED frame in meters
+ */
+static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field y from position_target_local_ned message
+ *
+ * @return Y Position in NED frame in meters
+ */
+static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field z from position_target_local_ned message
+ *
+ * @return Z Position in NED frame in meters (note, altitude is negative in NED)
+ */
+static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field vx from position_target_local_ned message
+ *
+ * @return X velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field vy from position_target_local_ned message
+ *
+ * @return Y velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field vz from position_target_local_ned message
+ *
+ * @return Z velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field afx from position_target_local_ned message
+ *
+ * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field afy from position_target_local_ned message
+ *
+ * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field afz from position_target_local_ned message
+ *
+ * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field yaw from position_target_local_ned message
+ *
+ * @return yaw setpoint in rad
+ */
+static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field yaw_rate from position_target_local_ned message
+ *
+ * @return yaw rate setpoint in rad/s
+ */
+static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a position_target_local_ned message into a struct
+ *
+ * @param msg The message to decode
+ * @param position_target_local_ned C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg);
+ position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg);
+ position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg);
+ position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg);
+ position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg);
+ position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg);
+ position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg);
+ position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg);
+ position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg);
+ position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg);
+ position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg);
+ position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg);
+ position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg);
+ position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg);
+#else
+ memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_set_attitude_target.h b/src/include/mavlink/custom/headers/common/mavlink_msg_set_attitude_target.h
new file mode 100644
index 000000000..792e885d6
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_set_attitude_target.h
@@ -0,0 +1,393 @@
+// MESSAGE SET_ATTITUDE_TARGET PACKING
+
+#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 155
+
+typedef struct __mavlink_set_attitude_target_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
+ float q[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ float body_roll_rate; ///< Body roll rate in radians per second
+ float body_pitch_rate; ///< Body roll rate in radians per second
+ float body_yaw_rate; ///< Body roll rate in radians per second
+ float thrust; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ uint8_t target_system; ///< System ID
+ uint8_t target_component; ///< Component ID
+ uint8_t type_mask; ///< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
+} mavlink_set_attitude_target_t;
+
+#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39
+#define MAVLINK_MSG_ID_155_LEN 39
+
+#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49
+#define MAVLINK_MSG_ID_155_CRC 49
+
+#define MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4
+
+#define MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET { \
+ "SET_ATTITUDE_TARGET", \
+ 9, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \
+ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \
+ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \
+ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \
+ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \
+ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a set_attitude_target message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#else
+ mavlink_set_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a set_attitude_target message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#else
+ mavlink_set_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_ATTITUDE_TARGET;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a set_attitude_target struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param set_attitude_target C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target)
+{
+ return mavlink_msg_set_attitude_target_pack(system_id, component_id, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust);
+}
+
+/**
+ * @brief Encode a set_attitude_target struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param set_attitude_target C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_attitude_target_t* set_attitude_target)
+{
+ return mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, chan, msg, set_attitude_target->time_boot_ms, set_attitude_target->target_system, set_attitude_target->target_component, set_attitude_target->type_mask, set_attitude_target->q, set_attitude_target->body_roll_rate, set_attitude_target->body_pitch_rate, set_attitude_target->body_yaw_rate, set_attitude_target->thrust);
+}
+
+/**
+ * @brief Send a set_attitude_target message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
+ * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ * @param body_roll_rate Body roll rate in radians per second
+ * @param body_pitch_rate Body roll rate in radians per second
+ * @param body_yaw_rate Body roll rate in radians per second
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+#else
+ mavlink_set_attitude_target_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.body_roll_rate = body_roll_rate;
+ packet.body_pitch_rate = body_pitch_rate;
+ packet.body_yaw_rate = body_yaw_rate;
+ packet.thrust = thrust;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type_mask = type_mask;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 20, body_roll_rate);
+ _mav_put_float(buf, 24, body_pitch_rate);
+ _mav_put_float(buf, 28, body_yaw_rate);
+ _mav_put_float(buf, 32, thrust);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, type_mask);
+ _mav_put_float_array(buf, 4, q, 4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+#else
+ mavlink_set_attitude_target_t *packet = (mavlink_set_attitude_target_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->body_roll_rate = body_roll_rate;
+ packet->body_pitch_rate = body_pitch_rate;
+ packet->body_yaw_rate = body_yaw_rate;
+ packet->thrust = thrust;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->type_mask = type_mask;
+ mav_array_memcpy(packet->q, q, sizeof(float)*4);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_ATTITUDE_TARGET UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from set_attitude_target message
+ *
+ * @return Timestamp in milliseconds since system boot
+ */
+static inline uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from set_attitude_target message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_attitude_target_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field target_component from set_attitude_target message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_attitude_target_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 37);
+}
+
+/**
+ * @brief Get field type_mask from set_attitude_target message
+ *
+ * @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude
+ */
+static inline uint8_t mavlink_msg_set_attitude_target_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 38);
+}
+
+/**
+ * @brief Get field q from set_attitude_target message
+ *
+ * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
+ */
+static inline uint16_t mavlink_msg_set_attitude_target_get_q(const mavlink_message_t* msg, float *q)
+{
+ return _MAV_RETURN_float_array(msg, q, 4, 4);
+}
+
+/**
+ * @brief Get field body_roll_rate from set_attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_set_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field body_pitch_rate from set_attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_set_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field body_yaw_rate from set_attitude_target message
+ *
+ * @return Body roll rate in radians per second
+ */
+static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field thrust from set_attitude_target message
+ *
+ * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ */
+static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Decode a set_attitude_target message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_attitude_target C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_attitude_target_decode(const mavlink_message_t* msg, mavlink_set_attitude_target_t* set_attitude_target)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ set_attitude_target->time_boot_ms = mavlink_msg_set_attitude_target_get_time_boot_ms(msg);
+ mavlink_msg_set_attitude_target_get_q(msg, set_attitude_target->q);
+ set_attitude_target->body_roll_rate = mavlink_msg_set_attitude_target_get_body_roll_rate(msg);
+ set_attitude_target->body_pitch_rate = mavlink_msg_set_attitude_target_get_body_pitch_rate(msg);
+ set_attitude_target->body_yaw_rate = mavlink_msg_set_attitude_target_get_body_yaw_rate(msg);
+ set_attitude_target->thrust = mavlink_msg_set_attitude_target_get_thrust(msg);
+ set_attitude_target->target_system = mavlink_msg_set_attitude_target_get_target_system(msg);
+ set_attitude_target->target_component = mavlink_msg_set_attitude_target_get_target_component(msg);
+ set_attitude_target->type_mask = mavlink_msg_set_attitude_target_get_type_mask(msg);
+#else
+ memcpy(set_attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_global_int.h b/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_global_int.h
new file mode 100644
index 000000000..52c6b8244
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_global_int.h
@@ -0,0 +1,569 @@
+// MESSAGE SET_POSITION_TARGET_GLOBAL_INT PACKING
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT 159
+
+typedef struct __mavlink_set_position_target_global_int_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ int32_t lat_int; ///< X Position in WGS84 frame in 1e7 * meters
+ int32_t lon_int; ///< Y Position in WGS84 frame in 1e7 * meters
+ float alt; ///< Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ float vx; ///< X velocity in NED frame in meter / s
+ float vy; ///< Y velocity in NED frame in meter / s
+ float vz; ///< Z velocity in NED frame in meter / s
+ float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float yaw; ///< yaw setpoint in rad
+ float yaw_rate; ///< yaw rate setpoint in rad/s
+ uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ uint8_t target_system; ///< System ID
+ uint8_t target_component; ///< Component ID
+ uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+} mavlink_set_position_target_global_int_t;
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN 53
+#define MAVLINK_MSG_ID_159_LEN 53
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC 5
+#define MAVLINK_MSG_ID_159_CRC 5
+
+
+
+#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT { \
+ "SET_POSITION_TARGET_GLOBAL_INT", \
+ 16, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_global_int_t, time_boot_ms) }, \
+ { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_position_target_global_int_t, lat_int) }, \
+ { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_position_target_global_int_t, lon_int) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_global_int_t, alt) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_global_int_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_global_int_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_global_int_t, vz) }, \
+ { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_global_int_t, afx) }, \
+ { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_global_int_t, afy) }, \
+ { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_global_int_t, afz) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_global_int_t, yaw) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_global_int_t, yaw_rate) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_global_int_t, type_mask) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_global_int_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_global_int_t, target_component) }, \
+ { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_global_int_t, coordinate_frame) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a set_position_target_global_int message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#else
+ mavlink_set_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a set_position_target_global_int message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#else
+ mavlink_set_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a set_position_target_global_int struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param set_position_target_global_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
+{
+ return mavlink_msg_set_position_target_global_int_pack(system_id, component_id, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
+}
+
+/**
+ * @brief Encode a set_position_target_global_int struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param set_position_target_global_int C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_global_int_t* set_position_target_global_int)
+{
+ return mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, chan, msg, set_position_target_global_int->time_boot_ms, set_position_target_global_int->target_system, set_position_target_global_int->target_component, set_position_target_global_int->coordinate_frame, set_position_target_global_int->type_mask, set_position_target_global_int->lat_int, set_position_target_global_int->lon_int, set_position_target_global_int->alt, set_position_target_global_int->vx, set_position_target_global_int->vy, set_position_target_global_int->vz, set_position_target_global_int->afx, set_position_target_global_int->afy, set_position_target_global_int->afz, set_position_target_global_int->yaw, set_position_target_global_int->yaw_rate);
+}
+
+/**
+ * @brief Send a set_position_target_global_int message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param lat_int X Position in WGS84 frame in 1e7 * meters
+ * @param lon_int Y Position in WGS84 frame in 1e7 * meters
+ * @param alt Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#else
+ mavlink_set_position_target_global_int_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat_int = lat_int;
+ packet.lon_int = lon_int;
+ packet.alt = alt;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat_int);
+ _mav_put_int32_t(buf, 8, lon_int);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#else
+ mavlink_set_position_target_global_int_t *packet = (mavlink_set_position_target_global_int_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->lat_int = lat_int;
+ packet->lon_int = lon_int;
+ packet->alt = alt;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->afx = afx;
+ packet->afy = afy;
+ packet->afz = afz;
+ packet->yaw = yaw;
+ packet->yaw_rate = yaw_rate;
+ packet->type_mask = type_mask;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_POSITION_TARGET_GLOBAL_INT UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from set_position_target_global_int message
+ *
+ * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
+ */
+static inline uint32_t mavlink_msg_set_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from set_position_target_global_int message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field target_component from set_position_target_global_int message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_position_target_global_int_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 51);
+}
+
+/**
+ * @brief Get field coordinate_frame from set_position_target_global_int message
+ *
+ * @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
+ */
+static inline uint8_t mavlink_msg_set_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 52);
+}
+
+/**
+ * @brief Get field type_mask from set_position_target_global_int message
+ *
+ * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ */
+static inline uint16_t mavlink_msg_set_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 48);
+}
+
+/**
+ * @brief Get field lat_int from set_position_target_global_int message
+ *
+ * @return X Position in WGS84 frame in 1e7 * meters
+ */
+static inline int32_t mavlink_msg_set_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field lon_int from set_position_target_global_int message
+ *
+ * @return Y Position in WGS84 frame in 1e7 * meters
+ */
+static inline int32_t mavlink_msg_set_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field alt from set_position_target_global_int message
+ *
+ * @return Altitude in meters in WGS84 altitude, not AMSL if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field vx from set_position_target_global_int message
+ *
+ * @return X velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field vy from set_position_target_global_int message
+ *
+ * @return Y velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field vz from set_position_target_global_int message
+ *
+ * @return Z velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field afx from set_position_target_global_int message
+ *
+ * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_afx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field afy from set_position_target_global_int message
+ *
+ * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_afy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field afz from set_position_target_global_int message
+ *
+ * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_afz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field yaw from set_position_target_global_int message
+ *
+ * @return yaw setpoint in rad
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field yaw_rate from set_position_target_global_int message
+ *
+ * @return yaw rate setpoint in rad/s
+ */
+static inline float mavlink_msg_set_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a set_position_target_global_int message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_position_target_global_int C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_set_position_target_global_int_t* set_position_target_global_int)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ set_position_target_global_int->time_boot_ms = mavlink_msg_set_position_target_global_int_get_time_boot_ms(msg);
+ set_position_target_global_int->lat_int = mavlink_msg_set_position_target_global_int_get_lat_int(msg);
+ set_position_target_global_int->lon_int = mavlink_msg_set_position_target_global_int_get_lon_int(msg);
+ set_position_target_global_int->alt = mavlink_msg_set_position_target_global_int_get_alt(msg);
+ set_position_target_global_int->vx = mavlink_msg_set_position_target_global_int_get_vx(msg);
+ set_position_target_global_int->vy = mavlink_msg_set_position_target_global_int_get_vy(msg);
+ set_position_target_global_int->vz = mavlink_msg_set_position_target_global_int_get_vz(msg);
+ set_position_target_global_int->afx = mavlink_msg_set_position_target_global_int_get_afx(msg);
+ set_position_target_global_int->afy = mavlink_msg_set_position_target_global_int_get_afy(msg);
+ set_position_target_global_int->afz = mavlink_msg_set_position_target_global_int_get_afz(msg);
+ set_position_target_global_int->yaw = mavlink_msg_set_position_target_global_int_get_yaw(msg);
+ set_position_target_global_int->yaw_rate = mavlink_msg_set_position_target_global_int_get_yaw_rate(msg);
+ set_position_target_global_int->type_mask = mavlink_msg_set_position_target_global_int_get_type_mask(msg);
+ set_position_target_global_int->target_system = mavlink_msg_set_position_target_global_int_get_target_system(msg);
+ set_position_target_global_int->target_component = mavlink_msg_set_position_target_global_int_get_target_component(msg);
+ set_position_target_global_int->coordinate_frame = mavlink_msg_set_position_target_global_int_get_coordinate_frame(msg);
+#else
+ memcpy(set_position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_local_ned.h b/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_local_ned.h
new file mode 100644
index 000000000..81d9bb6aa
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_set_position_target_local_ned.h
@@ -0,0 +1,569 @@
+// MESSAGE SET_POSITION_TARGET_LOCAL_NED PACKING
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED 157
+
+typedef struct __mavlink_set_position_target_local_ned_t
+{
+ uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
+ float x; ///< X Position in NED frame in meters
+ float y; ///< Y Position in NED frame in meters
+ float z; ///< Z Position in NED frame in meters (note, altitude is negative in NED)
+ float vx; ///< X velocity in NED frame in meter / s
+ float vy; ///< Y velocity in NED frame in meter / s
+ float vz; ///< Z velocity in NED frame in meter / s
+ float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ float yaw; ///< yaw setpoint in rad
+ float yaw_rate; ///< yaw rate setpoint in rad/s
+ uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ uint8_t target_system; ///< System ID
+ uint8_t target_component; ///< Component ID
+ uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+} mavlink_set_position_target_local_ned_t;
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN 53
+#define MAVLINK_MSG_ID_157_LEN 53
+
+#define MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC 143
+#define MAVLINK_MSG_ID_157_CRC 143
+
+
+
+#define MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED { \
+ "SET_POSITION_TARGET_LOCAL_NED", \
+ 16, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_position_target_local_ned_t, time_boot_ms) }, \
+ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_target_local_ned_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_target_local_ned_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_target_local_ned_t, z) }, \
+ { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_set_position_target_local_ned_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_position_target_local_ned_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_position_target_local_ned_t, vz) }, \
+ { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_position_target_local_ned_t, afx) }, \
+ { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_position_target_local_ned_t, afy) }, \
+ { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_set_position_target_local_ned_t, afz) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_set_position_target_local_ned_t, yaw) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_set_position_target_local_ned_t, yaw_rate) }, \
+ { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_set_position_target_local_ned_t, type_mask) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_set_position_target_local_ned_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_set_position_target_local_ned_t, target_component) }, \
+ { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_set_position_target_local_ned_t, coordinate_frame) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a set_position_target_local_ned message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#else
+ mavlink_set_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a set_position_target_local_ned message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#else
+ mavlink_set_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a set_position_target_local_ned struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param set_position_target_local_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
+{
+ return mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
+}
+
+/**
+ * @brief Encode a set_position_target_local_ned struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param set_position_target_local_ned C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
+{
+ return mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, set_position_target_local_ned->time_boot_ms, set_position_target_local_ned->target_system, set_position_target_local_ned->target_component, set_position_target_local_ned->coordinate_frame, set_position_target_local_ned->type_mask, set_position_target_local_ned->x, set_position_target_local_ned->y, set_position_target_local_ned->z, set_position_target_local_ned->vx, set_position_target_local_ned->vy, set_position_target_local_ned->vz, set_position_target_local_ned->afx, set_position_target_local_ned->afy, set_position_target_local_ned->afz, set_position_target_local_ned->yaw, set_position_target_local_ned->yaw_rate);
+}
+
+/**
+ * @brief Send a set_position_target_local_ned message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms Timestamp in milliseconds since system boot
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ * @param x X Position in NED frame in meters
+ * @param y Y Position in NED frame in meters
+ * @param z Z Position in NED frame in meters (note, altitude is negative in NED)
+ * @param vx X velocity in NED frame in meter / s
+ * @param vy Y velocity in NED frame in meter / s
+ * @param vz Z velocity in NED frame in meter / s
+ * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ * @param yaw yaw setpoint in rad
+ * @param yaw_rate yaw rate setpoint in rad/s
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#else
+ mavlink_set_position_target_local_ned_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.afx = afx;
+ packet.afy = afy;
+ packet.afz = afz;
+ packet.yaw = yaw;
+ packet.yaw_rate = yaw_rate;
+ packet.type_mask = type_mask;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_set_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, vx);
+ _mav_put_float(buf, 20, vy);
+ _mav_put_float(buf, 24, vz);
+ _mav_put_float(buf, 28, afx);
+ _mav_put_float(buf, 32, afy);
+ _mav_put_float(buf, 36, afz);
+ _mav_put_float(buf, 40, yaw);
+ _mav_put_float(buf, 44, yaw_rate);
+ _mav_put_uint16_t(buf, 48, type_mask);
+ _mav_put_uint8_t(buf, 50, target_system);
+ _mav_put_uint8_t(buf, 51, target_component);
+ _mav_put_uint8_t(buf, 52, coordinate_frame);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#else
+ mavlink_set_position_target_local_ned_t *packet = (mavlink_set_position_target_local_ned_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->afx = afx;
+ packet->afy = afy;
+ packet->afz = afz;
+ packet->yaw = yaw;
+ packet->yaw_rate = yaw_rate;
+ packet->type_mask = type_mask;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->coordinate_frame = coordinate_frame;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_POSITION_TARGET_LOCAL_NED UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from set_position_target_local_ned message
+ *
+ * @return Timestamp in milliseconds since system boot
+ */
+static inline uint32_t mavlink_msg_set_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from set_position_target_local_ned message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field target_component from set_position_target_local_ned message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_set_position_target_local_ned_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 51);
+}
+
+/**
+ * @brief Get field coordinate_frame from set_position_target_local_ned message
+ *
+ * @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
+ */
+static inline uint8_t mavlink_msg_set_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 52);
+}
+
+/**
+ * @brief Get field type_mask from set_position_target_local_ned message
+ *
+ * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
+ */
+static inline uint16_t mavlink_msg_set_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 48);
+}
+
+/**
+ * @brief Get field x from set_position_target_local_ned message
+ *
+ * @return X Position in NED frame in meters
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field y from set_position_target_local_ned message
+ *
+ * @return Y Position in NED frame in meters
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field z from set_position_target_local_ned message
+ *
+ * @return Z Position in NED frame in meters (note, altitude is negative in NED)
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field vx from set_position_target_local_ned message
+ *
+ * @return X velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field vy from set_position_target_local_ned message
+ *
+ * @return Y velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field vz from set_position_target_local_ned message
+ *
+ * @return Z velocity in NED frame in meter / s
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field afx from set_position_target_local_ned message
+ *
+ * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_afx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field afy from set_position_target_local_ned message
+ *
+ * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_afy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field afz from set_position_target_local_ned message
+ *
+ * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_afz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field yaw from set_position_target_local_ned message
+ *
+ * @return yaw setpoint in rad
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field yaw_rate from set_position_target_local_ned message
+ *
+ * @return yaw rate setpoint in rad/s
+ */
+static inline float mavlink_msg_set_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a set_position_target_local_ned message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_position_target_local_ned C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_set_position_target_local_ned_t* set_position_target_local_ned)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ set_position_target_local_ned->time_boot_ms = mavlink_msg_set_position_target_local_ned_get_time_boot_ms(msg);
+ set_position_target_local_ned->x = mavlink_msg_set_position_target_local_ned_get_x(msg);
+ set_position_target_local_ned->y = mavlink_msg_set_position_target_local_ned_get_y(msg);
+ set_position_target_local_ned->z = mavlink_msg_set_position_target_local_ned_get_z(msg);
+ set_position_target_local_ned->vx = mavlink_msg_set_position_target_local_ned_get_vx(msg);
+ set_position_target_local_ned->vy = mavlink_msg_set_position_target_local_ned_get_vy(msg);
+ set_position_target_local_ned->vz = mavlink_msg_set_position_target_local_ned_get_vz(msg);
+ set_position_target_local_ned->afx = mavlink_msg_set_position_target_local_ned_get_afx(msg);
+ set_position_target_local_ned->afy = mavlink_msg_set_position_target_local_ned_get_afy(msg);
+ set_position_target_local_ned->afz = mavlink_msg_set_position_target_local_ned_get_afz(msg);
+ set_position_target_local_ned->yaw = mavlink_msg_set_position_target_local_ned_get_yaw(msg);
+ set_position_target_local_ned->yaw_rate = mavlink_msg_set_position_target_local_ned_get_yaw_rate(msg);
+ set_position_target_local_ned->type_mask = mavlink_msg_set_position_target_local_ned_get_type_mask(msg);
+ set_position_target_local_ned->target_system = mavlink_msg_set_position_target_local_ned_get_target_system(msg);
+ set_position_target_local_ned->target_component = mavlink_msg_set_position_target_local_ned_get_target_component(msg);
+ set_position_target_local_ned->coordinate_frame = mavlink_msg_set_position_target_local_ned_get_coordinate_frame(msg);
+#else
+ memcpy(set_position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_sim_state.h b/src/include/mavlink/custom/headers/common/mavlink_msg_sim_state.h
index db3a92642..c47fc8c0c 100644
--- a/src/include/mavlink/custom/headers/common/mavlink_msg_sim_state.h
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_sim_state.h
@@ -4,10 +4,10 @@
typedef struct __mavlink_sim_state_t
{
- float q1; ///< True attitude quaternion component 1
- float q2; ///< True attitude quaternion component 2
- float q3; ///< True attitude quaternion component 3
- float q4; ///< True attitude quaternion component 4
+ float q1; ///< True attitude quaternion component 1, w (1 in null-rotation)
+ float q2; ///< True attitude quaternion component 2, x (0 in null-rotation)
+ float q3; ///< True attitude quaternion component 3, y (0 in null-rotation)
+ float q4; ///< True attitude quaternion component 4, z (0 in null-rotation)
float roll; ///< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
float pitch; ///< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
float yaw; ///< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
@@ -69,10 +69,10 @@ typedef struct __mavlink_sim_state_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param q1 True attitude quaternion component 1
- * @param q2 True attitude quaternion component 2
- * @param q3 True attitude quaternion component 3
- * @param q4 True attitude quaternion component 4
+ * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
+ * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
+ * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
+ * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
* @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
* @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
* @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
@@ -161,10 +161,10 @@ static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t com
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
- * @param q1 True attitude quaternion component 1
- * @param q2 True attitude quaternion component 2
- * @param q3 True attitude quaternion component 3
- * @param q4 True attitude quaternion component 4
+ * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
+ * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
+ * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
+ * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
* @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
* @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
* @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
@@ -279,10 +279,10 @@ static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint
* @brief Send a sim_state message
* @param chan MAVLink channel to send the message
*
- * @param q1 True attitude quaternion component 1
- * @param q2 True attitude quaternion component 2
- * @param q3 True attitude quaternion component 3
- * @param q4 True attitude quaternion component 4
+ * @param q1 True attitude quaternion component 1, w (1 in null-rotation)
+ * @param q2 True attitude quaternion component 2, x (0 in null-rotation)
+ * @param q3 True attitude quaternion component 3, y (0 in null-rotation)
+ * @param q4 True attitude quaternion component 4, z (0 in null-rotation)
* @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
* @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
* @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
@@ -446,7 +446,7 @@ static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mav
/**
* @brief Get field q1 from sim_state message
*
- * @return True attitude quaternion component 1
+ * @return True attitude quaternion component 1, w (1 in null-rotation)
*/
static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg)
{
@@ -456,7 +456,7 @@ static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg)
/**
* @brief Get field q2 from sim_state message
*
- * @return True attitude quaternion component 2
+ * @return True attitude quaternion component 2, x (0 in null-rotation)
*/
static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg)
{
@@ -466,7 +466,7 @@ static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg)
/**
* @brief Get field q3 from sim_state message
*
- * @return True attitude quaternion component 3
+ * @return True attitude quaternion component 3, y (0 in null-rotation)
*/
static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg)
{
@@ -476,7 +476,7 @@ static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg)
/**
* @brief Get field q4 from sim_state message
*
- * @return True attitude quaternion component 4
+ * @return True attitude quaternion component 4, z (0 in null-rotation)
*/
static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg)
{
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_check.h b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_check.h
new file mode 100644
index 000000000..ebdf71a23
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_check.h
@@ -0,0 +1,233 @@
+// MESSAGE TERRAIN_CHECK PACKING
+
+#define MAVLINK_MSG_ID_TERRAIN_CHECK 135
+
+typedef struct __mavlink_terrain_check_t
+{
+ int32_t lat; ///< Latitude (degrees *10^7)
+ int32_t lon; ///< Longitude (degrees *10^7)
+} mavlink_terrain_check_t;
+
+#define MAVLINK_MSG_ID_TERRAIN_CHECK_LEN 8
+#define MAVLINK_MSG_ID_135_LEN 8
+
+#define MAVLINK_MSG_ID_TERRAIN_CHECK_CRC 203
+#define MAVLINK_MSG_ID_135_CRC 203
+
+
+
+#define MAVLINK_MESSAGE_INFO_TERRAIN_CHECK { \
+ "TERRAIN_CHECK", \
+ 2, \
+ { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_check_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_check_t, lon) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a terrain_check message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_check_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int32_t lat, int32_t lon)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#else
+ mavlink_terrain_check_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a terrain_check message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_check_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int32_t lat,int32_t lon)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#else
+ mavlink_terrain_check_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_CHECK;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a terrain_check struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_check C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_check_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check)
+{
+ return mavlink_msg_terrain_check_pack(system_id, component_id, msg, terrain_check->lat, terrain_check->lon);
+}
+
+/**
+ * @brief Encode a terrain_check struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_check C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_check_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_check_t* terrain_check)
+{
+ return mavlink_msg_terrain_check_pack_chan(system_id, component_id, chan, msg, terrain_check->lat, terrain_check->lon);
+}
+
+/**
+ * @brief Send a terrain_check message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_terrain_check_send(mavlink_channel_t chan, int32_t lat, int32_t lon)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_CHECK_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+#else
+ mavlink_terrain_check_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_TERRAIN_CHECK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_terrain_check_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, buf, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+#else
+ mavlink_terrain_check_t *packet = (mavlink_terrain_check_t *)msgbuf;
+ packet->lat = lat;
+ packet->lon = lon;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN, MAVLINK_MSG_ID_TERRAIN_CHECK_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_CHECK, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE TERRAIN_CHECK UNPACKING
+
+
+/**
+ * @brief Get field lat from terrain_check message
+ *
+ * @return Latitude (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_check_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field lon from terrain_check message
+ *
+ * @return Longitude (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_check_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Decode a terrain_check message into a struct
+ *
+ * @param msg The message to decode
+ * @param terrain_check C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_terrain_check_decode(const mavlink_message_t* msg, mavlink_terrain_check_t* terrain_check)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ terrain_check->lat = mavlink_msg_terrain_check_get_lat(msg);
+ terrain_check->lon = mavlink_msg_terrain_check_get_lon(msg);
+#else
+ memcpy(terrain_check, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_CHECK_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_data.h b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_data.h
new file mode 100644
index 000000000..8fc0b4322
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_data.h
@@ -0,0 +1,297 @@
+// MESSAGE TERRAIN_DATA PACKING
+
+#define MAVLINK_MSG_ID_TERRAIN_DATA 134
+
+typedef struct __mavlink_terrain_data_t
+{
+ int32_t lat; ///< Latitude of SW corner of first grid (degrees *10^7)
+ int32_t lon; ///< Longitude of SW corner of first grid (in degrees *10^7)
+ uint16_t grid_spacing; ///< Grid spacing in meters
+ int16_t data[16]; ///< Terrain data in meters AMSL
+ uint8_t gridbit; ///< bit within the terrain request mask
+} mavlink_terrain_data_t;
+
+#define MAVLINK_MSG_ID_TERRAIN_DATA_LEN 43
+#define MAVLINK_MSG_ID_134_LEN 43
+
+#define MAVLINK_MSG_ID_TERRAIN_DATA_CRC 229
+#define MAVLINK_MSG_ID_134_CRC 229
+
+#define MAVLINK_MSG_TERRAIN_DATA_FIELD_DATA_LEN 16
+
+#define MAVLINK_MESSAGE_INFO_TERRAIN_DATA { \
+ "TERRAIN_DATA", \
+ 5, \
+ { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_data_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_data_t, lon) }, \
+ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_terrain_data_t, grid_spacing) }, \
+ { "data", NULL, MAVLINK_TYPE_INT16_T, 16, 10, offsetof(mavlink_terrain_data_t, data) }, \
+ { "gridbit", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_terrain_data_t, gridbit) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a terrain_data message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param gridbit bit within the terrain request mask
+ * @param data Terrain data in meters AMSL
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_uint16_t(buf, 8, grid_spacing);
+ _mav_put_uint8_t(buf, 42, gridbit);
+ _mav_put_int16_t_array(buf, 10, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#else
+ mavlink_terrain_data_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+ packet.gridbit = gridbit;
+ mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a terrain_data message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param gridbit bit within the terrain request mask
+ * @param data Terrain data in meters AMSL
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int32_t lat,int32_t lon,uint16_t grid_spacing,uint8_t gridbit,const int16_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_uint16_t(buf, 8, grid_spacing);
+ _mav_put_uint8_t(buf, 42, gridbit);
+ _mav_put_int16_t_array(buf, 10, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#else
+ mavlink_terrain_data_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+ packet.gridbit = gridbit;
+ mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_DATA;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a terrain_data struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_data C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data)
+{
+ return mavlink_msg_terrain_data_pack(system_id, component_id, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
+}
+
+/**
+ * @brief Encode a terrain_data struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_data C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_data_t* terrain_data)
+{
+ return mavlink_msg_terrain_data_pack_chan(system_id, component_id, chan, msg, terrain_data->lat, terrain_data->lon, terrain_data->grid_spacing, terrain_data->gridbit, terrain_data->data);
+}
+
+/**
+ * @brief Send a terrain_data message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param gridbit bit within the terrain request mask
+ * @param data Terrain data in meters AMSL
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_terrain_data_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_DATA_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_uint16_t(buf, 8, grid_spacing);
+ _mav_put_uint8_t(buf, 42, gridbit);
+ _mav_put_int16_t_array(buf, 10, data, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+#else
+ mavlink_terrain_data_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+ packet.gridbit = gridbit;
+ mav_array_memcpy(packet.data, data, sizeof(int16_t)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_TERRAIN_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_terrain_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint8_t gridbit, const int16_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_uint16_t(buf, 8, grid_spacing);
+ _mav_put_uint8_t(buf, 42, gridbit);
+ _mav_put_int16_t_array(buf, 10, data, 16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, buf, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+#else
+ mavlink_terrain_data_t *packet = (mavlink_terrain_data_t *)msgbuf;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->grid_spacing = grid_spacing;
+ packet->gridbit = gridbit;
+ mav_array_memcpy(packet->data, data, sizeof(int16_t)*16);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN, MAVLINK_MSG_ID_TERRAIN_DATA_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_DATA, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE TERRAIN_DATA UNPACKING
+
+
+/**
+ * @brief Get field lat from terrain_data message
+ *
+ * @return Latitude of SW corner of first grid (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_data_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field lon from terrain_data message
+ *
+ * @return Longitude of SW corner of first grid (in degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_data_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field grid_spacing from terrain_data message
+ *
+ * @return Grid spacing in meters
+ */
+static inline uint16_t mavlink_msg_terrain_data_get_grid_spacing(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 8);
+}
+
+/**
+ * @brief Get field gridbit from terrain_data message
+ *
+ * @return bit within the terrain request mask
+ */
+static inline uint8_t mavlink_msg_terrain_data_get_gridbit(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 42);
+}
+
+/**
+ * @brief Get field data from terrain_data message
+ *
+ * @return Terrain data in meters AMSL
+ */
+static inline uint16_t mavlink_msg_terrain_data_get_data(const mavlink_message_t* msg, int16_t *data)
+{
+ return _MAV_RETURN_int16_t_array(msg, data, 16, 10);
+}
+
+/**
+ * @brief Decode a terrain_data message into a struct
+ *
+ * @param msg The message to decode
+ * @param terrain_data C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_terrain_data_decode(const mavlink_message_t* msg, mavlink_terrain_data_t* terrain_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ terrain_data->lat = mavlink_msg_terrain_data_get_lat(msg);
+ terrain_data->lon = mavlink_msg_terrain_data_get_lon(msg);
+ terrain_data->grid_spacing = mavlink_msg_terrain_data_get_grid_spacing(msg);
+ mavlink_msg_terrain_data_get_data(msg, terrain_data->data);
+ terrain_data->gridbit = mavlink_msg_terrain_data_get_gridbit(msg);
+#else
+ memcpy(terrain_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_DATA_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_report.h b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_report.h
new file mode 100644
index 000000000..1b61dd4bf
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_report.h
@@ -0,0 +1,353 @@
+// MESSAGE TERRAIN_REPORT PACKING
+
+#define MAVLINK_MSG_ID_TERRAIN_REPORT 136
+
+typedef struct __mavlink_terrain_report_t
+{
+ int32_t lat; ///< Latitude (degrees *10^7)
+ int32_t lon; ///< Longitude (degrees *10^7)
+ float terrain_height; ///< Terrain height in meters AMSL
+ float current_height; ///< Current vehicle height above lat/lon terrain height (meters)
+ uint16_t spacing; ///< grid spacing (zero if terrain at this location unavailable)
+ uint16_t pending; ///< Number of 4x4 terrain blocks waiting to be received or read from disk
+ uint16_t loaded; ///< Number of 4x4 terrain blocks in memory
+} mavlink_terrain_report_t;
+
+#define MAVLINK_MSG_ID_TERRAIN_REPORT_LEN 22
+#define MAVLINK_MSG_ID_136_LEN 22
+
+#define MAVLINK_MSG_ID_TERRAIN_REPORT_CRC 1
+#define MAVLINK_MSG_ID_136_CRC 1
+
+
+
+#define MAVLINK_MESSAGE_INFO_TERRAIN_REPORT { \
+ "TERRAIN_REPORT", \
+ 7, \
+ { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_terrain_report_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_terrain_report_t, lon) }, \
+ { "terrain_height", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_terrain_report_t, terrain_height) }, \
+ { "current_height", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_terrain_report_t, current_height) }, \
+ { "spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_report_t, spacing) }, \
+ { "pending", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_terrain_report_t, pending) }, \
+ { "loaded", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_terrain_report_t, loaded) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a terrain_report message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ * @param spacing grid spacing (zero if terrain at this location unavailable)
+ * @param terrain_height Terrain height in meters AMSL
+ * @param current_height Current vehicle height above lat/lon terrain height (meters)
+ * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk
+ * @param loaded Number of 4x4 terrain blocks in memory
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_float(buf, 8, terrain_height);
+ _mav_put_float(buf, 12, current_height);
+ _mav_put_uint16_t(buf, 16, spacing);
+ _mav_put_uint16_t(buf, 18, pending);
+ _mav_put_uint16_t(buf, 20, loaded);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#else
+ mavlink_terrain_report_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.terrain_height = terrain_height;
+ packet.current_height = current_height;
+ packet.spacing = spacing;
+ packet.pending = pending;
+ packet.loaded = loaded;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a terrain_report message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ * @param spacing grid spacing (zero if terrain at this location unavailable)
+ * @param terrain_height Terrain height in meters AMSL
+ * @param current_height Current vehicle height above lat/lon terrain height (meters)
+ * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk
+ * @param loaded Number of 4x4 terrain blocks in memory
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int32_t lat,int32_t lon,uint16_t spacing,float terrain_height,float current_height,uint16_t pending,uint16_t loaded)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_float(buf, 8, terrain_height);
+ _mav_put_float(buf, 12, current_height);
+ _mav_put_uint16_t(buf, 16, spacing);
+ _mav_put_uint16_t(buf, 18, pending);
+ _mav_put_uint16_t(buf, 20, loaded);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#else
+ mavlink_terrain_report_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.terrain_height = terrain_height;
+ packet.current_height = current_height;
+ packet.spacing = spacing;
+ packet.pending = pending;
+ packet.loaded = loaded;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a terrain_report struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report)
+{
+ return mavlink_msg_terrain_report_pack(system_id, component_id, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded);
+}
+
+/**
+ * @brief Encode a terrain_report struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_report_t* terrain_report)
+{
+ return mavlink_msg_terrain_report_pack_chan(system_id, component_id, chan, msg, terrain_report->lat, terrain_report->lon, terrain_report->spacing, terrain_report->terrain_height, terrain_report->current_height, terrain_report->pending, terrain_report->loaded);
+}
+
+/**
+ * @brief Send a terrain_report message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param lat Latitude (degrees *10^7)
+ * @param lon Longitude (degrees *10^7)
+ * @param spacing grid spacing (zero if terrain at this location unavailable)
+ * @param terrain_height Terrain height in meters AMSL
+ * @param current_height Current vehicle height above lat/lon terrain height (meters)
+ * @param pending Number of 4x4 terrain blocks waiting to be received or read from disk
+ * @param loaded Number of 4x4 terrain blocks in memory
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_terrain_report_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REPORT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_float(buf, 8, terrain_height);
+ _mav_put_float(buf, 12, current_height);
+ _mav_put_uint16_t(buf, 16, spacing);
+ _mav_put_uint16_t(buf, 18, pending);
+ _mav_put_uint16_t(buf, 20, loaded);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+#else
+ mavlink_terrain_report_t packet;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.terrain_height = terrain_height;
+ packet.current_height = current_height;
+ packet.spacing = spacing;
+ packet.pending = pending;
+ packet.loaded = loaded;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_TERRAIN_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_terrain_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t spacing, float terrain_height, float current_height, uint16_t pending, uint16_t loaded)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lon);
+ _mav_put_float(buf, 8, terrain_height);
+ _mav_put_float(buf, 12, current_height);
+ _mav_put_uint16_t(buf, 16, spacing);
+ _mav_put_uint16_t(buf, 18, pending);
+ _mav_put_uint16_t(buf, 20, loaded);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, buf, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+#else
+ mavlink_terrain_report_t *packet = (mavlink_terrain_report_t *)msgbuf;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->terrain_height = terrain_height;
+ packet->current_height = current_height;
+ packet->spacing = spacing;
+ packet->pending = pending;
+ packet->loaded = loaded;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN, MAVLINK_MSG_ID_TERRAIN_REPORT_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REPORT, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE TERRAIN_REPORT UNPACKING
+
+
+/**
+ * @brief Get field lat from terrain_report message
+ *
+ * @return Latitude (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_report_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field lon from terrain_report message
+ *
+ * @return Longitude (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_report_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field spacing from terrain_report message
+ *
+ * @return grid spacing (zero if terrain at this location unavailable)
+ */
+static inline uint16_t mavlink_msg_terrain_report_get_spacing(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field terrain_height from terrain_report message
+ *
+ * @return Terrain height in meters AMSL
+ */
+static inline float mavlink_msg_terrain_report_get_terrain_height(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field current_height from terrain_report message
+ *
+ * @return Current vehicle height above lat/lon terrain height (meters)
+ */
+static inline float mavlink_msg_terrain_report_get_current_height(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field pending from terrain_report message
+ *
+ * @return Number of 4x4 terrain blocks waiting to be received or read from disk
+ */
+static inline uint16_t mavlink_msg_terrain_report_get_pending(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 18);
+}
+
+/**
+ * @brief Get field loaded from terrain_report message
+ *
+ * @return Number of 4x4 terrain blocks in memory
+ */
+static inline uint16_t mavlink_msg_terrain_report_get_loaded(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 20);
+}
+
+/**
+ * @brief Decode a terrain_report message into a struct
+ *
+ * @param msg The message to decode
+ * @param terrain_report C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_terrain_report_decode(const mavlink_message_t* msg, mavlink_terrain_report_t* terrain_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ terrain_report->lat = mavlink_msg_terrain_report_get_lat(msg);
+ terrain_report->lon = mavlink_msg_terrain_report_get_lon(msg);
+ terrain_report->terrain_height = mavlink_msg_terrain_report_get_terrain_height(msg);
+ terrain_report->current_height = mavlink_msg_terrain_report_get_current_height(msg);
+ terrain_report->spacing = mavlink_msg_terrain_report_get_spacing(msg);
+ terrain_report->pending = mavlink_msg_terrain_report_get_pending(msg);
+ terrain_report->loaded = mavlink_msg_terrain_report_get_loaded(msg);
+#else
+ memcpy(terrain_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REPORT_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_request.h b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_request.h
new file mode 100644
index 000000000..3a85b8564
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_terrain_request.h
@@ -0,0 +1,281 @@
+// MESSAGE TERRAIN_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_TERRAIN_REQUEST 133
+
+typedef struct __mavlink_terrain_request_t
+{
+ uint64_t mask; ///< Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
+ int32_t lat; ///< Latitude of SW corner of first grid (degrees *10^7)
+ int32_t lon; ///< Longitude of SW corner of first grid (in degrees *10^7)
+ uint16_t grid_spacing; ///< Grid spacing in meters
+} mavlink_terrain_request_t;
+
+#define MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN 18
+#define MAVLINK_MSG_ID_133_LEN 18
+
+#define MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC 6
+#define MAVLINK_MSG_ID_133_CRC 6
+
+
+
+#define MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST { \
+ "TERRAIN_REQUEST", \
+ 4, \
+ { { "mask", "0x%07x", MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_terrain_request_t, mask) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_terrain_request_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_terrain_request_t, lon) }, \
+ { "grid_spacing", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_terrain_request_t, grid_spacing) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a terrain_request message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
+ _mav_put_uint64_t(buf, 0, mask);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_uint16_t(buf, 16, grid_spacing);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#else
+ mavlink_terrain_request_t packet;
+ packet.mask = mask;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a terrain_request message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_terrain_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int32_t lat,int32_t lon,uint16_t grid_spacing,uint64_t mask)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
+ _mav_put_uint64_t(buf, 0, mask);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_uint16_t(buf, 16, grid_spacing);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#else
+ mavlink_terrain_request_t packet;
+ packet.mask = mask;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_TERRAIN_REQUEST;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a terrain_request struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request)
+{
+ return mavlink_msg_terrain_request_pack(system_id, component_id, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask);
+}
+
+/**
+ * @brief Encode a terrain_request struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param terrain_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_terrain_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_terrain_request_t* terrain_request)
+{
+ return mavlink_msg_terrain_request_pack_chan(system_id, component_id, chan, msg, terrain_request->lat, terrain_request->lon, terrain_request->grid_spacing, terrain_request->mask);
+}
+
+/**
+ * @brief Send a terrain_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param lat Latitude of SW corner of first grid (degrees *10^7)
+ * @param lon Longitude of SW corner of first grid (in degrees *10^7)
+ * @param grid_spacing Grid spacing in meters
+ * @param mask Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_terrain_request_send(mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN];
+ _mav_put_uint64_t(buf, 0, mask);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_uint16_t(buf, 16, grid_spacing);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+#else
+ mavlink_terrain_request_t packet;
+ packet.mask = mask;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.grid_spacing = grid_spacing;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_terrain_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lat, int32_t lon, uint16_t grid_spacing, uint64_t mask)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, mask);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lon);
+ _mav_put_uint16_t(buf, 16, grid_spacing);
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, buf, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+#else
+ mavlink_terrain_request_t *packet = (mavlink_terrain_request_t *)msgbuf;
+ packet->mask = mask;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->grid_spacing = grid_spacing;
+
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN, MAVLINK_MSG_ID_TERRAIN_REQUEST_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TERRAIN_REQUEST, (const char *)packet, MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE TERRAIN_REQUEST UNPACKING
+
+
+/**
+ * @brief Get field lat from terrain_request message
+ *
+ * @return Latitude of SW corner of first grid (degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_request_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field lon from terrain_request message
+ *
+ * @return Longitude of SW corner of first grid (in degrees *10^7)
+ */
+static inline int32_t mavlink_msg_terrain_request_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field grid_spacing from terrain_request message
+ *
+ * @return Grid spacing in meters
+ */
+static inline uint16_t mavlink_msg_terrain_request_get_grid_spacing(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field mask from terrain_request message
+ *
+ * @return Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)
+ */
+static inline uint64_t mavlink_msg_terrain_request_get_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Decode a terrain_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param terrain_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_terrain_request_decode(const mavlink_message_t* msg, mavlink_terrain_request_t* terrain_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ terrain_request->mask = mavlink_msg_terrain_request_get_mask(msg);
+ terrain_request->lat = mavlink_msg_terrain_request_get_lat(msg);
+ terrain_request->lon = mavlink_msg_terrain_request_get_lon(msg);
+ terrain_request->grid_spacing = mavlink_msg_terrain_request_get_grid_spacing(msg);
+#else
+ memcpy(terrain_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_TERRAIN_REQUEST_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/mavlink_msg_v2_extension.h b/src/include/mavlink/custom/headers/common/mavlink_msg_v2_extension.h
new file mode 100644
index 000000000..46c8d6ce5
--- /dev/null
+++ b/src/include/mavlink/custom/headers/common/mavlink_msg_v2_extension.h
@@ -0,0 +1,297 @@
+// MESSAGE V2_EXTENSION PACKING
+
+#define MAVLINK_MSG_ID_V2_EXTENSION 152
+
+typedef struct __mavlink_v2_extension_t
+{
+ uint16_t message_type; ///< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
+ uint8_t target_network; ///< Network ID (0 for broadcast)
+ uint8_t target_system; ///< System ID (0 for broadcast)
+ uint8_t target_component; ///< Component ID (0 for broadcast)
+ uint8_t payload[249]; ///< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+} mavlink_v2_extension_t;
+
+#define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254
+#define MAVLINK_MSG_ID_152_LEN 254
+
+#define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8
+#define MAVLINK_MSG_ID_152_CRC 8
+
+#define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249
+
+#define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \
+ "V2_EXTENSION", \
+ 5, \
+ { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \
+ { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \
+ { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \
+ } \
+}
+
+
+/**
+ * @brief Pack a v2_extension message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
+ _mav_put_uint16_t(buf, 0, message_type);
+ _mav_put_uint8_t(buf, 2, target_network);
+ _mav_put_uint8_t(buf, 3, target_system);
+ _mav_put_uint8_t(buf, 4, target_component);
+ _mav_put_uint8_t_array(buf, 5, payload, 249);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#else
+ mavlink_v2_extension_t packet;
+ packet.message_type = message_type;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a v2_extension message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
+ _mav_put_uint16_t(buf, 0, message_type);
+ _mav_put_uint8_t(buf, 2, target_network);
+ _mav_put_uint8_t(buf, 3, target_system);
+ _mav_put_uint8_t(buf, 4, target_component);
+ _mav_put_uint8_t_array(buf, 5, payload, 249);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#else
+ mavlink_v2_extension_t packet;
+ packet.message_type = message_type;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+}
+
+/**
+ * @brief Encode a v2_extension struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param v2_extension C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
+{
+ return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
+}
+
+/**
+ * @brief Encode a v2_extension struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param v2_extension C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
+{
+ return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
+}
+
+/**
+ * @brief Send a v2_extension message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_network Network ID (0 for broadcast)
+ * @param target_system System ID (0 for broadcast)
+ * @param target_component Component ID (0 for broadcast)
+ * @param message_type A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
+ * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
+ _mav_put_uint16_t(buf, 0, message_type);
+ _mav_put_uint8_t(buf, 2, target_network);
+ _mav_put_uint8_t(buf, 3, target_system);
+ _mav_put_uint8_t(buf, 4, target_component);
+ _mav_put_uint8_t_array(buf, 5, payload, 249);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+#else
+ mavlink_v2_extension_t packet;
+ packet.message_type = message_type;
+ packet.target_network = target_network;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+#endif
+}
+
+#if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This varient of _send() can be used to save stack space by re-using
+ memory from the receive buffer. The caller provides a
+ mavlink_message_t which is the size of a full mavlink message. This
+ is usually the receive buffer for the channel, and allows a reply to an
+ incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, message_type);
+ _mav_put_uint8_t(buf, 2, target_network);
+ _mav_put_uint8_t(buf, 3, target_system);
+ _mav_put_uint8_t(buf, 4, target_component);
+ _mav_put_uint8_t_array(buf, 5, payload, 249);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+#else
+ mavlink_v2_extension_t *packet = (mavlink_v2_extension_t *)msgbuf;
+ packet->message_type = message_type;
+ packet->target_network = target_network;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249);
+#if MAVLINK_CRC_EXTRA
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE V2_EXTENSION UNPACKING
+
+
+/**
+ * @brief Get field target_network from v2_extension message
+ *
+ * @return Network ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field target_system from v2_extension message
+ *
+ * @return System ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field target_component from v2_extension message
+ *
+ * @return Component ID (0 for broadcast)
+ */
+static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field message_type from v2_extension message
+ *
+ * @return A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.
+ */
+static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field payload from v2_extension message
+ *
+ * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
+ */
+static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload)
+{
+ return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5);
+}
+
+/**
+ * @brief Decode a v2_extension message into a struct
+ *
+ * @param msg The message to decode
+ * @param v2_extension C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension)
+{
+#if MAVLINK_NEED_BYTE_SWAP
+ v2_extension->message_type = mavlink_msg_v2_extension_get_message_type(msg);
+ v2_extension->target_network = mavlink_msg_v2_extension_get_target_network(msg);
+ v2_extension->target_system = mavlink_msg_v2_extension_get_target_system(msg);
+ v2_extension->target_component = mavlink_msg_v2_extension_get_target_component(msg);
+ mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload);
+#else
+ memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN);
+#endif
+}
diff --git a/src/include/mavlink/custom/headers/common/testsuite.h b/src/include/mavlink/custom/headers/common/testsuite.h
index 57c4b9abc..fb8baef45 100644
--- a/src/include/mavlink/custom/headers/common/testsuite.h
+++ b/src/include/mavlink/custom/headers/common/testsuite.h
@@ -30,13 +30,8 @@ static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_heartbeat_t packet_in = {
- 963497464,
- }17,
- }84,
- }151,
- }218,
- }3,
- };
+ 963497464,17,84,151,218,3
+ };
mavlink_heartbeat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.custom_mode = packet_in.custom_mode;
@@ -83,20 +78,8 @@ static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sys_status_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- }18379,
- }18483,
- }18587,
- }18691,
- }223,
- };
+ 963497464,963497672,963497880,17859,17963,18067,18171,18275,18379,18483,18587,18691,223
+ };
mavlink_sys_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present;
@@ -150,9 +133,8 @@ static void mavlink_test_system_time(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_system_time_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- };
+ 93372036854775807ULL,963497880
+ };
mavlink_system_time_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_unix_usec = packet_in.time_unix_usec;
@@ -195,11 +177,8 @@ static void mavlink_test_ping(uint8_t system_id, uint8_t component_id, mavlink_m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ping_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- }41,
- }108,
- };
+ 93372036854775807ULL,963497880,41,108
+ };
mavlink_ping_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -244,11 +223,8 @@ static void mavlink_test_change_operator_control(uint8_t system_id, uint8_t comp
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_t packet_in = {
- 5,
- }72,
- }139,
- }"DEFGHIJKLMNOPQRSTUVWXYZA",
- };
+ 5,72,139,"DEFGHIJKLMNOPQRSTUVWXYZA"
+ };
mavlink_change_operator_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -293,10 +269,8 @@ static void mavlink_test_change_operator_control_ack(uint8_t system_id, uint8_t
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_ack_t packet_in = {
- 5,
- }72,
- }139,
- };
+ 5,72,139
+ };
mavlink_change_operator_control_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.gcs_system_id = packet_in.gcs_system_id;
@@ -340,8 +314,8 @@ static void mavlink_test_auth_key(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_auth_key_t packet_in = {
- "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE",
- };
+ "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE"
+ };
mavlink_auth_key_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@@ -383,10 +357,8 @@ static void mavlink_test_set_mode(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mode_t packet_in = {
- 963497464,
- }17,
- }84,
- };
+ 963497464,17,84
+ };
mavlink_set_mode_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.custom_mode = packet_in.custom_mode;
@@ -430,11 +402,8 @@ static void mavlink_test_param_request_read(uint8_t system_id, uint8_t component
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_read_t packet_in = {
- 17235,
- }139,
- }206,
- }"EFGHIJKLMNOPQRS",
- };
+ 17235,139,206,"EFGHIJKLMNOPQRS"
+ };
mavlink_param_request_read_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_index = packet_in.param_index;
@@ -479,9 +448,8 @@ static void mavlink_test_param_request_list(uint8_t system_id, uint8_t component
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_list_t packet_in = {
- 5,
- }72,
- };
+ 5,72
+ };
mavlink_param_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -524,12 +492,8 @@ static void mavlink_test_param_value(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_value_t packet_in = {
- 17.0,
- }17443,
- }17547,
- }"IJKLMNOPQRSTUVW",
- }77,
- };
+ 17.0,17443,17547,"IJKLMNOPQRSTUVW",77
+ };
mavlink_param_value_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_value = packet_in.param_value;
@@ -575,12 +539,8 @@ static void mavlink_test_param_set(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_set_t packet_in = {
- 17.0,
- }17,
- }84,
- }"GHIJKLMNOPQRSTU",
- }199,
- };
+ 17.0,17,84,"GHIJKLMNOPQRSTU",199
+ };
mavlink_param_set_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_value = packet_in.param_value;
@@ -626,17 +586,8 @@ static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_raw_int_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- }963498088,
- }963498296,
- }18275,
- }18379,
- }18483,
- }18587,
- }89,
- }156,
- };
+ 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,89,156
+ };
mavlink_gps_raw_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -687,13 +638,8 @@ static void mavlink_test_gps_status(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_status_t packet_in = {
- 5,
- }{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },
- }{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },
- }{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },
- }{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },
- }{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 },
- };
+ 5,{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 }
+ };
mavlink_gps_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.satellites_visible = packet_in.satellites_visible;
@@ -740,17 +686,8 @@ static void mavlink_test_scaled_imu(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_imu_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275
+ };
mavlink_scaled_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -801,17 +738,8 @@ static void mavlink_test_raw_imu(uint8_t system_id, uint8_t component_id, mavlin
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_imu_t packet_in = {
- 93372036854775807ULL,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- }18379,
- }18483,
- };
+ 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483
+ };
mavlink_raw_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -862,12 +790,8 @@ static void mavlink_test_raw_pressure(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_pressure_t packet_in = {
- 93372036854775807ULL,
- }17651,
- }17755,
- }17859,
- }17963,
- };
+ 93372036854775807ULL,17651,17755,17859,17963
+ };
mavlink_raw_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -913,11 +837,8 @@ static void mavlink_test_scaled_pressure(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_pressure_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }17859,
- };
+ 963497464,45.0,73.0,17859
+ };
mavlink_scaled_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -962,14 +883,8 @@ static void mavlink_test_attitude(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- };
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0
+ };
mavlink_attitude_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1017,15 +932,8 @@ static void mavlink_test_attitude_quaternion(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_quaternion_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- };
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0
+ };
mavlink_attitude_quaternion_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1074,14 +982,8 @@ static void mavlink_test_local_position_ned(uint8_t system_id, uint8_t component
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_ned_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- };
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0
+ };
mavlink_local_position_ned_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1129,18 +1031,8 @@ static void mavlink_test_global_position_int(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_int_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }963498088,
- }963498296,
- }18275,
- }18379,
- }18483,
- }18587,
- }18691,
- }18795,
- };
+ 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587,18691,18795
+ };
mavlink_global_position_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1192,18 +1084,8 @@ static void mavlink_test_rc_channels_scaled(uint8_t system_id, uint8_t component
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_scaled_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }65,
- }132,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132
+ };
mavlink_rc_channels_scaled_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1255,18 +1137,8 @@ static void mavlink_test_rc_channels_raw(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_raw_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }65,
- }132,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65,132
+ };
mavlink_rc_channels_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -1318,17 +1190,8 @@ static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_i
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_servo_output_raw_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }65,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,65
+ };
mavlink_servo_output_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -1379,11 +1242,8 @@ static void mavlink_test_mission_request_partial_list(uint8_t system_id, uint8_t
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_partial_list_t packet_in = {
- 17235,
- }17339,
- }17,
- }84,
- };
+ 17235,17339,17,84
+ };
mavlink_mission_request_partial_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.start_index = packet_in.start_index;
@@ -1428,11 +1288,8 @@ static void mavlink_test_mission_write_partial_list(uint8_t system_id, uint8_t c
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_write_partial_list_t packet_in = {
- 17235,
- }17339,
- }17,
- }84,
- };
+ 17235,17339,17,84
+ };
mavlink_mission_write_partial_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.start_index = packet_in.start_index;
@@ -1477,21 +1334,8 @@ static void mavlink_test_mission_item(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_item_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }18691,
- }18795,
- }101,
- }168,
- }235,
- }46,
- }113,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,18795,101,168,235,46,113
+ };
mavlink_mission_item_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param1 = packet_in.param1;
@@ -1546,10 +1390,8 @@ static void mavlink_test_mission_request(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_t packet_in = {
- 17235,
- }139,
- }206,
- };
+ 17235,139,206
+ };
mavlink_mission_request_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
@@ -1593,10 +1435,8 @@ static void mavlink_test_mission_set_current(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_set_current_t packet_in = {
- 17235,
- }139,
- }206,
- };
+ 17235,139,206
+ };
mavlink_mission_set_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
@@ -1640,8 +1480,8 @@ static void mavlink_test_mission_current(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_current_t packet_in = {
- 17235,
- };
+ 17235
+ };
mavlink_mission_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
@@ -1683,9 +1523,8 @@ static void mavlink_test_mission_request_list(uint8_t system_id, uint8_t compone
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_list_t packet_in = {
- 5,
- }72,
- };
+ 5,72
+ };
mavlink_mission_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -1728,10 +1567,8 @@ static void mavlink_test_mission_count(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_count_t packet_in = {
- 17235,
- }139,
- }206,
- };
+ 17235,139,206
+ };
mavlink_mission_count_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.count = packet_in.count;
@@ -1775,9 +1612,8 @@ static void mavlink_test_mission_clear_all(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_clear_all_t packet_in = {
- 5,
- }72,
- };
+ 5,72
+ };
mavlink_mission_clear_all_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -1820,8 +1656,8 @@ static void mavlink_test_mission_item_reached(uint8_t system_id, uint8_t compone
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_item_reached_t packet_in = {
- 17235,
- };
+ 17235
+ };
mavlink_mission_item_reached_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
@@ -1863,10 +1699,8 @@ static void mavlink_test_mission_ack(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_ack_t packet_in = {
- 5,
- }72,
- }139,
- };
+ 5,72,139
+ };
mavlink_mission_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -1910,11 +1744,8 @@ static void mavlink_test_set_gps_global_origin(uint8_t system_id, uint8_t compon
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_gps_global_origin_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }41,
- };
+ 963497464,963497672,963497880,41
+ };
mavlink_set_gps_global_origin_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
@@ -1959,10 +1790,8 @@ static void mavlink_test_gps_global_origin(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_global_origin_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- };
+ 963497464,963497672,963497880
+ };
mavlink_gps_global_origin_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
@@ -2006,14 +1835,8 @@ static void mavlink_test_set_local_position_setpoint(uint8_t system_id, uint8_t
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_local_position_setpoint_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }53,
- }120,
- }187,
- };
+ 17.0,45.0,73.0,101.0,53,120,187
+ };
mavlink_set_local_position_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
@@ -2061,12 +1884,8 @@ static void mavlink_test_local_position_setpoint(uint8_t system_id, uint8_t comp
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_setpoint_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }53,
- };
+ 17.0,45.0,73.0,101.0,53
+ };
mavlink_local_position_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
@@ -2112,12 +1931,8 @@ static void mavlink_test_global_position_setpoint_int(uint8_t system_id, uint8_t
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_setpoint_int_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }17859,
- }175,
- };
+ 963497464,963497672,963497880,17859,175
+ };
mavlink_global_position_setpoint_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
@@ -2163,12 +1978,8 @@ static void mavlink_test_set_global_position_setpoint_int(uint8_t system_id, uin
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_global_position_setpoint_int_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }17859,
- }175,
- };
+ 963497464,963497672,963497880,17859,175
+ };
mavlink_set_global_position_setpoint_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
@@ -2214,16 +2025,8 @@ static void mavlink_test_safety_set_allowed_area(uint8_t system_id, uint8_t comp
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_set_allowed_area_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }77,
- }144,
- }211,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,77,144,211
+ };
mavlink_safety_set_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.p1x = packet_in.p1x;
@@ -2273,14 +2076,8 @@ static void mavlink_test_safety_allowed_area(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_allowed_area_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }77,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,77
+ };
mavlink_safety_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.p1x = packet_in.p1x;
@@ -2328,13 +2125,8 @@ static void mavlink_test_set_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t co
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_thrust_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }53,
- }120,
- };
+ 17.0,45.0,73.0,101.0,53,120
+ };
mavlink_set_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll = packet_in.roll;
@@ -2381,13 +2173,8 @@ static void mavlink_test_set_roll_pitch_yaw_speed_thrust(uint8_t system_id, uint
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_speed_thrust_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }53,
- }120,
- };
+ 17.0,45.0,73.0,101.0,53,120
+ };
mavlink_set_roll_pitch_yaw_speed_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll_speed = packet_in.roll_speed;
@@ -2434,12 +2221,8 @@ static void mavlink_test_roll_pitch_yaw_thrust_setpoint(uint8_t system_id, uint8
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_thrust_setpoint_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- };
+ 963497464,45.0,73.0,101.0,129.0
+ };
mavlink_roll_pitch_yaw_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -2485,12 +2268,8 @@ static void mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(uint8_t system_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- };
+ 963497464,45.0,73.0,101.0,129.0
+ };
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -2536,12 +2315,8 @@ static void mavlink_test_set_quad_motors_setpoint(uint8_t system_id, uint8_t com
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_motors_setpoint_t packet_in = {
- 17235,
- }17339,
- }17443,
- }17547,
- }29,
- };
+ 17235,17339,17443,17547,29
+ };
mavlink_set_quad_motors_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.motor_front_nw = packet_in.motor_front_nw;
@@ -2587,13 +2362,8 @@ static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet_in = {
- { 17235, 17236, 17237, 17238 },
- }{ 17651, 17652, 17653, 17654 },
- }{ 18067, 18068, 18069, 18070 },
- }{ 18483, 18484, 18485, 18486 },
- }101,
- }168,
- };
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },101,168
+ };
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.group = packet_in.group;
@@ -2640,15 +2410,8 @@ static void mavlink_test_nav_controller_output(uint8_t system_id, uint8_t compon
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_nav_controller_output_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }18275,
- }18379,
- }18483,
- };
+ 17.0,45.0,73.0,101.0,129.0,18275,18379,18483
+ };
mavlink_nav_controller_output_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.nav_roll = packet_in.nav_roll;
@@ -2697,16 +2460,8 @@ static void mavlink_test_set_quad_swarm_led_roll_pitch_yaw_thrust(uint8_t system
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet_in = {
- { 17235, 17236, 17237, 17238 },
- }{ 17651, 17652, 17653, 17654 },
- }{ 18067, 18068, 18069, 18070 },
- }{ 18483, 18484, 18485, 18486 },
- }101,
- }168,
- }{ 235, 236, 237, 238 },
- }{ 247, 248, 249, 250 },
- }{ 3, 4, 5, 6 },
- };
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },101,168,{ 235, 236, 237, 238 },{ 247, 248, 249, 250 },{ 3, 4, 5, 6 }
+ };
mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.group = packet_in.group;
@@ -2756,16 +2511,8 @@ static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_i
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_state_correction_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0
+ };
mavlink_state_correction_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.xErr = packet_in.xErr;
@@ -2815,28 +2562,8 @@ static void mavlink_test_rc_channels(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- }18379,
- }18483,
- }18587,
- }18691,
- }18795,
- }18899,
- }19003,
- }19107,
- }19211,
- }125,
- }192,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,18899,19003,19107,19211,125,192
+ };
mavlink_rc_channels_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -2898,12 +2625,8 @@ static void mavlink_test_request_data_stream(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_request_data_stream_t packet_in = {
- 17235,
- }139,
- }206,
- }17,
- }84,
- };
+ 17235,139,206,17,84
+ };
mavlink_request_data_stream_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.req_message_rate = packet_in.req_message_rate;
@@ -2949,10 +2672,8 @@ static void mavlink_test_data_stream(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_data_stream_t packet_in = {
- 17235,
- }139,
- }206,
- };
+ 17235,139,206
+ };
mavlink_data_stream_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.message_rate = packet_in.message_rate;
@@ -2996,13 +2717,8 @@ static void mavlink_test_manual_control(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_control_t packet_in = {
- 17235,
- }17339,
- }17443,
- }17547,
- }17651,
- }163,
- };
+ 17235,17339,17443,17547,17651,163
+ };
mavlink_manual_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
@@ -3049,17 +2765,8 @@ static void mavlink_test_rc_channels_override(uint8_t system_id, uint8_t compone
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_override_t packet_in = {
- 17235,
- }17339,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }53,
- }120,
- };
+ 17235,17339,17443,17547,17651,17755,17859,17963,53,120
+ };
mavlink_rc_channels_override_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.chan1_raw = packet_in.chan1_raw;
@@ -3104,19 +2811,70 @@ static void mavlink_test_rc_channels_override(uint8_t system_id, uint8_t compone
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_mission_item_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mission_item_int_t packet_in = {
+ 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,18795,101,168,235,46,113
+ };
+ mavlink_mission_item_int_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.param1 = packet_in.param1;
+ packet1.param2 = packet_in.param2;
+ packet1.param3 = packet_in.param3;
+ packet1.param4 = packet_in.param4;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.seq = packet_in.seq;
+ packet1.command = packet_in.command;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.frame = packet_in.frame;
+ packet1.current = packet_in.current;
+ packet1.autocontinue = packet_in.autocontinue;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mission_item_int_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mission_item_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mission_item_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_mission_item_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mission_item_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_mission_item_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_mission_item_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mission_item_int_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_mission_item_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
static void mavlink_test_vfr_hud(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vfr_hud_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }18067,
- }18171,
- };
+ 17.0,45.0,73.0,101.0,18067,18171
+ };
mavlink_vfr_hud_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.airspeed = packet_in.airspeed;
@@ -3157,24 +2915,69 @@ static void mavlink_test_vfr_hud(uint8_t system_id, uint8_t component_id, mavlin
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_command_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_command_int_t packet_in = {
+ 17.0,45.0,73.0,101.0,963498296,963498504,185.0,18691,223,34,101,168,235
+ };
+ mavlink_command_int_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.param1 = packet_in.param1;
+ packet1.param2 = packet_in.param2;
+ packet1.param3 = packet_in.param3;
+ packet1.param4 = packet_in.param4;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.command = packet_in.command;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.frame = packet_in.frame;
+ packet1.current = packet_in.current;
+ packet1.autocontinue = packet_in.autocontinue;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_command_int_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_command_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_command_int_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_command_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_command_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_command_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_command_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_command_int_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_command_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
static void mavlink_test_command_long(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_long_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }18691,
- }223,
- }34,
- }101,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,18691,223,34,101
+ };
mavlink_command_long_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param1 = packet_in.param1;
@@ -3226,9 +3029,8 @@ static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_ack_t packet_in = {
- 17235,
- }139,
- };
+ 17235,139
+ };
mavlink_command_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.command = packet_in.command;
@@ -3271,12 +3073,8 @@ static void mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(uint8_t system_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- };
+ 963497464,45.0,73.0,101.0,129.0
+ };
mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3322,14 +3120,8 @@ static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_setpoint_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }65,
- }132,
- };
+ 963497464,45.0,73.0,101.0,129.0,65,132
+ };
mavlink_manual_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3377,16 +3169,8 @@ static void mavlink_test_attitude_setpoint_external(uint8_t system_id, uint8_t c
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_setpoint_external_t packet_in = {
- 963497464,
- }{ 45.0, 46.0, 47.0, 48.0 },
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }113,
- }180,
- }247,
- };
+ 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113,180,247
+ };
mavlink_attitude_setpoint_external_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3436,21 +3220,8 @@ static void mavlink_test_local_ned_position_setpoint_external(uint8_t system_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_ned_position_setpoint_external_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }19315,
- }3,
- }70,
- }137,
- };
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,19315,3,70,137
+ };
mavlink_local_ned_position_setpoint_external_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3505,20 +3276,8 @@ static void mavlink_test_global_position_setpoint_external_int(uint8_t system_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_setpoint_external_int_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }19315,
- }3,
- }70,
- };
+ 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,19315,3,70
+ };
mavlink_global_position_setpoint_external_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3572,14 +3331,8 @@ static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_ned_system_global_offset_t packet_in = {
- 963497464,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- };
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0
+ };
mavlink_local_position_ned_system_global_offset_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -3627,23 +3380,8 @@ static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_state_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }963499128,
- }963499336,
- }963499544,
- }19523,
- }19627,
- }19731,
- }19835,
- }19939,
- }20043,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,963499128,963499336,963499544,19523,19627,19731,19835,19939,20043
+ };
mavlink_hil_state_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -3700,18 +3438,8 @@ static void mavlink_test_hil_controls(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_controls_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }125,
- }192,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192
+ };
mavlink_hil_controls_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -3763,21 +3491,8 @@ static void mavlink_test_hil_rc_inputs_raw(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_rc_inputs_raw_t packet_in = {
- 93372036854775807ULL,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- }18379,
- }18483,
- }18587,
- }18691,
- }18795,
- }101,
- };
+ 93372036854775807ULL,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,18691,18795,101
+ };
mavlink_hil_rc_inputs_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -3832,15 +3547,8 @@ static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_optical_flow_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }18275,
- }18379,
- }77,
- }144,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144
+ };
mavlink_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -3889,14 +3597,8 @@ static void mavlink_test_global_vision_position_estimate(uint8_t system_id, uint
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_vision_position_estimate_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0
+ };
mavlink_global_vision_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
@@ -3944,14 +3646,8 @@ static void mavlink_test_vision_position_estimate(uint8_t system_id, uint8_t com
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vision_position_estimate_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0
+ };
mavlink_vision_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
@@ -3999,11 +3695,8 @@ static void mavlink_test_vision_speed_estimate(uint8_t system_id, uint8_t compon
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vision_speed_estimate_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- };
+ 93372036854775807ULL,73.0,101.0,129.0
+ };
mavlink_vision_speed_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
@@ -4048,14 +3741,8 @@ static void mavlink_test_vicon_position_estimate(uint8_t system_id, uint8_t comp
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vicon_position_estimate_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0
+ };
mavlink_vicon_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
@@ -4103,22 +3790,8 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_highres_imu_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }297.0,
- }325.0,
- }353.0,
- }381.0,
- }409.0,
- }20355,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,20355
+ };
mavlink_highres_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4174,13 +3847,8 @@ static void mavlink_test_omnidirectional_flow(uint8_t system_id, uint8_t compone
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_omnidirectional_flow_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }{ 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 },
- }{ 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 },
- }161,
- }228,
- };
+ 93372036854775807ULL,73.0,{ 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 },{ 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 },161,228
+ };
mavlink_omnidirectional_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4227,23 +3895,8 @@ static void mavlink_test_hil_sensor(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_sensor_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }297.0,
- }325.0,
- }353.0,
- }381.0,
- }409.0,
- }437.0,
- }963500792,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,963500792
+ };
mavlink_hil_sensor_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4300,28 +3953,8 @@ static void mavlink_test_sim_state(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sim_state_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }241.0,
- }269.0,
- }297.0,
- }325.0,
- }353.0,
- }381.0,
- }409.0,
- }437.0,
- }465.0,
- }493.0,
- }521.0,
- }549.0,
- }577.0,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,577.0
+ };
mavlink_sim_state_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.q1 = packet_in.q1;
@@ -4383,14 +4016,8 @@ static void mavlink_test_radio_status(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_radio_status_t packet_in = {
- 17235,
- }17339,
- }17,
- }84,
- }151,
- }218,
- }29,
- };
+ 17235,17339,17,84,151,218,29
+ };
mavlink_radio_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rxerrors = packet_in.rxerrors;
@@ -4438,12 +4065,8 @@ static void mavlink_test_file_transfer_start(uint8_t system_id, uint8_t componen
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_start_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- }"MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",
- }249,
- }60,
- };
+ 93372036854775807ULL,963497880,"MNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQ",249,60
+ };
mavlink_file_transfer_start_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
@@ -4489,10 +4112,8 @@ static void mavlink_test_file_transfer_dir_list(uint8_t system_id, uint8_t compo
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_dir_list_t packet_in = {
- 93372036854775807ULL,
- }"IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",
- }237,
- };
+ 93372036854775807ULL,"IJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLM",237
+ };
mavlink_file_transfer_dir_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
@@ -4536,9 +4157,8 @@ static void mavlink_test_file_transfer_res(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_file_transfer_res_t packet_in = {
- 93372036854775807ULL,
- }29,
- };
+ 93372036854775807ULL,29
+ };
mavlink_file_transfer_res_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.transfer_uid = packet_in.transfer_uid;
@@ -4581,20 +4201,8 @@ static void mavlink_test_hil_gps(uint8_t system_id, uint8_t component_id, mavlin
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_gps_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- }963498088,
- }963498296,
- }18275,
- }18379,
- }18483,
- }18587,
- }18691,
- }18795,
- }18899,
- }235,
- }46,
- };
+ 93372036854775807ULL,963497880,963498088,963498296,18275,18379,18483,18587,18691,18795,18899,235,46
+ };
mavlink_hil_gps_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4648,15 +4256,8 @@ static void mavlink_test_hil_optical_flow(uint8_t system_id, uint8_t component_i
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_optical_flow_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }18275,
- }18379,
- }77,
- }144,
- };
+ 93372036854775807ULL,73.0,101.0,129.0,18275,18379,77,144
+ };
mavlink_hil_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4705,23 +4306,8 @@ static void mavlink_test_hil_state_quaternion(uint8_t system_id, uint8_t compone
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_state_quaternion_t packet_in = {
- 93372036854775807ULL,
- }{ 73.0, 74.0, 75.0, 76.0 },
- }185.0,
- }213.0,
- }241.0,
- }963499336,
- }963499544,
- }963499752,
- }19731,
- }19835,
- }19939,
- }20043,
- }20147,
- }20251,
- }20355,
- }20459,
- };
+ 93372036854775807ULL,{ 73.0, 74.0, 75.0, 76.0 },185.0,213.0,241.0,963499336,963499544,963499752,19731,19835,19939,20043,20147,20251,20355,20459
+ };
mavlink_hil_state_quaternion_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -4778,17 +4364,8 @@ static void mavlink_test_scaled_imu2(uint8_t system_id, uint8_t component_id, ma
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_imu2_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- };
+ 963497464,17443,17547,17651,17755,17859,17963,18067,18171,18275
+ };
mavlink_scaled_imu2_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -4839,11 +4416,8 @@ static void mavlink_test_log_request_list(uint8_t system_id, uint8_t component_i
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_request_list_t packet_in = {
- 17235,
- }17339,
- }17,
- }84,
- };
+ 17235,17339,17,84
+ };
mavlink_log_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.start = packet_in.start;
@@ -4888,12 +4462,8 @@ static void mavlink_test_log_entry(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_entry_t packet_in = {
- 963497464,
- }963497672,
- }17651,
- }17755,
- }17859,
- };
+ 963497464,963497672,17651,17755,17859
+ };
mavlink_log_entry_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_utc = packet_in.time_utc;
@@ -4939,12 +4509,8 @@ static void mavlink_test_log_request_data(uint8_t system_id, uint8_t component_i
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_request_data_t packet_in = {
- 963497464,
- }963497672,
- }17651,
- }163,
- }230,
- };
+ 963497464,963497672,17651,163,230
+ };
mavlink_log_request_data_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.ofs = packet_in.ofs;
@@ -4990,11 +4556,8 @@ static void mavlink_test_log_data(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_data_t packet_in = {
- 963497464,
- }17443,
- }151,
- }{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51 },
- };
+ 963497464,17443,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51 }
+ };
mavlink_log_data_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.ofs = packet_in.ofs;
@@ -5039,9 +4602,8 @@ static void mavlink_test_log_erase(uint8_t system_id, uint8_t component_id, mavl
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_erase_t packet_in = {
- 5,
- }72,
- };
+ 5,72
+ };
mavlink_log_erase_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -5084,9 +4646,8 @@ static void mavlink_test_log_request_end(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_log_request_end_t packet_in = {
- 5,
- }72,
- };
+ 5,72
+ };
mavlink_log_request_end_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -5129,11 +4690,8 @@ static void mavlink_test_gps_inject_data(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_inject_data_t packet_in = {
- 5,
- }72,
- }139,
- }{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 },
- };
+ 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59 }
+ };
mavlink_gps_inject_data_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
@@ -5178,19 +4736,8 @@ static void mavlink_test_gps2_raw(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps2_raw_t packet_in = {
- 93372036854775807ULL,
- }963497880,
- }963498088,
- }963498296,
- }963498504,
- }18483,
- }18587,
- }18691,
- }18795,
- }101,
- }168,
- }235,
- };
+ 93372036854775807ULL,963497880,963498088,963498296,963498504,18483,18587,18691,18795,101,168,235
+ };
mavlink_gps2_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -5243,10 +4790,8 @@ static void mavlink_test_power_status(uint8_t system_id, uint8_t component_id, m
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_power_status_t packet_in = {
- 17235,
- }17339,
- }17443,
- };
+ 17235,17339,17443
+ };
mavlink_power_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.Vcc = packet_in.Vcc;
@@ -5290,13 +4835,8 @@ static void mavlink_test_serial_control(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_serial_control_t packet_in = {
- 963497464,
- }17443,
- }151,
- }218,
- }29,
- }{ 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165 },
- };
+ 963497464,17443,151,218,29,{ 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165 }
+ };
mavlink_serial_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.baudrate = packet_in.baudrate;
@@ -5343,20 +4883,8 @@ static void mavlink_test_gps_rtk(uint8_t system_id, uint8_t component_id, mavlin
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_rtk_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }963498088,
- }963498296,
- }963498504,
- }963498712,
- }18691,
- }223,
- }34,
- }101,
- }168,
- }235,
- };
+ 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235
+ };
mavlink_gps_rtk_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms;
@@ -5410,20 +4938,8 @@ static void mavlink_test_gps2_rtk(uint8_t system_id, uint8_t component_id, mavli
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps2_rtk_t packet_in = {
- 963497464,
- }963497672,
- }963497880,
- }963498088,
- }963498296,
- }963498504,
- }963498712,
- }18691,
- }223,
- }34,
- }101,
- }168,
- }235,
- };
+ 963497464,963497672,963497880,963498088,963498296,963498504,963498712,18691,223,34,101,168,235
+ };
mavlink_gps2_rtk_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms;
@@ -5477,14 +4993,8 @@ static void mavlink_test_data_transmission_handshake(uint8_t system_id, uint8_t
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_data_transmission_handshake_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }163,
- }230,
- }41,
- };
+ 963497464,17443,17547,17651,163,230,41
+ };
mavlink_data_transmission_handshake_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.size = packet_in.size;
@@ -5532,9 +5042,8 @@ static void mavlink_test_encapsulated_data(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_encapsulated_data_t packet_in = {
- 17235,
- }{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 },
- };
+ 17235,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135 }
+ };
mavlink_encapsulated_data_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seqnr = packet_in.seqnr;
@@ -5577,15 +5086,8 @@ static void mavlink_test_distance_sensor(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_distance_sensor_t packet_in = {
- 963497464,
- }17443,
- }17547,
- }17651,
- }163,
- }230,
- }41,
- }108,
- };
+ 963497464,17443,17547,17651,163,230,41,108
+ };
mavlink_distance_sensor_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -5628,38 +5130,212 @@ static void mavlink_test_distance_sensor(uint8_t system_id, uint8_t component_id
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_terrain_request(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_terrain_request_t packet_in = {
+ 93372036854775807ULL,963497880,963498088,18067
+ };
+ mavlink_terrain_request_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.mask = packet_in.mask;
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.grid_spacing = packet_in.grid_spacing;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_request_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_terrain_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_request_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
+ mavlink_msg_terrain_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
+ mavlink_msg_terrain_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_terrain_request_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_request_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.mask );
+ mavlink_msg_terrain_request_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_terrain_data(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_terrain_data_t packet_in = {
+ 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764, 17765, 17766, 17767, 17768, 17769, 17770 },3
+ };
+ mavlink_terrain_data_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.grid_spacing = packet_in.grid_spacing;
+ packet1.gridbit = packet_in.gridbit;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(int16_t)*16);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_data_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_terrain_data_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_data_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
+ mavlink_msg_terrain_data_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
+ mavlink_msg_terrain_data_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_terrain_data_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_data_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.grid_spacing , packet1.gridbit , packet1.data );
+ mavlink_msg_terrain_data_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_terrain_check(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_terrain_check_t packet_in = {
+ 963497464,963497672
+ };
+ mavlink_terrain_check_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_check_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_terrain_check_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_check_pack(system_id, component_id, &msg , packet1.lat , packet1.lon );
+ mavlink_msg_terrain_check_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_check_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon );
+ mavlink_msg_terrain_check_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_terrain_check_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_check_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon );
+ mavlink_msg_terrain_check_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_terrain_report(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_terrain_report_t packet_in = {
+ 963497464,963497672,73.0,101.0,18067,18171,18275
+ };
+ mavlink_terrain_report_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.terrain_height = packet_in.terrain_height;
+ packet1.current_height = packet_in.current_height;
+ packet1.spacing = packet_in.spacing;
+ packet1.pending = packet_in.pending;
+ packet1.loaded = packet_in.loaded;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_report_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_terrain_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_report_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded );
+ mavlink_msg_terrain_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded );
+ mavlink_msg_terrain_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_terrain_report_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_terrain_report_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.spacing , packet1.terrain_height , packet1.current_height , packet1.pending , packet1.loaded );
+ mavlink_msg_terrain_report_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_battery_status_t packet_in = {
- 963497464,
- }963497672,
- }17651,
- }17755,
- }17859,
- }17963,
- }18067,
- }18171,
- }18275,
- }199,
- }10,
- };
+ 963497464,963497672,17651,{ 17755, 17756, 17757, 17758, 17759, 17760, 17761, 17762, 17763, 17764 },18795,101,168,235,46
+ };
mavlink_battery_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.current_consumed = packet_in.current_consumed;
packet1.energy_consumed = packet_in.energy_consumed;
- packet1.voltage_cell_1 = packet_in.voltage_cell_1;
- packet1.voltage_cell_2 = packet_in.voltage_cell_2;
- packet1.voltage_cell_3 = packet_in.voltage_cell_3;
- packet1.voltage_cell_4 = packet_in.voltage_cell_4;
- packet1.voltage_cell_5 = packet_in.voltage_cell_5;
- packet1.voltage_cell_6 = packet_in.voltage_cell_6;
+ packet1.temperature = packet_in.temperature;
packet1.current_battery = packet_in.current_battery;
- packet1.accu_id = packet_in.accu_id;
+ packet1.id = packet_in.id;
+ packet1.battery_function = packet_in.battery_function;
+ packet1.type = packet_in.type;
packet1.battery_remaining = packet_in.battery_remaining;
+ mav_array_memcpy(packet1.voltages, packet_in.voltages, sizeof(uint16_t)*10);
memset(&packet2, 0, sizeof(packet2));
@@ -5668,12 +5344,12 @@ static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.accu_id , packet1.voltage_cell_1 , packet1.voltage_cell_2 , packet1.voltage_cell_3 , packet1.voltage_cell_4 , packet1.voltage_cell_5 , packet1.voltage_cell_6 , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
+ mavlink_msg_battery_status_pack(system_id, component_id, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.accu_id , packet1.voltage_cell_1 , packet1.voltage_cell_2 , packet1.voltage_cell_3 , packet1.voltage_cell_4 , packet1.voltage_cell_5 , packet1.voltage_cell_6 , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
+ mavlink_msg_battery_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@@ -5686,7 +5362,7 @@ static void mavlink_test_battery_status(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_battery_status_send(MAVLINK_COMM_1 , packet1.accu_id , packet1.voltage_cell_1 , packet1.voltage_cell_2 , packet1.voltage_cell_3 , packet1.voltage_cell_4 , packet1.voltage_cell_5 , packet1.voltage_cell_6 , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
+ mavlink_msg_battery_status_send(MAVLINK_COMM_1 , packet1.id , packet1.battery_function , packet1.type , packet1.temperature , packet1.voltages , packet1.current_battery , packet1.current_consumed , packet1.energy_consumed , packet1.battery_remaining );
mavlink_msg_battery_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@@ -5697,16 +5373,8 @@ static void mavlink_test_setpoint_8dof(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_setpoint_8dof_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }185.0,
- }213.0,
- }101,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,101
+ };
mavlink_setpoint_8dof_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.val1 = packet_in.val1;
@@ -5756,14 +5424,8 @@ static void mavlink_test_setpoint_6dof(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_setpoint_6dof_t packet_in = {
- 17.0,
- }45.0,
- }73.0,
- }101.0,
- }129.0,
- }157.0,
- }77,
- };
+ 17.0,45.0,73.0,101.0,129.0,157.0,77
+ };
mavlink_setpoint_6dof_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.trans_x = packet_in.trans_x;
@@ -5805,17 +5467,633 @@ static void mavlink_test_setpoint_6dof(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
+static void mavlink_test_autopilot_version(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_autopilot_version_t packet_in = {
+ 93372036854775807ULL,963497880,{ 41, 42, 43, 44, 45, 46, 47, 48 }
+ };
+ mavlink_autopilot_version_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.capabilities = packet_in.capabilities;
+ packet1.version = packet_in.version;
+
+ mav_array_memcpy(packet1.custom_version, packet_in.custom_version, sizeof(uint8_t)*8);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_autopilot_version_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_pack(system_id, component_id, &msg , packet1.capabilities , packet1.version , packet1.custom_version );
+ mavlink_msg_autopilot_version_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.capabilities , packet1.version , packet1.custom_version );
+ mavlink_msg_autopilot_version_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_autopilot_version_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_send(MAVLINK_COMM_1 , packet1.capabilities , packet1.version , packet1.custom_version );
+ mavlink_msg_autopilot_version_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_attitude_quaternion_cov(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_attitude_quaternion_cov_t packet_in = {
+ 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,{ 241.0, 242.0, 243.0, 244.0, 245.0, 246.0, 247.0, 248.0, 249.0 }
+ };
+ mavlink_attitude_quaternion_cov_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.rollspeed = packet_in.rollspeed;
+ packet1.pitchspeed = packet_in.pitchspeed;
+ packet1.yawspeed = packet_in.yawspeed;
+
+ mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
+ mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*9);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_quaternion_cov_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance );
+ mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance );
+ mavlink_msg_attitude_quaternion_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_attitude_quaternion_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_quaternion_cov_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.q , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.covariance );
+ mavlink_msg_attitude_quaternion_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_v2_extension(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_v2_extension_t packet_in = {
+ 17235,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76 }
+ };
+ mavlink_v2_extension_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.message_type = packet_in.message_type;
+ packet1.target_network = packet_in.target_network;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+ mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*249);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_v2_extension_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_v2_extension_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_v2_extension_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload );
+ mavlink_msg_v2_extension_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_v2_extension_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload );
+ mavlink_msg_v2_extension_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_v2_extension_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_v2_extension_send(MAVLINK_COMM_1 , packet1.target_network , packet1.target_system , packet1.target_component , packet1.message_type , packet1.payload );
+ mavlink_msg_v2_extension_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_global_position_int_cov(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_global_position_int_cov_t packet_in = {
+ 93372036854775807ULL,963497880,963498088,963498296,963498504,963498712,213.0,241.0,269.0,{ 297.0, 298.0, 299.0, 300.0, 301.0, 302.0, 303.0, 304.0, 305.0, 306.0, 307.0, 308.0, 309.0, 310.0, 311.0, 312.0, 313.0, 314.0, 315.0, 316.0, 317.0, 318.0, 319.0, 320.0, 321.0, 322.0, 323.0, 324.0, 325.0, 326.0, 327.0, 328.0, 329.0, 330.0, 331.0, 332.0 },45
+ };
+ mavlink_global_position_int_cov_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_utc = packet_in.time_utc;
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.alt = packet_in.alt;
+ packet1.relative_alt = packet_in.relative_alt;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.estimator_type = packet_in.estimator_type;
+
+ mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*36);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_cov_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_global_position_int_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_cov_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_global_position_int_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_global_position_int_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_global_position_int_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_cov_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_global_position_int_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_local_position_ned_cov(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_local_position_ned_cov_t packet_in = {
+ 93372036854775807ULL,963497880,101.0,129.0,157.0,185.0,213.0,241.0,{ 269.0, 270.0, 271.0, 272.0, 273.0, 274.0, 275.0, 276.0, 277.0, 278.0, 279.0, 280.0, 281.0, 282.0, 283.0, 284.0, 285.0, 286.0, 287.0, 288.0, 289.0, 290.0, 291.0, 292.0, 293.0, 294.0, 295.0, 296.0, 297.0, 298.0, 299.0, 300.0, 301.0, 302.0, 303.0, 304.0 },33
+ };
+ mavlink_local_position_ned_cov_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_utc = packet_in.time_utc;
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.estimator_type = packet_in.estimator_type;
+
+ mav_array_memcpy(packet1.covariance, packet_in.covariance, sizeof(float)*36);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_local_position_ned_cov_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_local_position_ned_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_local_position_ned_cov_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_local_position_ned_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_local_position_ned_cov_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_local_position_ned_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_local_position_ned_cov_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.time_utc , packet1.estimator_type , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.covariance );
+ mavlink_msg_local_position_ned_cov_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_set_attitude_target(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_set_attitude_target_t packet_in = {
+ 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113,180,247
+ };
+ mavlink_set_attitude_target_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.body_roll_rate = packet_in.body_roll_rate;
+ packet1.body_pitch_rate = packet_in.body_pitch_rate;
+ packet1.body_yaw_rate = packet_in.body_yaw_rate;
+ packet1.thrust = packet_in.thrust;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.type_mask = packet_in.type_mask;
+
+ mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_attitude_target_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_set_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_set_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_set_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_set_attitude_target_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_attitude_target_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_set_attitude_target_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_attitude_target(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_attitude_target_t packet_in = {
+ 963497464,{ 45.0, 46.0, 47.0, 48.0 },157.0,185.0,213.0,241.0,113
+ };
+ mavlink_attitude_target_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.body_roll_rate = packet_in.body_roll_rate;
+ packet1.body_pitch_rate = packet_in.body_pitch_rate;
+ packet1.body_yaw_rate = packet_in.body_yaw_rate;
+ packet1.thrust = packet_in.thrust;
+ packet1.type_mask = packet_in.type_mask;
+
+ mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_target_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_target_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_attitude_target_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_attitude_target_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_attitude_target_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.type_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust );
+ mavlink_msg_attitude_target_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_set_position_target_local_ned(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_set_position_target_local_ned_t packet_in = {
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161
+ };
+ mavlink_set_position_target_local_ned_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.afx = packet_in.afx;
+ packet1.afy = packet_in.afy;
+ packet1.afz = packet_in.afz;
+ packet1.yaw = packet_in.yaw;
+ packet1.yaw_rate = packet_in.yaw_rate;
+ packet1.type_mask = packet_in.type_mask;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.coordinate_frame = packet_in.coordinate_frame;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_local_ned_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_set_position_target_local_ned_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_local_ned_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_position_target_local_ned(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_position_target_local_ned_t packet_in = {
+ 963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27
+ };
+ mavlink_position_target_local_ned_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.afx = packet_in.afx;
+ packet1.afy = packet_in.afy;
+ packet1.afz = packet_in.afz;
+ packet1.yaw = packet_in.yaw;
+ packet1.yaw_rate = packet_in.yaw_rate;
+ packet1.type_mask = packet_in.type_mask;
+ packet1.coordinate_frame = packet_in.coordinate_frame;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_local_ned_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_local_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_local_ned_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_position_target_local_ned_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_local_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_local_ned_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_set_position_target_global_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_set_position_target_global_int_t packet_in = {
+ 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27,94,161
+ };
+ mavlink_set_position_target_global_int_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.lat_int = packet_in.lat_int;
+ packet1.lon_int = packet_in.lon_int;
+ packet1.alt = packet_in.alt;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.afx = packet_in.afx;
+ packet1.afy = packet_in.afy;
+ packet1.afz = packet_in.afz;
+ packet1.yaw = packet_in.yaw;
+ packet1.yaw_rate = packet_in.yaw_rate;
+ packet1.type_mask = packet_in.type_mask;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.coordinate_frame = packet_in.coordinate_frame;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_global_int_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_set_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_set_position_target_global_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_set_position_target_global_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_position_target_global_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_position_target_global_int_t packet_in = {
+ 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,19731,27
+ };
+ mavlink_position_target_global_int_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.lat_int = packet_in.lat_int;
+ packet1.lon_int = packet_in.lon_int;
+ packet1.alt = packet_in.alt;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.afx = packet_in.afx;
+ packet1.afy = packet_in.afy;
+ packet1.afz = packet_in.afz;
+ packet1.yaw = packet_in.yaw;
+ packet1.yaw_rate = packet_in.yaw_rate;
+ packet1.type_mask = packet_in.type_mask;
+ packet1.coordinate_frame = packet_in.coordinate_frame;
+
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_global_int_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_global_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_global_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_position_target_global_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_position_target_global_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.coordinate_frame , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz , packet1.yaw , packet1.yaw_rate );
+ mavlink_msg_position_target_global_int_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
+static void mavlink_test_file_transfer_protocol(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_file_transfer_protocol_t packet_in = {
+ 5,72,139,{ 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200 }
+ };
+ mavlink_file_transfer_protocol_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_network = packet_in.target_network;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+ mav_array_memcpy(packet1.payload, packet_in.payload, sizeof(uint8_t)*251);
+
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_protocol_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_file_transfer_protocol_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_protocol_pack(system_id, component_id, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload );
+ mavlink_msg_file_transfer_protocol_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload );
+ mavlink_msg_file_transfer_protocol_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_to_send_buffer(buffer, &msg);
+ for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+ comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+ }
+ mavlink_msg_file_transfer_protocol_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_file_transfer_protocol_send(MAVLINK_COMM_1 , packet1.target_network , packet1.target_system , packet1.target_component , packet1.payload );
+ mavlink_msg_file_transfer_protocol_decode(last_msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+}
+
static void mavlink_test_memory_vect(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_memory_vect_t packet_in = {
- 17235,
- }139,
- }206,
- }{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 },
- };
+ 17235,139,206,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 }
+ };
mavlink_memory_vect_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.address = packet_in.address;
@@ -5860,12 +6138,8 @@ static void mavlink_test_debug_vect(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_vect_t packet_in = {
- 93372036854775807ULL,
- }73.0,
- }101.0,
- }129.0,
- }"UVWXYZABC",
- };
+ 93372036854775807ULL,73.0,101.0,129.0,"UVWXYZABC"
+ };
mavlink_debug_vect_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
@@ -5911,10 +6185,8 @@ static void mavlink_test_named_value_float(uint8_t system_id, uint8_t component_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_float_t packet_in = {
- 963497464,
- }45.0,
- }"IJKLMNOPQ",
- };
+ 963497464,45.0,"IJKLMNOPQ"
+ };
mavlink_named_value_float_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -5958,10 +6230,8 @@ static void mavlink_test_named_value_int(uint8_t system_id, uint8_t component_id
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_int_t packet_in = {
- 963497464,
- }963497672,
- }"IJKLMNOPQ",
- };
+ 963497464,963497672,"IJKLMNOPQ"
+ };
mavlink_named_value_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -6005,9 +6275,8 @@ static void mavlink_test_statustext(uint8_t system_id, uint8_t component_id, mav
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_statustext_t packet_in = {
- 5,
- }"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX",
- };
+ 5,"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX"
+ };
mavlink_statustext_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.severity = packet_in.severity;
@@ -6050,10 +6319,8 @@ static void mavlink_test_debug(uint8_t system_id, uint8_t component_id, mavlink_
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_t packet_in = {
- 963497464,
- }45.0,
- }29,
- };
+ 963497464,45.0,29
+ };
mavlink_debug_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
@@ -6151,7 +6418,9 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_data_stream(system_id, component_id, last_msg);
mavlink_test_manual_control(system_id, component_id, last_msg);
mavlink_test_rc_channels_override(system_id, component_id, last_msg);
+ mavlink_test_mission_item_int(system_id, component_id, last_msg);
mavlink_test_vfr_hud(system_id, component_id, last_msg);
+ mavlink_test_command_int(system_id, component_id, last_msg);
mavlink_test_command_long(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_rates_thrust_setpoint(system_id, component_id, last_msg);
@@ -6195,9 +6464,25 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_data_transmission_handshake(system_id, component_id, last_msg);
mavlink_test_encapsulated_data(system_id, component_id, last_msg);
mavlink_test_distance_sensor(system_id, component_id, last_msg);
+ mavlink_test_terrain_request(system_id, component_id, last_msg);
+ mavlink_test_terrain_data(system_id, component_id, last_msg);
+ mavlink_test_terrain_check(system_id, component_id, last_msg);
+ mavlink_test_terrain_report(system_id, component_id, last_msg);
mavlink_test_battery_status(system_id, component_id, last_msg);
mavlink_test_setpoint_8dof(system_id, component_id, last_msg);
mavlink_test_setpoint_6dof(system_id, component_id, last_msg);
+ mavlink_test_autopilot_version(system_id, component_id, last_msg);
+ mavlink_test_attitude_quaternion_cov(system_id, component_id, last_msg);
+ mavlink_test_v2_extension(system_id, component_id, last_msg);
+ mavlink_test_global_position_int_cov(system_id, component_id, last_msg);
+ mavlink_test_local_position_ned_cov(system_id, component_id, last_msg);
+ mavlink_test_set_attitude_target(system_id, component_id, last_msg);
+ mavlink_test_attitude_target(system_id, component_id, last_msg);
+ mavlink_test_set_position_target_local_ned(system_id, component_id, last_msg);
+ mavlink_test_position_target_local_ned(system_id, component_id, last_msg);
+ mavlink_test_set_position_target_global_int(system_id, component_id, last_msg);
+ mavlink_test_position_target_global_int(system_id, component_id, last_msg);
+ mavlink_test_file_transfer_protocol(system_id, component_id, last_msg);
mavlink_test_memory_vect(system_id, component_id, last_msg);
mavlink_test_debug_vect(system_id, component_id, last_msg);
mavlink_test_named_value_float(system_id, component_id, last_msg);
diff --git a/src/include/mavlink/custom/headers/common/version.h b/src/include/mavlink/custom/headers/common/version.h
index 8896585ae..e10118f3c 100644
--- a/src/include/mavlink/custom/headers/common/version.h
+++ b/src/include/mavlink/custom/headers/common/version.h
@@ -1,11 +1,11 @@
/** @file
* @brief MAVLink comm protocol built from common.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
+ * @see http://mavlink.org
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
-#define MAVLINK_BUILD_DATE "Tue Oct 21 18:04:06 2014"
+#define MAVLINK_BUILD_DATE "Sun Oct 26 16:00:39 2014"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
diff --git a/src/include/mavlink/custom/headers/mavlink_conversions.h b/src/include/mavlink/custom/headers/mavlink_conversions.h
index a5da98ab1..beac630a3 100644
--- a/src/include/mavlink/custom/headers/mavlink_conversions.h
+++ b/src/include/mavlink/custom/headers/mavlink_conversions.h
@@ -27,6 +27,13 @@
* @author James Goppert
*/
+
+/**
+ * Converts a quaternion to a rotation matrix
+ *
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ * @param dcm a 3x3 rotation matrix
+ */
MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
{
double a = quaternion[0];
@@ -48,6 +55,15 @@ MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float d
dcm[2][2] = aSq - bSq - cSq + dSq;
}
+
+/**
+ * Converts a rotation matrix to euler angles
+ *
+ * @param dcm a 3x3 rotation matrix
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ */
MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
{
float phi, theta, psi;
@@ -73,6 +89,15 @@ MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, flo
*yaw = psi;
}
+
+/**
+ * Converts a quaternion to euler angles
+ *
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ */
MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
{
float dcm[3][3];
@@ -80,6 +105,15 @@ MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float
mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
}
+
+/**
+ * Converts euler angles to a quaternion
+ *
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ */
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
{
double cosPhi_2 = cos((double)roll / 2.0);
@@ -98,6 +132,13 @@ MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float y
sinPhi_2 * sinTheta_2 * cosPsi_2);
}
+
+/**
+ * Converts a rotation matrix to a quaternion
+ *
+ * @param dcm a 3x3 rotation matrix
+ * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
+ */
MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
{
quaternion[0] = (0.5 * sqrt(1.0 +
@@ -110,6 +151,15 @@ MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quate
(double)(-dcm[0][0] - dcm[1][1] + dcm[2][2])));
}
+
+/**
+ * Converts euler angles to a rotation matrix
+ *
+ * @param roll the roll angle in radians
+ * @param pitch the pitch angle in radians
+ * @param yaw the yaw angle in radians
+ * @param dcm a 3x3 rotation matrix
+ */
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
{
double cosPhi = cos(roll);
diff --git a/src/include/mavlink/custom/headers/mavlink_helpers.h b/src/include/mavlink/custom/headers/mavlink_helpers.h
index 1639a830b..daaf0e37c 100644
--- a/src/include/mavlink/custom/headers/mavlink_helpers.h
+++ b/src/include/mavlink/custom/headers/mavlink_helpers.h
@@ -16,7 +16,7 @@
#ifndef MAVLINK_GET_CHANNEL_STATUS
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
-#if MAVLINK_EXTERNAL_RX_STATUS
+#ifdef MAVLINK_EXTERNAL_RX_STATUS
// No m_mavlink_status array defined in function,
// has to be defined externally
#else
@@ -33,7 +33,7 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
-#if MAVLINK_EXTERNAL_RX_BUFFER
+#ifdef MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_buffer array defined in function,
// has to be defined externally
#else
@@ -209,13 +209,18 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
* it could be successfully decoded. Checksum and other failures will be silently
* ignored.
*
+ * Messages are parsed into an internal buffer (one for each channel). When a complete
+ * message is received it is copies into *returnMsg and the channel's status is
+ * copied into *returnStats.
+ *
* @param chan ID of the current channel. This allows to parse different channels with this function.
* a channel is not a physical message channel like a serial port, but a logic partition of
* the communication streams in this case. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
- * @param c The char to barse
+ * @param c The char to parse
*
* @param returnMsg NULL if no message could be decoded, the message data else
+ * @param returnStats if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded, 1 else
*
* A typical use scenario of this function call is:
@@ -258,7 +263,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
and out). Only use if the channel will only contain messages types listed in
the headers.
*/
-#if MAVLINK_CHECK_MESSAGE_LENGTH
+#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
#ifndef MAVLINK_MESSAGE_LENGTH
static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS;
#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid]
@@ -327,7 +332,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
break;
case MAVLINK_PARSE_STATE_GOT_COMPID:
-#if MAVLINK_CHECK_MESSAGE_LENGTH
+#ifdef MAVLINK_CHECK_MESSAGE_LENGTH
if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c))
{
status->parse_error++;
diff --git a/src/include/mavlink/custom/headers/mavlink_types.h b/src/include/mavlink/custom/headers/mavlink_types.h
index 85ef8c036..de98622c2 100644
--- a/src/include/mavlink/custom/headers/mavlink_types.h
+++ b/src/include/mavlink/custom/headers/mavlink_types.h
@@ -2,7 +2,7 @@
#define MAVLINK_TYPES_H_
// Visual Studio versions before 2013 don't conform to C99.
-#if (defined _MSC_VER) & (_MSC_VER < 1800)
+#if (defined _MSC_VER) && (_MSC_VER < 1800)
#include <stdint.h>
#else
#include <inttypes.h>
@@ -23,7 +23,7 @@
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
-#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
+#if (defined _MSC_VER) || ((defined __APPLE__) && (defined __MACH__)) || (defined __linux__)
/* full fledged 32bit++ OS */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#else
@@ -36,6 +36,8 @@
#pragma pack(push, 1)
/**
+ * Old-style 4 byte param union
+ *
* This struct is the data format to be used when sending
* parameters. The parameter should be copied to the native
* type (without type conversion)
@@ -56,6 +58,39 @@ typedef struct param_union {
uint8_t type;
} mavlink_param_union_t;
+
+/**
+ * New-style 8 byte param union
+ * mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering.
+ * The mavlink_param_union_double_t will be treated as a little-endian structure.
+ *
+ * If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero.
+ * The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the
+ * lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union.
+ * The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above,
+ * as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86,
+ * which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number,
+ * and the bits pulled out using the shifts/masks.
+*/
+typedef union {
+ struct {
+ uint8_t is_double:1;
+ uint8_t mavlink_type:7;
+ union {
+ char c;
+ uint8_t uint8;
+ int8_t int8;
+ uint16_t uint16;
+ int16_t int16;
+ uint32_t uint32;
+ int32_t int32;
+ float f;
+ uint8_t align[7];
+ };
+ };
+ uint8_t data[8];
+} mavlink_param_union_double_t;
+
typedef struct __mavlink_system {
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
@@ -66,7 +101,7 @@ typedef struct __mavlink_system {
} mavlink_system_t;
typedef struct __mavlink_message {
- uint16_t checksum; /// sent at end of packet
+ uint16_t checksum; ///< sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t seq; ///< Sequence of packet
diff --git a/src/include/mavlink/custom/headers/protocol.h b/src/include/mavlink/custom/headers/protocol.h
index 86e7ff588..abebfaa65 100644
--- a/src/include/mavlink/custom/headers/protocol.h
+++ b/src/include/mavlink/custom/headers/protocol.h
@@ -34,46 +34,51 @@
#define MAVLINK_END_UART_SEND(chan, length)
#endif
+/* option to provide alternative implementation of mavlink_helpers.h */
#ifdef MAVLINK_SEPARATE_HELPERS
-#define MAVLINK_HELPER
-#else
-#define MAVLINK_HELPER static inline
-#include "mavlink_helpers.h"
-#endif // MAVLINK_SEPARATE_HELPERS
-/* always include the prototypes to ensure we don't get out of sync */
-#ifndef MAVLINK_GET_CHANNEL_STATUS
-MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
-#endif
-MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
-#if MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length, uint8_t crc_extra);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length, uint8_t crc_extra);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
- uint8_t length, uint8_t crc_extra);
-#endif
+ #define MAVLINK_HELPER
+
+ /* decls in sync with those in mavlink_helpers.h */
+ #ifndef MAVLINK_GET_CHANNEL_STATUS
+ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
+ #endif
+ MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan);
+ #if MAVLINK_CRC_EXTRA
+ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length, uint8_t crc_extra);
+ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length, uint8_t crc_extra);
+ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
+ uint8_t length, uint8_t crc_extra);
+ #endif
+ #else
+ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t chan, uint8_t length);
+ MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
+ uint8_t length);
+ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
+ #endif
+ #endif // MAVLINK_CRC_EXTRA
+ MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
+ MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
+ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
+ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
+ MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
+ uint8_t* r_bit_index, uint8_t* buffer);
+ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
+ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
+ #endif
+
#else
-MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t chan, uint8_t length);
-MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
- uint8_t length);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
-#endif
-#endif // MAVLINK_CRC_EXTRA
-MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
-MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
-MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
-MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
-MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
- uint8_t* r_bit_index, uint8_t* buffer);
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
-MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg);
-#endif
+
+ #define MAVLINK_HELPER static inline
+ #include "mavlink_helpers.h"
+
+#endif // MAVLINK_SEPARATE_HELPERS
/**
* @brief Get the required buffer size for this message
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index dacb401f1..2b3ed11c6 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -939,6 +939,9 @@ private:
MavlinkOrbSubscription *_home_sub;
uint64_t _home_time;
+ MavlinkOrbSubscription *_gps_sub;
+ uint64_t _gps_time;
+
/* do not allow top copying this class */
MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &);
MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &);
@@ -948,16 +951,20 @@ protected:
_pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_global_position))),
_pos_time(0),
_home_sub(_mavlink->add_orb_subscription(ORB_ID(home_position))),
- _home_time(0)
+ _home_time(0),
+ _gps_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position))),
+ _gps_time(0)
{}
void send(const hrt_abstime t)
{
struct vehicle_global_position_s pos;
- struct home_position_s home;
-
- bool updated = _pos_sub->update(&_pos_time, &pos);
- updated |= _home_sub->update(&_home_time, &home);
+ struct home_position_s home;
+ struct vehicle_gps_position_s gps;
+
+ bool updated = _pos_sub->update(&_pos_time, &pos);
+ updated |= _home_sub->update(&_home_time, &home);
+ updated |= _gps_sub->update(&_gps_time, &gps);
if (updated) {
mavlink_global_position_int_t msg;
@@ -1459,7 +1466,7 @@ protected:
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
msg.lon_int = pos_sp_triplet.current.lon * 1e7;
msg.alt = pos_sp_triplet.current.alt;
-
+ msg.yaw = pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f;
_mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, &msg);
}
}
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 367b265cf..2e4971ab8 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -105,7 +105,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_battery_pub(-1),
_cmd_pub(-1),
_flow_pub(-1),
- _range_pub(-1),
+ //_range_pub(-1),
_offboard_control_sp_pub(-1),
_global_vel_sp_pub(-1),
_att_sp_pub(-1),
@@ -437,11 +437,12 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable
r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance);
- if (_range_pub < 0) {
- _range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r);
- } else {
- orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r);
- }
+ //Range finder should be separete from optical flow
+ // if (_range_pub < 0) {
+ // _range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r);
+ // } else {
+ // orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r);
+ // }
}
void