aboutsummaryrefslogtreecommitdiff
path: root/mavlink/include/mavlink/v0.9/pixhawk
diff options
context:
space:
mode:
Diffstat (limited to 'mavlink/include/mavlink/v0.9/pixhawk')
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink.h27
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_attitude_control.h320
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_brief_feature.h292
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h232
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_encapsulated_data.h160
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_available.h628
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_trigger_control.h144
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_triggered.h386
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_marker.h276
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_pattern_detected.h204
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest.h292
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h358
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h254
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h232
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h276
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_raw_aux.h276
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h254
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h276
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h276
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h210
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_command.h210
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h166
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h227
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h254
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/pixhawk.h86
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/testsuite.h1312
-rw-r--r--mavlink/include/mavlink/v0.9/pixhawk/version.h12
27 files changed, 0 insertions, 7640 deletions
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink.h
deleted file mode 100644
index 81c47524b..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from pixhawk.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_H
-#define MAVLINK_H
-
-#ifndef MAVLINK_STX
-#define MAVLINK_STX 85
-#endif
-
-#ifndef MAVLINK_ENDIAN
-#define MAVLINK_ENDIAN MAVLINK_BIG_ENDIAN
-#endif
-
-#ifndef MAVLINK_ALIGNED_FIELDS
-#define MAVLINK_ALIGNED_FIELDS 0
-#endif
-
-#ifndef MAVLINK_CRC_EXTRA
-#define MAVLINK_CRC_EXTRA 0
-#endif
-
-#include "version.h"
-#include "pixhawk.h"
-
-#endif // MAVLINK_H
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_attitude_control.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_attitude_control.h
deleted file mode 100644
index 3d9acdc00..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_attitude_control.h
+++ /dev/null
@@ -1,320 +0,0 @@
-// MESSAGE ATTITUDE_CONTROL PACKING
-
-#define MAVLINK_MSG_ID_ATTITUDE_CONTROL 200
-
-typedef struct __mavlink_attitude_control_t
-{
- uint8_t target; ///< The system to be controlled
- float roll; ///< roll
- float pitch; ///< pitch
- float yaw; ///< yaw
- float thrust; ///< thrust
- uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
- uint8_t pitch_manual; ///< pitch auto:0, manual:1
- uint8_t yaw_manual; ///< yaw auto:0, manual:1
- uint8_t thrust_manual; ///< thrust auto:0, manual:1
-} mavlink_attitude_control_t;
-
-#define MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN 21
-#define MAVLINK_MSG_ID_200_LEN 21
-
-
-
-#define MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL { \
- "ATTITUDE_CONTROL", \
- 9, \
- { { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_attitude_control_t, target) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_attitude_control_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_attitude_control_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_attitude_control_t, yaw) }, \
- { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_attitude_control_t, thrust) }, \
- { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_attitude_control_t, roll_manual) }, \
- { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_attitude_control_t, pitch_manual) }, \
- { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_attitude_control_t, yaw_manual) }, \
- { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_attitude_control_t, thrust_manual) }, \
- } \
-}
-
-
-/**
- * @brief Pack a attitude_control 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 The system to be controlled
- * @param roll roll
- * @param pitch pitch
- * @param yaw yaw
- * @param thrust thrust
- * @param roll_manual roll control enabled auto:0, manual:1
- * @param pitch_manual pitch auto:0, manual:1
- * @param yaw_manual yaw auto:0, manual:1
- * @param thrust_manual thrust auto:0, manual:1
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[21];
- _mav_put_uint8_t(buf, 0, target);
- _mav_put_float(buf, 1, roll);
- _mav_put_float(buf, 5, pitch);
- _mav_put_float(buf, 9, yaw);
- _mav_put_float(buf, 13, thrust);
- _mav_put_uint8_t(buf, 17, roll_manual);
- _mav_put_uint8_t(buf, 18, pitch_manual);
- _mav_put_uint8_t(buf, 19, yaw_manual);
- _mav_put_uint8_t(buf, 20, thrust_manual);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
-#else
- mavlink_attitude_control_t packet;
- packet.target = target;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.thrust = thrust;
- packet.roll_manual = roll_manual;
- packet.pitch_manual = pitch_manual;
- packet.yaw_manual = yaw_manual;
- packet.thrust_manual = thrust_manual;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
- return mavlink_finalize_message(msg, system_id, component_id, 21);
-}
-
-/**
- * @brief Pack a attitude_control 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target The system to be controlled
- * @param roll roll
- * @param pitch pitch
- * @param yaw yaw
- * @param thrust thrust
- * @param roll_manual roll control enabled auto:0, manual:1
- * @param pitch_manual pitch auto:0, manual:1
- * @param yaw_manual yaw auto:0, manual:1
- * @param thrust_manual thrust auto:0, manual:1
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[21];
- _mav_put_uint8_t(buf, 0, target);
- _mav_put_float(buf, 1, roll);
- _mav_put_float(buf, 5, pitch);
- _mav_put_float(buf, 9, yaw);
- _mav_put_float(buf, 13, thrust);
- _mav_put_uint8_t(buf, 17, roll_manual);
- _mav_put_uint8_t(buf, 18, pitch_manual);
- _mav_put_uint8_t(buf, 19, yaw_manual);
- _mav_put_uint8_t(buf, 20, thrust_manual);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
-#else
- mavlink_attitude_control_t packet;
- packet.target = target;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.thrust = thrust;
- packet.roll_manual = roll_manual;
- packet.pitch_manual = pitch_manual;
- packet.yaw_manual = yaw_manual;
- packet.thrust_manual = thrust_manual;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21);
-}
-
-/**
- * @brief Encode a attitude_control struct into a 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 attitude_control C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control)
-{
- return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual);
-}
-
-/**
- * @brief Send a attitude_control message
- * @param chan MAVLink channel to send the message
- *
- * @param target The system to be controlled
- * @param roll roll
- * @param pitch pitch
- * @param yaw yaw
- * @param thrust thrust
- * @param roll_manual roll control enabled auto:0, manual:1
- * @param pitch_manual pitch auto:0, manual:1
- * @param yaw_manual yaw auto:0, manual:1
- * @param thrust_manual thrust auto:0, manual:1
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[21];
- _mav_put_uint8_t(buf, 0, target);
- _mav_put_float(buf, 1, roll);
- _mav_put_float(buf, 5, pitch);
- _mav_put_float(buf, 9, yaw);
- _mav_put_float(buf, 13, thrust);
- _mav_put_uint8_t(buf, 17, roll_manual);
- _mav_put_uint8_t(buf, 18, pitch_manual);
- _mav_put_uint8_t(buf, 19, yaw_manual);
- _mav_put_uint8_t(buf, 20, thrust_manual);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, 21);
-#else
- mavlink_attitude_control_t packet;
- packet.target = target;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.thrust = thrust;
- packet.roll_manual = roll_manual;
- packet.pitch_manual = pitch_manual;
- packet.yaw_manual = yaw_manual;
- packet.thrust_manual = thrust_manual;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, 21);
-#endif
-}
-
-#endif
-
-// MESSAGE ATTITUDE_CONTROL UNPACKING
-
-
-/**
- * @brief Get field target from attitude_control message
- *
- * @return The system to be controlled
- */
-static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field roll from attitude_control message
- *
- * @return roll
- */
-static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 1);
-}
-
-/**
- * @brief Get field pitch from attitude_control message
- *
- * @return pitch
- */
-static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 5);
-}
-
-/**
- * @brief Get field yaw from attitude_control message
- *
- * @return yaw
- */
-static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 9);
-}
-
-/**
- * @brief Get field thrust from attitude_control message
- *
- * @return thrust
- */
-static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 13);
-}
-
-/**
- * @brief Get field roll_manual from attitude_control message
- *
- * @return roll control enabled auto:0, manual:1
- */
-static inline uint8_t mavlink_msg_attitude_control_get_roll_manual(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 17);
-}
-
-/**
- * @brief Get field pitch_manual from attitude_control message
- *
- * @return pitch auto:0, manual:1
- */
-static inline uint8_t mavlink_msg_attitude_control_get_pitch_manual(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 18);
-}
-
-/**
- * @brief Get field yaw_manual from attitude_control message
- *
- * @return yaw auto:0, manual:1
- */
-static inline uint8_t mavlink_msg_attitude_control_get_yaw_manual(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 19);
-}
-
-/**
- * @brief Get field thrust_manual from attitude_control message
- *
- * @return thrust auto:0, manual:1
- */
-static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 20);
-}
-
-/**
- * @brief Decode a attitude_control message into a struct
- *
- * @param msg The message to decode
- * @param attitude_control C-struct to decode the message contents into
- */
-static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- attitude_control->target = mavlink_msg_attitude_control_get_target(msg);
- attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg);
- attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg);
- attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg);
- attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg);
- attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg);
- attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg);
- attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg);
- attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg);
-#else
- memcpy(attitude_control, _MAV_PAYLOAD(msg), 21);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_brief_feature.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_brief_feature.h
deleted file mode 100644
index 866d1be44..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_brief_feature.h
+++ /dev/null
@@ -1,292 +0,0 @@
-// MESSAGE BRIEF_FEATURE PACKING
-
-#define MAVLINK_MSG_ID_BRIEF_FEATURE 195
-
-typedef struct __mavlink_brief_feature_t
-{
- float x; ///< x position in m
- float y; ///< y position in m
- float z; ///< z position in m
- uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true
- uint16_t size; ///< Size in pixels
- uint16_t orientation; ///< Orientation
- uint8_t descriptor[32]; ///< Descriptor
- float response; ///< Harris operator response at this location
-} mavlink_brief_feature_t;
-
-#define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53
-#define MAVLINK_MSG_ID_195_LEN 53
-
-#define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32
-
-#define MAVLINK_MESSAGE_INFO_BRIEF_FEATURE { \
- "BRIEF_FEATURE", \
- 8, \
- { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_brief_feature_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_brief_feature_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_brief_feature_t, z) }, \
- { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \
- { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 13, offsetof(mavlink_brief_feature_t, size) }, \
- { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 15, offsetof(mavlink_brief_feature_t, orientation) }, \
- { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 17, offsetof(mavlink_brief_feature_t, descriptor) }, \
- { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 49, offsetof(mavlink_brief_feature_t, response) }, \
- } \
-}
-
-
-/**
- * @brief Pack a brief_feature 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 x x position in m
- * @param y y position in m
- * @param z z position in m
- * @param orientation_assignment Orientation assignment 0: false, 1:true
- * @param size Size in pixels
- * @param orientation Orientation
- * @param descriptor Descriptor
- * @param response Harris operator response at this location
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[53];
- _mav_put_float(buf, 0, x);
- _mav_put_float(buf, 4, y);
- _mav_put_float(buf, 8, z);
- _mav_put_uint8_t(buf, 12, orientation_assignment);
- _mav_put_uint16_t(buf, 13, size);
- _mav_put_uint16_t(buf, 15, orientation);
- _mav_put_float(buf, 49, response);
- _mav_put_uint8_t_array(buf, 17, descriptor, 32);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53);
-#else
- mavlink_brief_feature_t packet;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.orientation_assignment = orientation_assignment;
- packet.size = size;
- packet.orientation = orientation;
- packet.response = response;
- mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
- return mavlink_finalize_message(msg, system_id, component_id, 53);
-}
-
-/**
- * @brief Pack a brief_feature 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param x x position in m
- * @param y y position in m
- * @param z z position in m
- * @param orientation_assignment Orientation assignment 0: false, 1:true
- * @param size Size in pixels
- * @param orientation Orientation
- * @param descriptor Descriptor
- * @param response Harris operator response at this location
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- float x,float y,float z,uint8_t orientation_assignment,uint16_t size,uint16_t orientation,const uint8_t *descriptor,float response)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[53];
- _mav_put_float(buf, 0, x);
- _mav_put_float(buf, 4, y);
- _mav_put_float(buf, 8, z);
- _mav_put_uint8_t(buf, 12, orientation_assignment);
- _mav_put_uint16_t(buf, 13, size);
- _mav_put_uint16_t(buf, 15, orientation);
- _mav_put_float(buf, 49, response);
- _mav_put_uint8_t_array(buf, 17, descriptor, 32);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53);
-#else
- mavlink_brief_feature_t packet;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.orientation_assignment = orientation_assignment;
- packet.size = size;
- packet.orientation = orientation;
- packet.response = response;
- mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53);
-}
-
-/**
- * @brief Encode a brief_feature struct into a 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 brief_feature C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature)
-{
- return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response);
-}
-
-/**
- * @brief Send a brief_feature message
- * @param chan MAVLink channel to send the message
- *
- * @param x x position in m
- * @param y y position in m
- * @param z z position in m
- * @param orientation_assignment Orientation assignment 0: false, 1:true
- * @param size Size in pixels
- * @param orientation Orientation
- * @param descriptor Descriptor
- * @param response Harris operator response at this location
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[53];
- _mav_put_float(buf, 0, x);
- _mav_put_float(buf, 4, y);
- _mav_put_float(buf, 8, z);
- _mav_put_uint8_t(buf, 12, orientation_assignment);
- _mav_put_uint16_t(buf, 13, size);
- _mav_put_uint16_t(buf, 15, orientation);
- _mav_put_float(buf, 49, response);
- _mav_put_uint8_t_array(buf, 17, descriptor, 32);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, 53);
-#else
- mavlink_brief_feature_t packet;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.orientation_assignment = orientation_assignment;
- packet.size = size;
- packet.orientation = orientation;
- packet.response = response;
- mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, 53);
-#endif
-}
-
-#endif
-
-// MESSAGE BRIEF_FEATURE UNPACKING
-
-
-/**
- * @brief Get field x from brief_feature message
- *
- * @return x position in m
- */
-static inline float mavlink_msg_brief_feature_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 0);
-}
-
-/**
- * @brief Get field y from brief_feature message
- *
- * @return y position in m
- */
-static inline float mavlink_msg_brief_feature_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field z from brief_feature message
- *
- * @return z position in m
- */
-static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field orientation_assignment from brief_feature message
- *
- * @return Orientation assignment 0: false, 1:true
- */
-static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 12);
-}
-
-/**
- * @brief Get field size from brief_feature message
- *
- * @return Size in pixels
- */
-static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 13);
-}
-
-/**
- * @brief Get field orientation from brief_feature message
- *
- * @return Orientation
- */
-static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 15);
-}
-
-/**
- * @brief Get field descriptor from brief_feature message
- *
- * @return Descriptor
- */
-static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t *descriptor)
-{
- return _MAV_RETURN_uint8_t_array(msg, descriptor, 32, 17);
-}
-
-/**
- * @brief Get field response from brief_feature message
- *
- * @return Harris operator response at this location
- */
-static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 49);
-}
-
-/**
- * @brief Decode a brief_feature message into a struct
- *
- * @param msg The message to decode
- * @param brief_feature C-struct to decode the message contents into
- */
-static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- brief_feature->x = mavlink_msg_brief_feature_get_x(msg);
- brief_feature->y = mavlink_msg_brief_feature_get_y(msg);
- brief_feature->z = mavlink_msg_brief_feature_get_z(msg);
- brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg);
- brief_feature->size = mavlink_msg_brief_feature_get_size(msg);
- brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg);
- mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor);
- brief_feature->response = mavlink_msg_brief_feature_get_response(msg);
-#else
- memcpy(brief_feature, _MAV_PAYLOAD(msg), 53);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h
deleted file mode 100644
index 9c0d75a9a..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_data_transmission_handshake.h
+++ /dev/null
@@ -1,232 +0,0 @@
-// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
-
-#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 193
-
-typedef struct __mavlink_data_transmission_handshake_t
-{
- uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
- uint32_t size; ///< total data size in bytes (set on ACK only)
- uint8_t packets; ///< number of packets beeing sent (set on ACK only)
- uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
- uint8_t jpg_quality; ///< JPEG quality out of [1,100]
-} mavlink_data_transmission_handshake_t;
-
-#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 8
-#define MAVLINK_MSG_ID_193_LEN 8
-
-
-
-#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \
- "DATA_TRANSMISSION_HANDSHAKE", \
- 5, \
- { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, type) }, \
- { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 1, offsetof(mavlink_data_transmission_handshake_t, size) }, \
- { "packets", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
- { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
- { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
- } \
-}
-
-
-/**
- * @brief Pack a data_transmission_handshake 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 type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
- * @param size total data size in bytes (set on ACK only)
- * @param packets number of packets beeing sent (set on ACK only)
- * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
- * @param jpg_quality JPEG quality out of [1,100]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[8];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint32_t(buf, 1, size);
- _mav_put_uint8_t(buf, 5, packets);
- _mav_put_uint8_t(buf, 6, payload);
- _mav_put_uint8_t(buf, 7, jpg_quality);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
-#else
- mavlink_data_transmission_handshake_t packet;
- packet.type = type;
- packet.size = size;
- packet.packets = packets;
- packet.payload = payload;
- packet.jpg_quality = jpg_quality;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
- return mavlink_finalize_message(msg, system_id, component_id, 8);
-}
-
-/**
- * @brief Pack a data_transmission_handshake 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
- * @param size total data size in bytes (set on ACK only)
- * @param packets number of packets beeing sent (set on ACK only)
- * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
- * @param jpg_quality JPEG quality out of [1,100]
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t type,uint32_t size,uint8_t packets,uint8_t payload,uint8_t jpg_quality)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[8];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint32_t(buf, 1, size);
- _mav_put_uint8_t(buf, 5, packets);
- _mav_put_uint8_t(buf, 6, payload);
- _mav_put_uint8_t(buf, 7, jpg_quality);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
-#else
- mavlink_data_transmission_handshake_t packet;
- packet.type = type;
- packet.size = size;
- packet.packets = packets;
- packet.payload = payload;
- packet.jpg_quality = jpg_quality;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
-}
-
-/**
- * @brief Encode a data_transmission_handshake struct into a 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 data_transmission_handshake C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
-{
- return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
-}
-
-/**
- * @brief Send a data_transmission_handshake message
- * @param chan MAVLink channel to send the message
- *
- * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
- * @param size total data size in bytes (set on ACK only)
- * @param packets number of packets beeing sent (set on ACK only)
- * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
- * @param jpg_quality JPEG quality out of [1,100]
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[8];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint32_t(buf, 1, size);
- _mav_put_uint8_t(buf, 5, packets);
- _mav_put_uint8_t(buf, 6, payload);
- _mav_put_uint8_t(buf, 7, jpg_quality);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, 8);
-#else
- mavlink_data_transmission_handshake_t packet;
- packet.type = type;
- packet.size = size;
- packet.packets = packets;
- packet.payload = payload;
- packet.jpg_quality = jpg_quality;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, 8);
-#endif
-}
-
-#endif
-
-// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
-
-
-/**
- * @brief Get field type from data_transmission_handshake message
- *
- * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
- */
-static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field size from data_transmission_handshake message
- *
- * @return total data size in bytes (set on ACK only)
- */
-static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 1);
-}
-
-/**
- * @brief Get field packets from data_transmission_handshake message
- *
- * @return number of packets beeing sent (set on ACK only)
- */
-static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Get field payload from data_transmission_handshake message
- *
- * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
- */
-static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 6);
-}
-
-/**
- * @brief Get field jpg_quality from data_transmission_handshake message
- *
- * @return JPEG quality out of [1,100]
- */
-static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 7);
-}
-
-/**
- * @brief Decode a data_transmission_handshake message into a struct
- *
- * @param msg The message to decode
- * @param data_transmission_handshake C-struct to decode the message contents into
- */
-static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
- data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
- data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
- data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
- data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
-#else
- memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), 8);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_encapsulated_data.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_encapsulated_data.h
deleted file mode 100644
index 705a6cc29..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_encapsulated_data.h
+++ /dev/null
@@ -1,160 +0,0 @@
-// MESSAGE ENCAPSULATED_DATA PACKING
-
-#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 194
-
-typedef struct __mavlink_encapsulated_data_t
-{
- uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
- uint8_t data[253]; ///< image data bytes
-} mavlink_encapsulated_data_t;
-
-#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
-#define MAVLINK_MSG_ID_194_LEN 255
-
-#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
-
-#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \
- "ENCAPSULATED_DATA", \
- 2, \
- { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \
- { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \
- } \
-}
-
-
-/**
- * @brief Pack a encapsulated_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 seqnr sequence number (starting with 0 on every transmission)
- * @param data image data bytes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t seqnr, const uint8_t *data)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, seqnr);
- _mav_put_uint8_t_array(buf, 2, data, 253);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255);
-#else
- mavlink_encapsulated_data_t packet;
- packet.seqnr = seqnr;
- mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
- return mavlink_finalize_message(msg, system_id, component_id, 255);
-}
-
-/**
- * @brief Pack a encapsulated_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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param seqnr sequence number (starting with 0 on every transmission)
- * @param data image data bytes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t seqnr,const uint8_t *data)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, seqnr);
- _mav_put_uint8_t_array(buf, 2, data, 253);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255);
-#else
- mavlink_encapsulated_data_t packet;
- packet.seqnr = seqnr;
- mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255);
-}
-
-/**
- * @brief Encode a encapsulated_data struct into a 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 encapsulated_data C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
-{
- return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
-}
-
-/**
- * @brief Send a encapsulated_data message
- * @param chan MAVLink channel to send the message
- *
- * @param seqnr sequence number (starting with 0 on every transmission)
- * @param data image data bytes
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, seqnr);
- _mav_put_uint8_t_array(buf, 2, data, 253);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, 255);
-#else
- mavlink_encapsulated_data_t packet;
- packet.seqnr = seqnr;
- mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, 255);
-#endif
-}
-
-#endif
-
-// MESSAGE ENCAPSULATED_DATA UNPACKING
-
-
-/**
- * @brief Get field seqnr from encapsulated_data message
- *
- * @return sequence number (starting with 0 on every transmission)
- */
-static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field data from encapsulated_data message
- *
- * @return image data bytes
- */
-static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data)
-{
- return _MAV_RETURN_uint8_t_array(msg, data, 253, 2);
-}
-
-/**
- * @brief Decode a encapsulated_data message into a struct
- *
- * @param msg The message to decode
- * @param encapsulated_data C-struct to decode the message contents into
- */
-static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
- mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
-#else
- memcpy(encapsulated_data, _MAV_PAYLOAD(msg), 255);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_available.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_available.h
deleted file mode 100644
index 40d1901c6..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_available.h
+++ /dev/null
@@ -1,628 +0,0 @@
-// MESSAGE IMAGE_AVAILABLE PACKING
-
-#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 154
-
-typedef struct __mavlink_image_available_t
-{
- uint64_t cam_id; ///< Camera id
- uint8_t cam_no; ///< Camera # (starts with 0)
- uint64_t timestamp; ///< Timestamp
- uint64_t valid_until; ///< Until which timestamp this buffer will stay valid
- uint32_t img_seq; ///< The image sequence number
- uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0
- uint16_t width; ///< Image width
- uint16_t height; ///< Image height
- uint16_t depth; ///< Image depth
- uint8_t channels; ///< Image channels
- uint32_t key; ///< Shared memory area key
- uint32_t exposure; ///< Exposure time, in microseconds
- float gain; ///< Camera gain
- float roll; ///< Roll angle in rad
- float pitch; ///< Pitch angle in rad
- float yaw; ///< Yaw angle in rad
- float local_z; ///< Local frame Z coordinate (height over ground)
- float lat; ///< GPS X coordinate
- float lon; ///< GPS Y coordinate
- float alt; ///< Global frame altitude
- float ground_x; ///< Ground truth X
- float ground_y; ///< Ground truth Y
- float ground_z; ///< Ground truth Z
-} mavlink_image_available_t;
-
-#define MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN 92
-#define MAVLINK_MSG_ID_154_LEN 92
-
-
-
-#define MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE { \
- "IMAGE_AVAILABLE", \
- 23, \
- { { "cam_id", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_available_t, cam_id) }, \
- { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_image_available_t, cam_no) }, \
- { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 9, offsetof(mavlink_image_available_t, timestamp) }, \
- { "valid_until", NULL, MAVLINK_TYPE_UINT64_T, 0, 17, offsetof(mavlink_image_available_t, valid_until) }, \
- { "img_seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 25, offsetof(mavlink_image_available_t, img_seq) }, \
- { "img_buf_index", NULL, MAVLINK_TYPE_UINT32_T, 0, 29, offsetof(mavlink_image_available_t, img_buf_index) }, \
- { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 33, offsetof(mavlink_image_available_t, width) }, \
- { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_image_available_t, height) }, \
- { "depth", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_image_available_t, depth) }, \
- { "channels", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_image_available_t, channels) }, \
- { "key", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_image_available_t, key) }, \
- { "exposure", NULL, MAVLINK_TYPE_UINT32_T, 0, 44, offsetof(mavlink_image_available_t, exposure) }, \
- { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_available_t, gain) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_image_available_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_image_available_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_image_available_t, yaw) }, \
- { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_image_available_t, local_z) }, \
- { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_image_available_t, lat) }, \
- { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_image_available_t, lon) }, \
- { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_image_available_t, alt) }, \
- { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_image_available_t, ground_x) }, \
- { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_image_available_t, ground_y) }, \
- { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 88, offsetof(mavlink_image_available_t, ground_z) }, \
- } \
-}
-
-
-/**
- * @brief Pack a image_available 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 cam_id Camera id
- * @param cam_no Camera # (starts with 0)
- * @param timestamp Timestamp
- * @param valid_until Until which timestamp this buffer will stay valid
- * @param img_seq The image sequence number
- * @param img_buf_index Position of the image in the buffer, starts with 0
- * @param width Image width
- * @param height Image height
- * @param depth Image depth
- * @param channels Image channels
- * @param key Shared memory area key
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[92];
- _mav_put_uint64_t(buf, 0, cam_id);
- _mav_put_uint8_t(buf, 8, cam_no);
- _mav_put_uint64_t(buf, 9, timestamp);
- _mav_put_uint64_t(buf, 17, valid_until);
- _mav_put_uint32_t(buf, 25, img_seq);
- _mav_put_uint32_t(buf, 29, img_buf_index);
- _mav_put_uint16_t(buf, 33, width);
- _mav_put_uint16_t(buf, 35, height);
- _mav_put_uint16_t(buf, 37, depth);
- _mav_put_uint8_t(buf, 39, channels);
- _mav_put_uint32_t(buf, 40, key);
- _mav_put_uint32_t(buf, 44, exposure);
- _mav_put_float(buf, 48, gain);
- _mav_put_float(buf, 52, roll);
- _mav_put_float(buf, 56, pitch);
- _mav_put_float(buf, 60, yaw);
- _mav_put_float(buf, 64, local_z);
- _mav_put_float(buf, 68, lat);
- _mav_put_float(buf, 72, lon);
- _mav_put_float(buf, 76, alt);
- _mav_put_float(buf, 80, ground_x);
- _mav_put_float(buf, 84, ground_y);
- _mav_put_float(buf, 88, ground_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92);
-#else
- mavlink_image_available_t packet;
- packet.cam_id = cam_id;
- packet.cam_no = cam_no;
- packet.timestamp = timestamp;
- packet.valid_until = valid_until;
- packet.img_seq = img_seq;
- packet.img_buf_index = img_buf_index;
- packet.width = width;
- packet.height = height;
- packet.depth = depth;
- packet.channels = channels;
- packet.key = key;
- packet.exposure = exposure;
- packet.gain = gain;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
- return mavlink_finalize_message(msg, system_id, component_id, 92);
-}
-
-/**
- * @brief Pack a image_available 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param cam_id Camera id
- * @param cam_no Camera # (starts with 0)
- * @param timestamp Timestamp
- * @param valid_until Until which timestamp this buffer will stay valid
- * @param img_seq The image sequence number
- * @param img_buf_index Position of the image in the buffer, starts with 0
- * @param width Image width
- * @param height Image height
- * @param depth Image depth
- * @param channels Image channels
- * @param key Shared memory area key
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t cam_id,uint8_t cam_no,uint64_t timestamp,uint64_t valid_until,uint32_t img_seq,uint32_t img_buf_index,uint16_t width,uint16_t height,uint16_t depth,uint8_t channels,uint32_t key,uint32_t exposure,float gain,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[92];
- _mav_put_uint64_t(buf, 0, cam_id);
- _mav_put_uint8_t(buf, 8, cam_no);
- _mav_put_uint64_t(buf, 9, timestamp);
- _mav_put_uint64_t(buf, 17, valid_until);
- _mav_put_uint32_t(buf, 25, img_seq);
- _mav_put_uint32_t(buf, 29, img_buf_index);
- _mav_put_uint16_t(buf, 33, width);
- _mav_put_uint16_t(buf, 35, height);
- _mav_put_uint16_t(buf, 37, depth);
- _mav_put_uint8_t(buf, 39, channels);
- _mav_put_uint32_t(buf, 40, key);
- _mav_put_uint32_t(buf, 44, exposure);
- _mav_put_float(buf, 48, gain);
- _mav_put_float(buf, 52, roll);
- _mav_put_float(buf, 56, pitch);
- _mav_put_float(buf, 60, yaw);
- _mav_put_float(buf, 64, local_z);
- _mav_put_float(buf, 68, lat);
- _mav_put_float(buf, 72, lon);
- _mav_put_float(buf, 76, alt);
- _mav_put_float(buf, 80, ground_x);
- _mav_put_float(buf, 84, ground_y);
- _mav_put_float(buf, 88, ground_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 92);
-#else
- mavlink_image_available_t packet;
- packet.cam_id = cam_id;
- packet.cam_no = cam_no;
- packet.timestamp = timestamp;
- packet.valid_until = valid_until;
- packet.img_seq = img_seq;
- packet.img_buf_index = img_buf_index;
- packet.width = width;
- packet.height = height;
- packet.depth = depth;
- packet.channels = channels;
- packet.key = key;
- packet.exposure = exposure;
- packet.gain = gain;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 92);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 92);
-}
-
-/**
- * @brief Encode a image_available struct into a 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 image_available C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available)
-{
- return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z);
-}
-
-/**
- * @brief Send a image_available message
- * @param chan MAVLink channel to send the message
- *
- * @param cam_id Camera id
- * @param cam_no Camera # (starts with 0)
- * @param timestamp Timestamp
- * @param valid_until Until which timestamp this buffer will stay valid
- * @param img_seq The image sequence number
- * @param img_buf_index Position of the image in the buffer, starts with 0
- * @param width Image width
- * @param height Image height
- * @param depth Image depth
- * @param channels Image channels
- * @param key Shared memory area key
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[92];
- _mav_put_uint64_t(buf, 0, cam_id);
- _mav_put_uint8_t(buf, 8, cam_no);
- _mav_put_uint64_t(buf, 9, timestamp);
- _mav_put_uint64_t(buf, 17, valid_until);
- _mav_put_uint32_t(buf, 25, img_seq);
- _mav_put_uint32_t(buf, 29, img_buf_index);
- _mav_put_uint16_t(buf, 33, width);
- _mav_put_uint16_t(buf, 35, height);
- _mav_put_uint16_t(buf, 37, depth);
- _mav_put_uint8_t(buf, 39, channels);
- _mav_put_uint32_t(buf, 40, key);
- _mav_put_uint32_t(buf, 44, exposure);
- _mav_put_float(buf, 48, gain);
- _mav_put_float(buf, 52, roll);
- _mav_put_float(buf, 56, pitch);
- _mav_put_float(buf, 60, yaw);
- _mav_put_float(buf, 64, local_z);
- _mav_put_float(buf, 68, lat);
- _mav_put_float(buf, 72, lon);
- _mav_put_float(buf, 76, alt);
- _mav_put_float(buf, 80, ground_x);
- _mav_put_float(buf, 84, ground_y);
- _mav_put_float(buf, 88, ground_z);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, 92);
-#else
- mavlink_image_available_t packet;
- packet.cam_id = cam_id;
- packet.cam_no = cam_no;
- packet.timestamp = timestamp;
- packet.valid_until = valid_until;
- packet.img_seq = img_seq;
- packet.img_buf_index = img_buf_index;
- packet.width = width;
- packet.height = height;
- packet.depth = depth;
- packet.channels = channels;
- packet.key = key;
- packet.exposure = exposure;
- packet.gain = gain;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, 92);
-#endif
-}
-
-#endif
-
-// MESSAGE IMAGE_AVAILABLE UNPACKING
-
-
-/**
- * @brief Get field cam_id from image_available message
- *
- * @return Camera id
- */
-static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field cam_no from image_available message
- *
- * @return Camera # (starts with 0)
- */
-static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 8);
-}
-
-/**
- * @brief Get field timestamp from image_available message
- *
- * @return Timestamp
- */
-static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 9);
-}
-
-/**
- * @brief Get field valid_until from image_available message
- *
- * @return Until which timestamp this buffer will stay valid
- */
-static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 17);
-}
-
-/**
- * @brief Get field img_seq from image_available message
- *
- * @return The image sequence number
- */
-static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 25);
-}
-
-/**
- * @brief Get field img_buf_index from image_available message
- *
- * @return Position of the image in the buffer, starts with 0
- */
-static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 29);
-}
-
-/**
- * @brief Get field width from image_available message
- *
- * @return Image width
- */
-static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 33);
-}
-
-/**
- * @brief Get field height from image_available message
- *
- * @return Image height
- */
-static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 35);
-}
-
-/**
- * @brief Get field depth from image_available message
- *
- * @return Image depth
- */
-static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 37);
-}
-
-/**
- * @brief Get field channels from image_available message
- *
- * @return Image channels
- */
-static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 39);
-}
-
-/**
- * @brief Get field key from image_available message
- *
- * @return Shared memory area key
- */
-static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 40);
-}
-
-/**
- * @brief Get field exposure from image_available message
- *
- * @return Exposure time, in microseconds
- */
-static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 44);
-}
-
-/**
- * @brief Get field gain from image_available message
- *
- * @return Camera gain
- */
-static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Get field roll from image_available message
- *
- * @return Roll angle in rad
- */
-static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 52);
-}
-
-/**
- * @brief Get field pitch from image_available message
- *
- * @return Pitch angle in rad
- */
-static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 56);
-}
-
-/**
- * @brief Get field yaw from image_available message
- *
- * @return Yaw angle in rad
- */
-static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 60);
-}
-
-/**
- * @brief Get field local_z from image_available message
- *
- * @return Local frame Z coordinate (height over ground)
- */
-static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 64);
-}
-
-/**
- * @brief Get field lat from image_available message
- *
- * @return GPS X coordinate
- */
-static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 68);
-}
-
-/**
- * @brief Get field lon from image_available message
- *
- * @return GPS Y coordinate
- */
-static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 72);
-}
-
-/**
- * @brief Get field alt from image_available message
- *
- * @return Global frame altitude
- */
-static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 76);
-}
-
-/**
- * @brief Get field ground_x from image_available message
- *
- * @return Ground truth X
- */
-static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 80);
-}
-
-/**
- * @brief Get field ground_y from image_available message
- *
- * @return Ground truth Y
- */
-static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 84);
-}
-
-/**
- * @brief Get field ground_z from image_available message
- *
- * @return Ground truth Z
- */
-static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 88);
-}
-
-/**
- * @brief Decode a image_available message into a struct
- *
- * @param msg The message to decode
- * @param image_available C-struct to decode the message contents into
- */
-static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg);
- image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg);
- image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg);
- image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg);
- image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg);
- image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg);
- image_available->width = mavlink_msg_image_available_get_width(msg);
- image_available->height = mavlink_msg_image_available_get_height(msg);
- image_available->depth = mavlink_msg_image_available_get_depth(msg);
- image_available->channels = mavlink_msg_image_available_get_channels(msg);
- image_available->key = mavlink_msg_image_available_get_key(msg);
- image_available->exposure = mavlink_msg_image_available_get_exposure(msg);
- image_available->gain = mavlink_msg_image_available_get_gain(msg);
- image_available->roll = mavlink_msg_image_available_get_roll(msg);
- image_available->pitch = mavlink_msg_image_available_get_pitch(msg);
- image_available->yaw = mavlink_msg_image_available_get_yaw(msg);
- image_available->local_z = mavlink_msg_image_available_get_local_z(msg);
- image_available->lat = mavlink_msg_image_available_get_lat(msg);
- image_available->lon = mavlink_msg_image_available_get_lon(msg);
- image_available->alt = mavlink_msg_image_available_get_alt(msg);
- image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg);
- image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg);
- image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg);
-#else
- memcpy(image_available, _MAV_PAYLOAD(msg), 92);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_trigger_control.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_trigger_control.h
deleted file mode 100644
index 36b280ec0..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_trigger_control.h
+++ /dev/null
@@ -1,144 +0,0 @@
-// MESSAGE IMAGE_TRIGGER_CONTROL PACKING
-
-#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 153
-
-typedef struct __mavlink_image_trigger_control_t
-{
- uint8_t enable; ///< 0 to disable, 1 to enable
-} mavlink_image_trigger_control_t;
-
-#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN 1
-#define MAVLINK_MSG_ID_153_LEN 1
-
-
-
-#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL { \
- "IMAGE_TRIGGER_CONTROL", \
- 1, \
- { { "enable", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_image_trigger_control_t, enable) }, \
- } \
-}
-
-
-/**
- * @brief Pack a image_trigger_control 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 enable 0 to disable, 1 to enable
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t enable)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[1];
- _mav_put_uint8_t(buf, 0, enable);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1);
-#else
- mavlink_image_trigger_control_t packet;
- packet.enable = enable;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
- return mavlink_finalize_message(msg, system_id, component_id, 1);
-}
-
-/**
- * @brief Pack a image_trigger_control 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param enable 0 to disable, 1 to enable
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t enable)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[1];
- _mav_put_uint8_t(buf, 0, enable);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 1);
-#else
- mavlink_image_trigger_control_t packet;
- packet.enable = enable;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 1);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 1);
-}
-
-/**
- * @brief Encode a image_trigger_control struct into a 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 image_trigger_control C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control)
-{
- return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable);
-}
-
-/**
- * @brief Send a image_trigger_control message
- * @param chan MAVLink channel to send the message
- *
- * @param enable 0 to disable, 1 to enable
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[1];
- _mav_put_uint8_t(buf, 0, enable);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, 1);
-#else
- mavlink_image_trigger_control_t packet;
- packet.enable = enable;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, 1);
-#endif
-}
-
-#endif
-
-// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING
-
-
-/**
- * @brief Get field enable from image_trigger_control message
- *
- * @return 0 to disable, 1 to enable
- */
-static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Decode a image_trigger_control message into a struct
- *
- * @param msg The message to decode
- * @param image_trigger_control C-struct to decode the message contents into
- */
-static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg);
-#else
- memcpy(image_trigger_control, _MAV_PAYLOAD(msg), 1);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_triggered.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_triggered.h
deleted file mode 100644
index a40bc134b..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_image_triggered.h
+++ /dev/null
@@ -1,386 +0,0 @@
-// MESSAGE IMAGE_TRIGGERED PACKING
-
-#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 152
-
-typedef struct __mavlink_image_triggered_t
-{
- uint64_t timestamp; ///< Timestamp
- uint32_t seq; ///< IMU seq
- float roll; ///< Roll angle in rad
- float pitch; ///< Pitch angle in rad
- float yaw; ///< Yaw angle in rad
- float local_z; ///< Local frame Z coordinate (height over ground)
- float lat; ///< GPS X coordinate
- float lon; ///< GPS Y coordinate
- float alt; ///< Global frame altitude
- float ground_x; ///< Ground truth X
- float ground_y; ///< Ground truth Y
- float ground_z; ///< Ground truth Z
-} mavlink_image_triggered_t;
-
-#define MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN 52
-#define MAVLINK_MSG_ID_152_LEN 52
-
-
-
-#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED { \
- "IMAGE_TRIGGERED", \
- 12, \
- { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_triggered_t, timestamp) }, \
- { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_image_triggered_t, seq) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_image_triggered_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_image_triggered_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_image_triggered_t, yaw) }, \
- { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_image_triggered_t, local_z) }, \
- { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_image_triggered_t, lat) }, \
- { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_image_triggered_t, lon) }, \
- { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_image_triggered_t, alt) }, \
- { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_triggered_t, ground_x) }, \
- { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_triggered_t, ground_y) }, \
- { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_triggered_t, ground_z) }, \
- } \
-}
-
-
-/**
- * @brief Pack a image_triggered 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 timestamp Timestamp
- * @param seq IMU seq
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[52];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, seq);
- _mav_put_float(buf, 12, roll);
- _mav_put_float(buf, 16, pitch);
- _mav_put_float(buf, 20, yaw);
- _mav_put_float(buf, 24, local_z);
- _mav_put_float(buf, 28, lat);
- _mav_put_float(buf, 32, lon);
- _mav_put_float(buf, 36, alt);
- _mav_put_float(buf, 40, ground_x);
- _mav_put_float(buf, 44, ground_y);
- _mav_put_float(buf, 48, ground_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52);
-#else
- mavlink_image_triggered_t packet;
- packet.timestamp = timestamp;
- packet.seq = seq;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
- return mavlink_finalize_message(msg, system_id, component_id, 52);
-}
-
-/**
- * @brief Pack a image_triggered 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param timestamp Timestamp
- * @param seq IMU seq
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t timestamp,uint32_t seq,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[52];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, seq);
- _mav_put_float(buf, 12, roll);
- _mav_put_float(buf, 16, pitch);
- _mav_put_float(buf, 20, yaw);
- _mav_put_float(buf, 24, local_z);
- _mav_put_float(buf, 28, lat);
- _mav_put_float(buf, 32, lon);
- _mav_put_float(buf, 36, alt);
- _mav_put_float(buf, 40, ground_x);
- _mav_put_float(buf, 44, ground_y);
- _mav_put_float(buf, 48, ground_z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 52);
-#else
- mavlink_image_triggered_t packet;
- packet.timestamp = timestamp;
- packet.seq = seq;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 52);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 52);
-}
-
-/**
- * @brief Encode a image_triggered struct into a 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 image_triggered C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered)
-{
- return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z);
-}
-
-/**
- * @brief Send a image_triggered message
- * @param chan MAVLink channel to send the message
- *
- * @param timestamp Timestamp
- * @param seq IMU seq
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @param local_z Local frame Z coordinate (height over ground)
- * @param lat GPS X coordinate
- * @param lon GPS Y coordinate
- * @param alt Global frame altitude
- * @param ground_x Ground truth X
- * @param ground_y Ground truth Y
- * @param ground_z Ground truth Z
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[52];
- _mav_put_uint64_t(buf, 0, timestamp);
- _mav_put_uint32_t(buf, 8, seq);
- _mav_put_float(buf, 12, roll);
- _mav_put_float(buf, 16, pitch);
- _mav_put_float(buf, 20, yaw);
- _mav_put_float(buf, 24, local_z);
- _mav_put_float(buf, 28, lat);
- _mav_put_float(buf, 32, lon);
- _mav_put_float(buf, 36, alt);
- _mav_put_float(buf, 40, ground_x);
- _mav_put_float(buf, 44, ground_y);
- _mav_put_float(buf, 48, ground_z);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, 52);
-#else
- mavlink_image_triggered_t packet;
- packet.timestamp = timestamp;
- packet.seq = seq;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
- packet.local_z = local_z;
- packet.lat = lat;
- packet.lon = lon;
- packet.alt = alt;
- packet.ground_x = ground_x;
- packet.ground_y = ground_y;
- packet.ground_z = ground_z;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, 52);
-#endif
-}
-
-#endif
-
-// MESSAGE IMAGE_TRIGGERED UNPACKING
-
-
-/**
- * @brief Get field timestamp from image_triggered message
- *
- * @return Timestamp
- */
-static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field seq from image_triggered message
- *
- * @return IMU seq
- */
-static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint32_t(msg, 8);
-}
-
-/**
- * @brief Get field roll from image_triggered message
- *
- * @return Roll angle in rad
- */
-static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field pitch from image_triggered message
- *
- * @return Pitch angle in rad
- */
-static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field yaw from image_triggered message
- *
- * @return Yaw angle in rad
- */
-static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field local_z from image_triggered message
- *
- * @return Local frame Z coordinate (height over ground)
- */
-static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field lat from image_triggered message
- *
- * @return GPS X coordinate
- */
-static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Get field lon from image_triggered message
- *
- * @return GPS Y coordinate
- */
-static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 32);
-}
-
-/**
- * @brief Get field alt from image_triggered message
- *
- * @return Global frame altitude
- */
-static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 36);
-}
-
-/**
- * @brief Get field ground_x from image_triggered message
- *
- * @return Ground truth X
- */
-static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 40);
-}
-
-/**
- * @brief Get field ground_y from image_triggered message
- *
- * @return Ground truth Y
- */
-static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 44);
-}
-
-/**
- * @brief Get field ground_z from image_triggered message
- *
- * @return Ground truth Z
- */
-static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 48);
-}
-
-/**
- * @brief Decode a image_triggered message into a struct
- *
- * @param msg The message to decode
- * @param image_triggered C-struct to decode the message contents into
- */
-static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg);
- image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg);
- image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg);
- image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg);
- image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg);
- image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg);
- image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg);
- image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg);
- image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg);
- image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg);
- image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg);
- image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg);
-#else
- memcpy(image_triggered, _MAV_PAYLOAD(msg), 52);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_marker.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_marker.h
deleted file mode 100644
index f5d20dd04..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_marker.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE MARKER PACKING
-
-#define MAVLINK_MSG_ID_MARKER 171
-
-typedef struct __mavlink_marker_t
-{
- uint16_t id; ///< ID
- float x; ///< x position
- float y; ///< y position
- float z; ///< z position
- float roll; ///< roll orientation
- float pitch; ///< pitch orientation
- float yaw; ///< yaw orientation
-} mavlink_marker_t;
-
-#define MAVLINK_MSG_ID_MARKER_LEN 26
-#define MAVLINK_MSG_ID_171_LEN 26
-
-
-
-#define MAVLINK_MESSAGE_INFO_MARKER { \
- "MARKER", \
- 7, \
- { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_marker_t, id) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_marker_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_marker_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_marker_t, z) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_marker_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_marker_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_marker_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a marker 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 id ID
- * @param x x position
- * @param y y position
- * @param z z position
- * @param roll roll orientation
- * @param pitch pitch orientation
- * @param yaw yaw orientation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[26];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, roll);
- _mav_put_float(buf, 18, pitch);
- _mav_put_float(buf, 22, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
-#else
- mavlink_marker_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MARKER;
- return mavlink_finalize_message(msg, system_id, component_id, 26);
-}
-
-/**
- * @brief Pack a marker 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param id ID
- * @param x x position
- * @param y y position
- * @param z z position
- * @param roll roll orientation
- * @param pitch pitch orientation
- * @param yaw yaw orientation
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t id,float x,float y,float z,float roll,float pitch,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[26];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, roll);
- _mav_put_float(buf, 18, pitch);
- _mav_put_float(buf, 22, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
-#else
- mavlink_marker_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_MARKER;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
-}
-
-/**
- * @brief Encode a marker struct into a 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 marker C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
-{
- return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
-}
-
-/**
- * @brief Send a marker message
- * @param chan MAVLink channel to send the message
- *
- * @param id ID
- * @param x x position
- * @param y y position
- * @param z z position
- * @param roll roll orientation
- * @param pitch pitch orientation
- * @param yaw yaw orientation
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[26];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, roll);
- _mav_put_float(buf, 18, pitch);
- _mav_put_float(buf, 22, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, 26);
-#else
- mavlink_marker_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, 26);
-#endif
-}
-
-#endif
-
-// MESSAGE MARKER UNPACKING
-
-
-/**
- * @brief Get field id from marker message
- *
- * @return ID
- */
-static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field x from marker message
- *
- * @return x position
- */
-static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 2);
-}
-
-/**
- * @brief Get field y from marker message
- *
- * @return y position
- */
-static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 6);
-}
-
-/**
- * @brief Get field z from marker message
- *
- * @return z position
- */
-static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 10);
-}
-
-/**
- * @brief Get field roll from marker message
- *
- * @return roll orientation
- */
-static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 14);
-}
-
-/**
- * @brief Get field pitch from marker message
- *
- * @return pitch orientation
- */
-static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 18);
-}
-
-/**
- * @brief Get field yaw from marker message
- *
- * @return yaw orientation
- */
-static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 22);
-}
-
-/**
- * @brief Decode a marker message into a struct
- *
- * @param msg The message to decode
- * @param marker C-struct to decode the message contents into
- */
-static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- marker->id = mavlink_msg_marker_get_id(msg);
- marker->x = mavlink_msg_marker_get_x(msg);
- marker->y = mavlink_msg_marker_get_y(msg);
- marker->z = mavlink_msg_marker_get_z(msg);
- marker->roll = mavlink_msg_marker_get_roll(msg);
- marker->pitch = mavlink_msg_marker_get_pitch(msg);
- marker->yaw = mavlink_msg_marker_get_yaw(msg);
-#else
- memcpy(marker, _MAV_PAYLOAD(msg), 26);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_pattern_detected.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_pattern_detected.h
deleted file mode 100644
index a5aabe9f9..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_pattern_detected.h
+++ /dev/null
@@ -1,204 +0,0 @@
-// MESSAGE PATTERN_DETECTED PACKING
-
-#define MAVLINK_MSG_ID_PATTERN_DETECTED 190
-
-typedef struct __mavlink_pattern_detected_t
-{
- uint8_t type; ///< 0: Pattern, 1: Letter
- float confidence; ///< Confidence of detection
- char file[100]; ///< Pattern file name
- uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes
-} mavlink_pattern_detected_t;
-
-#define MAVLINK_MSG_ID_PATTERN_DETECTED_LEN 106
-#define MAVLINK_MSG_ID_190_LEN 106
-
-#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100
-
-#define MAVLINK_MESSAGE_INFO_PATTERN_DETECTED { \
- "PATTERN_DETECTED", \
- 4, \
- { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_pattern_detected_t, type) }, \
- { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_pattern_detected_t, confidence) }, \
- { "file", NULL, MAVLINK_TYPE_CHAR, 100, 5, offsetof(mavlink_pattern_detected_t, file) }, \
- { "detected", NULL, MAVLINK_TYPE_UINT8_T, 0, 105, offsetof(mavlink_pattern_detected_t, detected) }, \
- } \
-}
-
-
-/**
- * @brief Pack a pattern_detected 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 type 0: Pattern, 1: Letter
- * @param confidence Confidence of detection
- * @param file Pattern file name
- * @param detected Accepted as true detection, 0 no, 1 yes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t type, float confidence, const char *file, uint8_t detected)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[106];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_float(buf, 1, confidence);
- _mav_put_uint8_t(buf, 105, detected);
- _mav_put_char_array(buf, 5, file, 100);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106);
-#else
- mavlink_pattern_detected_t packet;
- packet.type = type;
- packet.confidence = confidence;
- packet.detected = detected;
- mav_array_memcpy(packet.file, file, sizeof(char)*100);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
- return mavlink_finalize_message(msg, system_id, component_id, 106);
-}
-
-/**
- * @brief Pack a pattern_detected 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param type 0: Pattern, 1: Letter
- * @param confidence Confidence of detection
- * @param file Pattern file name
- * @param detected Accepted as true detection, 0 no, 1 yes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t type,float confidence,const char *file,uint8_t detected)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[106];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_float(buf, 1, confidence);
- _mav_put_uint8_t(buf, 105, detected);
- _mav_put_char_array(buf, 5, file, 100);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 106);
-#else
- mavlink_pattern_detected_t packet;
- packet.type = type;
- packet.confidence = confidence;
- packet.detected = detected;
- mav_array_memcpy(packet.file, file, sizeof(char)*100);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 106);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 106);
-}
-
-/**
- * @brief Encode a pattern_detected struct into a 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 pattern_detected C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected)
-{
- return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected);
-}
-
-/**
- * @brief Send a pattern_detected message
- * @param chan MAVLink channel to send the message
- *
- * @param type 0: Pattern, 1: Letter
- * @param confidence Confidence of detection
- * @param file Pattern file name
- * @param detected Accepted as true detection, 0 no, 1 yes
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[106];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_float(buf, 1, confidence);
- _mav_put_uint8_t(buf, 105, detected);
- _mav_put_char_array(buf, 5, file, 100);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, 106);
-#else
- mavlink_pattern_detected_t packet;
- packet.type = type;
- packet.confidence = confidence;
- packet.detected = detected;
- mav_array_memcpy(packet.file, file, sizeof(char)*100);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, 106);
-#endif
-}
-
-#endif
-
-// MESSAGE PATTERN_DETECTED UNPACKING
-
-
-/**
- * @brief Get field type from pattern_detected message
- *
- * @return 0: Pattern, 1: Letter
- */
-static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field confidence from pattern_detected message
- *
- * @return Confidence of detection
- */
-static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 1);
-}
-
-/**
- * @brief Get field file from pattern_detected message
- *
- * @return Pattern file name
- */
-static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, char *file)
-{
- return _MAV_RETURN_char_array(msg, file, 100, 5);
-}
-
-/**
- * @brief Get field detected from pattern_detected message
- *
- * @return Accepted as true detection, 0 no, 1 yes
- */
-static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 105);
-}
-
-/**
- * @brief Decode a pattern_detected message into a struct
- *
- * @param msg The message to decode
- * @param pattern_detected C-struct to decode the message contents into
- */
-static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg);
- pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg);
- mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file);
- pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg);
-#else
- memcpy(pattern_detected, _MAV_PAYLOAD(msg), 106);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest.h
deleted file mode 100644
index 008ed436e..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest.h
+++ /dev/null
@@ -1,292 +0,0 @@
-// MESSAGE POINT_OF_INTEREST PACKING
-
-#define MAVLINK_MSG_ID_POINT_OF_INTEREST 191
-
-typedef struct __mavlink_point_of_interest_t
-{
- uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- uint8_t coordinate_system; ///< 0: global, 1:local
- uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
- float x; ///< X Position
- float y; ///< Y Position
- float z; ///< Z Position
- char name[26]; ///< POI name
-} mavlink_point_of_interest_t;
-
-#define MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN 43
-#define MAVLINK_MSG_ID_191_LEN 43
-
-#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 26
-
-#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST { \
- "POINT_OF_INTEREST", \
- 8, \
- { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_point_of_interest_t, type) }, \
- { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_point_of_interest_t, color) }, \
- { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_point_of_interest_t, coordinate_system) }, \
- { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_point_of_interest_t, timeout) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_point_of_interest_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_point_of_interest_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_point_of_interest_t, z) }, \
- { "name", NULL, MAVLINK_TYPE_CHAR, 26, 17, offsetof(mavlink_point_of_interest_t, name) }, \
- } \
-}
-
-
-/**
- * @brief Pack a point_of_interest 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param x X Position
- * @param y Y Position
- * @param z Z Position
- * @param name POI name
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[43];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, x);
- _mav_put_float(buf, 9, y);
- _mav_put_float(buf, 13, z);
- _mav_put_char_array(buf, 17, name, 26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43);
-#else
- mavlink_point_of_interest_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
- return mavlink_finalize_message(msg, system_id, component_id, 43);
-}
-
-/**
- * @brief Pack a point_of_interest 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param x X Position
- * @param y Y Position
- * @param z Z Position
- * @param name POI name
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float x,float y,float z,const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[43];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, x);
- _mav_put_float(buf, 9, y);
- _mav_put_float(buf, 13, z);
- _mav_put_char_array(buf, 17, name, 26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 43);
-#else
- mavlink_point_of_interest_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 43);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 43);
-}
-
-/**
- * @brief Encode a point_of_interest struct into a 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 point_of_interest C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest)
-{
- return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name);
-}
-
-/**
- * @brief Send a point_of_interest message
- * @param chan MAVLink channel to send the message
- *
- * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param x X Position
- * @param y Y Position
- * @param z Z Position
- * @param name POI name
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[43];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, x);
- _mav_put_float(buf, 9, y);
- _mav_put_float(buf, 13, z);
- _mav_put_char_array(buf, 17, name, 26);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, 43);
-#else
- mavlink_point_of_interest_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, 43);
-#endif
-}
-
-#endif
-
-// MESSAGE POINT_OF_INTEREST UNPACKING
-
-
-/**
- * @brief Get field type from point_of_interest message
- *
- * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- */
-static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field color from point_of_interest message
- *
- * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- */
-static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field coordinate_system from point_of_interest message
- *
- * @return 0: global, 1:local
- */
-static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field timeout from point_of_interest message
- *
- * @return 0: no timeout, >1: timeout in seconds
- */
-static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 3);
-}
-
-/**
- * @brief Get field x from point_of_interest message
- *
- * @return X Position
- */
-static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 5);
-}
-
-/**
- * @brief Get field y from point_of_interest message
- *
- * @return Y Position
- */
-static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 9);
-}
-
-/**
- * @brief Get field z from point_of_interest message
- *
- * @return Z Position
- */
-static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 13);
-}
-
-/**
- * @brief Get field name from point_of_interest message
- *
- * @return POI name
- */
-static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, char *name)
-{
- return _MAV_RETURN_char_array(msg, name, 26, 17);
-}
-
-/**
- * @brief Decode a point_of_interest message into a struct
- *
- * @param msg The message to decode
- * @param point_of_interest C-struct to decode the message contents into
- */
-static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg);
- point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg);
- point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg);
- point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg);
- point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg);
- point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg);
- point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg);
- mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name);
-#else
- memcpy(point_of_interest, _MAV_PAYLOAD(msg), 43);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h
deleted file mode 100644
index d8de738c7..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_point_of_interest_connection.h
+++ /dev/null
@@ -1,358 +0,0 @@
-// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING
-
-#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 192
-
-typedef struct __mavlink_point_of_interest_connection_t
-{
- uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- uint8_t coordinate_system; ///< 0: global, 1:local
- uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds
- float xp1; ///< X1 Position
- float yp1; ///< Y1 Position
- float zp1; ///< Z1 Position
- float xp2; ///< X2 Position
- float yp2; ///< Y2 Position
- float zp2; ///< Z2 Position
- char name[26]; ///< POI connection name
-} mavlink_point_of_interest_connection_t;
-
-#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN 55
-#define MAVLINK_MSG_ID_192_LEN 55
-
-#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 26
-
-#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION { \
- "POINT_OF_INTEREST_CONNECTION", \
- 11, \
- { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_point_of_interest_connection_t, type) }, \
- { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_point_of_interest_connection_t, color) }, \
- { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_point_of_interest_connection_t, coordinate_system) }, \
- { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_point_of_interest_connection_t, timeout) }, \
- { "xp1", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_point_of_interest_connection_t, xp1) }, \
- { "yp1", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_point_of_interest_connection_t, yp1) }, \
- { "zp1", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_point_of_interest_connection_t, zp1) }, \
- { "xp2", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_point_of_interest_connection_t, xp2) }, \
- { "yp2", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_point_of_interest_connection_t, yp2) }, \
- { "zp2", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_point_of_interest_connection_t, zp2) }, \
- { "name", NULL, MAVLINK_TYPE_CHAR, 26, 29, offsetof(mavlink_point_of_interest_connection_t, name) }, \
- } \
-}
-
-
-/**
- * @brief Pack a point_of_interest_connection 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 type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param xp1 X1 Position
- * @param yp1 Y1 Position
- * @param zp1 Z1 Position
- * @param xp2 X2 Position
- * @param yp2 Y2 Position
- * @param zp2 Z2 Position
- * @param name POI connection name
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[55];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, xp1);
- _mav_put_float(buf, 9, yp1);
- _mav_put_float(buf, 13, zp1);
- _mav_put_float(buf, 17, xp2);
- _mav_put_float(buf, 21, yp2);
- _mav_put_float(buf, 25, zp2);
- _mav_put_char_array(buf, 29, name, 26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55);
-#else
- mavlink_point_of_interest_connection_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.xp1 = xp1;
- packet.yp1 = yp1;
- packet.zp1 = zp1;
- packet.xp2 = xp2;
- packet.yp2 = yp2;
- packet.zp2 = zp2;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
- return mavlink_finalize_message(msg, system_id, component_id, 55);
-}
-
-/**
- * @brief Pack a point_of_interest_connection 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param xp1 X1 Position
- * @param yp1 Y1 Position
- * @param zp1 Z1 Position
- * @param xp2 X2 Position
- * @param yp2 Y2 Position
- * @param zp2 Z2 Position
- * @param name POI connection name
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float xp1,float yp1,float zp1,float xp2,float yp2,float zp2,const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[55];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, xp1);
- _mav_put_float(buf, 9, yp1);
- _mav_put_float(buf, 13, zp1);
- _mav_put_float(buf, 17, xp2);
- _mav_put_float(buf, 21, yp2);
- _mav_put_float(buf, 25, zp2);
- _mav_put_char_array(buf, 29, name, 26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 55);
-#else
- mavlink_point_of_interest_connection_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.xp1 = xp1;
- packet.yp1 = yp1;
- packet.zp1 = zp1;
- packet.xp2 = xp2;
- packet.yp2 = yp2;
- packet.zp2 = zp2;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 55);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 55);
-}
-
-/**
- * @brief Encode a point_of_interest_connection struct into a 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 point_of_interest_connection C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection)
-{
- return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name);
-}
-
-/**
- * @brief Send a point_of_interest_connection message
- * @param chan MAVLink channel to send the message
- *
- * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- * @param coordinate_system 0: global, 1:local
- * @param timeout 0: no timeout, >1: timeout in seconds
- * @param xp1 X1 Position
- * @param yp1 Y1 Position
- * @param zp1 Z1 Position
- * @param xp2 X2 Position
- * @param yp2 Y2 Position
- * @param zp2 Z2 Position
- * @param name POI connection name
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[55];
- _mav_put_uint8_t(buf, 0, type);
- _mav_put_uint8_t(buf, 1, color);
- _mav_put_uint8_t(buf, 2, coordinate_system);
- _mav_put_uint16_t(buf, 3, timeout);
- _mav_put_float(buf, 5, xp1);
- _mav_put_float(buf, 9, yp1);
- _mav_put_float(buf, 13, zp1);
- _mav_put_float(buf, 17, xp2);
- _mav_put_float(buf, 21, yp2);
- _mav_put_float(buf, 25, zp2);
- _mav_put_char_array(buf, 29, name, 26);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, 55);
-#else
- mavlink_point_of_interest_connection_t packet;
- packet.type = type;
- packet.color = color;
- packet.coordinate_system = coordinate_system;
- packet.timeout = timeout;
- packet.xp1 = xp1;
- packet.yp1 = yp1;
- packet.zp1 = zp1;
- packet.xp2 = xp2;
- packet.yp2 = yp2;
- packet.zp2 = zp2;
- mav_array_memcpy(packet.name, name, sizeof(char)*26);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, 55);
-#endif
-}
-
-#endif
-
-// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING
-
-
-/**
- * @brief Get field type from point_of_interest_connection message
- *
- * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug
- */
-static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field color from point_of_interest_connection message
- *
- * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta
- */
-static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field coordinate_system from point_of_interest_connection message
- *
- * @return 0: global, 1:local
- */
-static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field timeout from point_of_interest_connection message
- *
- * @return 0: no timeout, >1: timeout in seconds
- */
-static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 3);
-}
-
-/**
- * @brief Get field xp1 from point_of_interest_connection message
- *
- * @return X1 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 5);
-}
-
-/**
- * @brief Get field yp1 from point_of_interest_connection message
- *
- * @return Y1 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 9);
-}
-
-/**
- * @brief Get field zp1 from point_of_interest_connection message
- *
- * @return Z1 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 13);
-}
-
-/**
- * @brief Get field xp2 from point_of_interest_connection message
- *
- * @return X2 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 17);
-}
-
-/**
- * @brief Get field yp2 from point_of_interest_connection message
- *
- * @return Y2 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 21);
-}
-
-/**
- * @brief Get field zp2 from point_of_interest_connection message
- *
- * @return Z2 Position
- */
-static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 25);
-}
-
-/**
- * @brief Get field name from point_of_interest_connection message
- *
- * @return POI connection name
- */
-static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, char *name)
-{
- return _MAV_RETURN_char_array(msg, name, 26, 29);
-}
-
-/**
- * @brief Decode a point_of_interest_connection message into a struct
- *
- * @param msg The message to decode
- * @param point_of_interest_connection C-struct to decode the message contents into
- */
-static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg);
- point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg);
- point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg);
- point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg);
- point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg);
- point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg);
- point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg);
- point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg);
- point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg);
- point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg);
- mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name);
-#else
- memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), 55);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h
deleted file mode 100644
index 1591b6abe..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_offset_set.h
+++ /dev/null
@@ -1,254 +0,0 @@
-// MESSAGE POSITION_CONTROL_OFFSET_SET PACKING
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET 160
-
-typedef struct __mavlink_position_control_offset_set_t
-{
- uint8_t target_system; ///< System ID
- uint8_t target_component; ///< Component ID
- float x; ///< x position offset
- float y; ///< y position offset
- float z; ///< z position offset
- float yaw; ///< yaw orientation offset in radians, 0 = NORTH
-} mavlink_position_control_offset_set_t;
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET_LEN 18
-#define MAVLINK_MSG_ID_160_LEN 18
-
-
-
-#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET { \
- "POSITION_CONTROL_OFFSET_SET", \
- 6, \
- { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_position_control_offset_set_t, target_system) }, \
- { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_position_control_offset_set_t, target_component) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_position_control_offset_set_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_position_control_offset_set_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_position_control_offset_set_t, z) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_position_control_offset_set_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a position_control_offset_set 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 x x position offset
- * @param y y position offset
- * @param z z position offset
- * @param yaw yaw orientation offset in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_offset_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
-#else
- mavlink_position_control_offset_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
- return mavlink_finalize_message(msg, system_id, component_id, 18);
-}
-
-/**
- * @brief Pack a position_control_offset_set 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target_system System ID
- * @param target_component Component ID
- * @param x x position offset
- * @param y y position offset
- * @param z z position offset
- * @param yaw yaw orientation offset in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_offset_set_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,float x,float y,float z,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
-#else
- mavlink_position_control_offset_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
-}
-
-/**
- * @brief Encode a position_control_offset_set struct into a 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 position_control_offset_set C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_position_control_offset_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_offset_set_t* position_control_offset_set)
-{
- return mavlink_msg_position_control_offset_set_pack(system_id, component_id, msg, position_control_offset_set->target_system, position_control_offset_set->target_component, position_control_offset_set->x, position_control_offset_set->y, position_control_offset_set->z, position_control_offset_set->yaw);
-}
-
-/**
- * @brief Send a position_control_offset_set message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system System ID
- * @param target_component Component ID
- * @param x x position offset
- * @param y y position offset
- * @param z z position offset
- * @param yaw yaw orientation offset in radians, 0 = NORTH
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_position_control_offset_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, buf, 18);
-#else
- mavlink_position_control_offset_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_OFFSET_SET, (const char *)&packet, 18);
-#endif
-}
-
-#endif
-
-// MESSAGE POSITION_CONTROL_OFFSET_SET UNPACKING
-
-
-/**
- * @brief Get field target_system from position_control_offset_set message
- *
- * @return System ID
- */
-static inline uint8_t mavlink_msg_position_control_offset_set_get_target_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field target_component from position_control_offset_set message
- *
- * @return Component ID
- */
-static inline uint8_t mavlink_msg_position_control_offset_set_get_target_component(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field x from position_control_offset_set message
- *
- * @return x position offset
- */
-static inline float mavlink_msg_position_control_offset_set_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 2);
-}
-
-/**
- * @brief Get field y from position_control_offset_set message
- *
- * @return y position offset
- */
-static inline float mavlink_msg_position_control_offset_set_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 6);
-}
-
-/**
- * @brief Get field z from position_control_offset_set message
- *
- * @return z position offset
- */
-static inline float mavlink_msg_position_control_offset_set_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 10);
-}
-
-/**
- * @brief Get field yaw from position_control_offset_set message
- *
- * @return yaw orientation offset in radians, 0 = NORTH
- */
-static inline float mavlink_msg_position_control_offset_set_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 14);
-}
-
-/**
- * @brief Decode a position_control_offset_set message into a struct
- *
- * @param msg The message to decode
- * @param position_control_offset_set C-struct to decode the message contents into
- */
-static inline void mavlink_msg_position_control_offset_set_decode(const mavlink_message_t* msg, mavlink_position_control_offset_set_t* position_control_offset_set)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- position_control_offset_set->target_system = mavlink_msg_position_control_offset_set_get_target_system(msg);
- position_control_offset_set->target_component = mavlink_msg_position_control_offset_set_get_target_component(msg);
- position_control_offset_set->x = mavlink_msg_position_control_offset_set_get_x(msg);
- position_control_offset_set->y = mavlink_msg_position_control_offset_set_get_y(msg);
- position_control_offset_set->z = mavlink_msg_position_control_offset_set_get_z(msg);
- position_control_offset_set->yaw = mavlink_msg_position_control_offset_set_get_yaw(msg);
-#else
- memcpy(position_control_offset_set, _MAV_PAYLOAD(msg), 18);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h
deleted file mode 100644
index 3e13f402d..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint.h
+++ /dev/null
@@ -1,232 +0,0 @@
-// MESSAGE POSITION_CONTROL_SETPOINT PACKING
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 170
-
-typedef struct __mavlink_position_control_setpoint_t
-{
- uint16_t id; ///< ID of waypoint, 0 for plain position
- float x; ///< x position
- float y; ///< y position
- float z; ///< z position
- float yaw; ///< yaw orientation in radians, 0 = NORTH
-} mavlink_position_control_setpoint_t;
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN 18
-#define MAVLINK_MSG_ID_170_LEN 18
-
-
-
-#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT { \
- "POSITION_CONTROL_SETPOINT", \
- 5, \
- { { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_position_control_setpoint_t, id) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_position_control_setpoint_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_position_control_setpoint_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_position_control_setpoint_t, z) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_position_control_setpoint_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a position_control_setpoint 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 id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t id, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
-#else
- mavlink_position_control_setpoint_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
- return mavlink_finalize_message(msg, system_id, component_id, 18);
-}
-
-/**
- * @brief Pack a position_control_setpoint 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t id,float x,float y,float z,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
-#else
- mavlink_position_control_setpoint_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
-}
-
-/**
- * @brief Encode a position_control_setpoint struct into a 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 position_control_setpoint C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint)
-{
- return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw);
-}
-
-/**
- * @brief Send a position_control_setpoint message
- * @param chan MAVLink channel to send the message
- *
- * @param id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[18];
- _mav_put_uint16_t(buf, 0, id);
- _mav_put_float(buf, 2, x);
- _mav_put_float(buf, 6, y);
- _mav_put_float(buf, 10, z);
- _mav_put_float(buf, 14, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, 18);
-#else
- mavlink_position_control_setpoint_t packet;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, 18);
-#endif
-}
-
-#endif
-
-// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING
-
-
-/**
- * @brief Get field id from position_control_setpoint message
- *
- * @return ID of waypoint, 0 for plain position
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field x from position_control_setpoint message
- *
- * @return x position
- */
-static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 2);
-}
-
-/**
- * @brief Get field y from position_control_setpoint message
- *
- * @return y position
- */
-static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 6);
-}
-
-/**
- * @brief Get field z from position_control_setpoint message
- *
- * @return z position
- */
-static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 10);
-}
-
-/**
- * @brief Get field yaw from position_control_setpoint message
- *
- * @return yaw orientation in radians, 0 = NORTH
- */
-static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 14);
-}
-
-/**
- * @brief Decode a position_control_setpoint message into a struct
- *
- * @param msg The message to decode
- * @param position_control_setpoint C-struct to decode the message contents into
- */
-static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg);
- position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg);
- position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg);
- position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg);
- position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg);
-#else
- memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), 18);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h
deleted file mode 100644
index 4a556e57f..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_position_control_setpoint_set.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE POSITION_CONTROL_SETPOINT_SET PACKING
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET 159
-
-typedef struct __mavlink_position_control_setpoint_set_t
-{
- uint8_t target_system; ///< System ID
- uint8_t target_component; ///< Component ID
- uint16_t id; ///< ID of waypoint, 0 for plain position
- float x; ///< x position
- float y; ///< y position
- float z; ///< z position
- float yaw; ///< yaw orientation in radians, 0 = NORTH
-} mavlink_position_control_setpoint_set_t;
-
-#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET_LEN 20
-#define MAVLINK_MSG_ID_159_LEN 20
-
-
-
-#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET { \
- "POSITION_CONTROL_SETPOINT_SET", \
- 7, \
- { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_position_control_setpoint_set_t, target_system) }, \
- { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_position_control_setpoint_set_t, target_component) }, \
- { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_position_control_setpoint_set_t, id) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_set_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_set_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_set_t, z) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_control_setpoint_set_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a position_control_setpoint_set 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 id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_uint16_t(buf, 2, id);
- _mav_put_float(buf, 4, x);
- _mav_put_float(buf, 8, y);
- _mav_put_float(buf, 12, z);
- _mav_put_float(buf, 16, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
-#else
- mavlink_position_control_setpoint_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
- return mavlink_finalize_message(msg, system_id, component_id, 20);
-}
-
-/**
- * @brief Pack a position_control_setpoint_set 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target_system System ID
- * @param target_component Component ID
- * @param id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_set_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 id,float x,float y,float z,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_uint16_t(buf, 2, id);
- _mav_put_float(buf, 4, x);
- _mav_put_float(buf, 8, y);
- _mav_put_float(buf, 12, z);
- _mav_put_float(buf, 16, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
-#else
- mavlink_position_control_setpoint_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20);
-}
-
-/**
- * @brief Encode a position_control_setpoint_set struct into a 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 position_control_setpoint_set C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
-{
- return mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, msg, position_control_setpoint_set->target_system, position_control_setpoint_set->target_component, position_control_setpoint_set->id, position_control_setpoint_set->x, position_control_setpoint_set->y, position_control_setpoint_set->z, position_control_setpoint_set->yaw);
-}
-
-/**
- * @brief Send a position_control_setpoint_set message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system System ID
- * @param target_component Component ID
- * @param id ID of waypoint, 0 for plain position
- * @param x x position
- * @param y y position
- * @param z z position
- * @param yaw yaw orientation in radians, 0 = NORTH
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_position_control_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, float x, float y, float z, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint8_t(buf, 0, target_system);
- _mav_put_uint8_t(buf, 1, target_component);
- _mav_put_uint16_t(buf, 2, id);
- _mav_put_float(buf, 4, x);
- _mav_put_float(buf, 8, y);
- _mav_put_float(buf, 12, z);
- _mav_put_float(buf, 16, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, buf, 20);
-#else
- mavlink_position_control_setpoint_set_t packet;
- packet.target_system = target_system;
- packet.target_component = target_component;
- packet.id = id;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_SET, (const char *)&packet, 20);
-#endif
-}
-
-#endif
-
-// MESSAGE POSITION_CONTROL_SETPOINT_SET UNPACKING
-
-
-/**
- * @brief Get field target_system from position_control_setpoint_set message
- *
- * @return System ID
- */
-static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_system(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field target_component from position_control_setpoint_set message
- *
- * @return Component ID
- */
-static inline uint8_t mavlink_msg_position_control_setpoint_set_get_target_component(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field id from position_control_setpoint_set message
- *
- * @return ID of waypoint, 0 for plain position
- */
-static inline uint16_t mavlink_msg_position_control_setpoint_set_get_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Get field x from position_control_setpoint_set message
- *
- * @return x position
- */
-static inline float mavlink_msg_position_control_setpoint_set_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 4);
-}
-
-/**
- * @brief Get field y from position_control_setpoint_set message
- *
- * @return y position
- */
-static inline float mavlink_msg_position_control_setpoint_set_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field z from position_control_setpoint_set message
- *
- * @return z position
- */
-static inline float mavlink_msg_position_control_setpoint_set_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field yaw from position_control_setpoint_set message
- *
- * @return yaw orientation in radians, 0 = NORTH
- */
-static inline float mavlink_msg_position_control_setpoint_set_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Decode a position_control_setpoint_set message into a struct
- *
- * @param msg The message to decode
- * @param position_control_setpoint_set C-struct to decode the message contents into
- */
-static inline void mavlink_msg_position_control_setpoint_set_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_set_t* position_control_setpoint_set)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- position_control_setpoint_set->target_system = mavlink_msg_position_control_setpoint_set_get_target_system(msg);
- position_control_setpoint_set->target_component = mavlink_msg_position_control_setpoint_set_get_target_component(msg);
- position_control_setpoint_set->id = mavlink_msg_position_control_setpoint_set_get_id(msg);
- position_control_setpoint_set->x = mavlink_msg_position_control_setpoint_set_get_x(msg);
- position_control_setpoint_set->y = mavlink_msg_position_control_setpoint_set_get_y(msg);
- position_control_setpoint_set->z = mavlink_msg_position_control_setpoint_set_get_z(msg);
- position_control_setpoint_set->yaw = mavlink_msg_position_control_setpoint_set_get_yaw(msg);
-#else
- memcpy(position_control_setpoint_set, _MAV_PAYLOAD(msg), 20);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_raw_aux.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_raw_aux.h
deleted file mode 100644
index 154653de2..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_raw_aux.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE RAW_AUX PACKING
-
-#define MAVLINK_MSG_ID_RAW_AUX 172
-
-typedef struct __mavlink_raw_aux_t
-{
- uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6)
- uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2)
- uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1)
- uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3)
- uint16_t vbat; ///< Battery voltage
- int16_t temp; ///< Temperature (degrees celcius)
- int32_t baro; ///< Barometric pressure (hecto Pascal)
-} mavlink_raw_aux_t;
-
-#define MAVLINK_MSG_ID_RAW_AUX_LEN 16
-#define MAVLINK_MSG_ID_172_LEN 16
-
-
-
-#define MAVLINK_MESSAGE_INFO_RAW_AUX { \
- "RAW_AUX", \
- 7, \
- { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_raw_aux_t, adc1) }, \
- { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_raw_aux_t, adc2) }, \
- { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc3) }, \
- { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc4) }, \
- { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, vbat) }, \
- { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_aux_t, temp) }, \
- { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_raw_aux_t, baro) }, \
- } \
-}
-
-
-/**
- * @brief Pack a raw_aux 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 adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
- * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
- * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
- * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
- * @param vbat Battery voltage
- * @param temp Temperature (degrees celcius)
- * @param baro Barometric pressure (hecto Pascal)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[16];
- _mav_put_uint16_t(buf, 0, adc1);
- _mav_put_uint16_t(buf, 2, adc2);
- _mav_put_uint16_t(buf, 4, adc3);
- _mav_put_uint16_t(buf, 6, adc4);
- _mav_put_uint16_t(buf, 8, vbat);
- _mav_put_int16_t(buf, 10, temp);
- _mav_put_int32_t(buf, 12, baro);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
-#else
- mavlink_raw_aux_t packet;
- packet.adc1 = adc1;
- packet.adc2 = adc2;
- packet.adc3 = adc3;
- packet.adc4 = adc4;
- packet.vbat = vbat;
- packet.temp = temp;
- packet.baro = baro;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
- return mavlink_finalize_message(msg, system_id, component_id, 16);
-}
-
-/**
- * @brief Pack a raw_aux 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
- * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
- * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
- * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
- * @param vbat Battery voltage
- * @param temp Temperature (degrees celcius)
- * @param baro Barometric pressure (hecto Pascal)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t vbat,int16_t temp,int32_t baro)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[16];
- _mav_put_uint16_t(buf, 0, adc1);
- _mav_put_uint16_t(buf, 2, adc2);
- _mav_put_uint16_t(buf, 4, adc3);
- _mav_put_uint16_t(buf, 6, adc4);
- _mav_put_uint16_t(buf, 8, vbat);
- _mav_put_int16_t(buf, 10, temp);
- _mav_put_int32_t(buf, 12, baro);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
-#else
- mavlink_raw_aux_t packet;
- packet.adc1 = adc1;
- packet.adc2 = adc2;
- packet.adc3 = adc3;
- packet.adc4 = adc4;
- packet.vbat = vbat;
- packet.temp = temp;
- packet.baro = baro;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_RAW_AUX;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16);
-}
-
-/**
- * @brief Encode a raw_aux struct into a 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 raw_aux C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux)
-{
- return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro);
-}
-
-/**
- * @brief Send a raw_aux message
- * @param chan MAVLink channel to send the message
- *
- * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6)
- * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2)
- * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1)
- * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3)
- * @param vbat Battery voltage
- * @param temp Temperature (degrees celcius)
- * @param baro Barometric pressure (hecto Pascal)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[16];
- _mav_put_uint16_t(buf, 0, adc1);
- _mav_put_uint16_t(buf, 2, adc2);
- _mav_put_uint16_t(buf, 4, adc3);
- _mav_put_uint16_t(buf, 6, adc4);
- _mav_put_uint16_t(buf, 8, vbat);
- _mav_put_int16_t(buf, 10, temp);
- _mav_put_int32_t(buf, 12, baro);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, 16);
-#else
- mavlink_raw_aux_t packet;
- packet.adc1 = adc1;
- packet.adc2 = adc2;
- packet.adc3 = adc3;
- packet.adc4 = adc4;
- packet.vbat = vbat;
- packet.temp = temp;
- packet.baro = baro;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, 16);
-#endif
-}
-
-#endif
-
-// MESSAGE RAW_AUX UNPACKING
-
-
-/**
- * @brief Get field adc1 from raw_aux message
- *
- * @return ADC1 (J405 ADC3, LPC2148 AD0.6)
- */
-static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field adc2 from raw_aux message
- *
- * @return ADC2 (J405 ADC5, LPC2148 AD0.2)
- */
-static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Get field adc3 from raw_aux message
- *
- * @return ADC3 (J405 ADC6, LPC2148 AD0.1)
- */
-static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 4);
-}
-
-/**
- * @brief Get field adc4 from raw_aux message
- *
- * @return ADC4 (J405 ADC7, LPC2148 AD1.3)
- */
-static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 6);
-}
-
-/**
- * @brief Get field vbat from raw_aux message
- *
- * @return Battery voltage
- */
-static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 8);
-}
-
-/**
- * @brief Get field temp from raw_aux message
- *
- * @return Temperature (degrees celcius)
- */
-static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int16_t(msg, 10);
-}
-
-/**
- * @brief Get field baro from raw_aux message
- *
- * @return Barometric pressure (hecto Pascal)
- */
-static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 12);
-}
-
-/**
- * @brief Decode a raw_aux message into a struct
- *
- * @param msg The message to decode
- * @param raw_aux C-struct to decode the message contents into
- */
-static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg);
- raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg);
- raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg);
- raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg);
- raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg);
- raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg);
- raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg);
-#else
- memcpy(raw_aux, _MAV_PAYLOAD(msg), 16);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h
deleted file mode 100644
index c51ac730d..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_set_cam_shutter.h
+++ /dev/null
@@ -1,254 +0,0 @@
-// MESSAGE SET_CAM_SHUTTER PACKING
-
-#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 151
-
-typedef struct __mavlink_set_cam_shutter_t
-{
- uint8_t cam_no; ///< Camera id
- uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual
- uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly
- uint16_t interval; ///< Shutter interval, in microseconds
- uint16_t exposure; ///< Exposure time, in microseconds
- float gain; ///< Camera gain
-} mavlink_set_cam_shutter_t;
-
-#define MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN 11
-#define MAVLINK_MSG_ID_151_LEN 11
-
-
-
-#define MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER { \
- "SET_CAM_SHUTTER", \
- 6, \
- { { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_cam_shutter_t, cam_no) }, \
- { "cam_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_cam_shutter_t, cam_mode) }, \
- { "trigger_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_set_cam_shutter_t, trigger_pin) }, \
- { "interval", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_set_cam_shutter_t, interval) }, \
- { "exposure", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_set_cam_shutter_t, exposure) }, \
- { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 7, offsetof(mavlink_set_cam_shutter_t, gain) }, \
- } \
-}
-
-
-/**
- * @brief Pack a set_cam_shutter 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 cam_no Camera id
- * @param cam_mode Camera mode: 0 = auto, 1 = manual
- * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
- * @param interval Shutter interval, in microseconds
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[11];
- _mav_put_uint8_t(buf, 0, cam_no);
- _mav_put_uint8_t(buf, 1, cam_mode);
- _mav_put_uint8_t(buf, 2, trigger_pin);
- _mav_put_uint16_t(buf, 3, interval);
- _mav_put_uint16_t(buf, 5, exposure);
- _mav_put_float(buf, 7, gain);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
-#else
- mavlink_set_cam_shutter_t packet;
- packet.cam_no = cam_no;
- packet.cam_mode = cam_mode;
- packet.trigger_pin = trigger_pin;
- packet.interval = interval;
- packet.exposure = exposure;
- packet.gain = gain;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
- return mavlink_finalize_message(msg, system_id, component_id, 11);
-}
-
-/**
- * @brief Pack a set_cam_shutter 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param cam_no Camera id
- * @param cam_mode Camera mode: 0 = auto, 1 = manual
- * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
- * @param interval Shutter interval, in microseconds
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t cam_no,uint8_t cam_mode,uint8_t trigger_pin,uint16_t interval,uint16_t exposure,float gain)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[11];
- _mav_put_uint8_t(buf, 0, cam_no);
- _mav_put_uint8_t(buf, 1, cam_mode);
- _mav_put_uint8_t(buf, 2, trigger_pin);
- _mav_put_uint16_t(buf, 3, interval);
- _mav_put_uint16_t(buf, 5, exposure);
- _mav_put_float(buf, 7, gain);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
-#else
- mavlink_set_cam_shutter_t packet;
- packet.cam_no = cam_no;
- packet.cam_mode = cam_mode;
- packet.trigger_pin = trigger_pin;
- packet.interval = interval;
- packet.exposure = exposure;
- packet.gain = gain;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11);
-}
-
-/**
- * @brief Encode a set_cam_shutter struct into a 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 set_cam_shutter C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter)
-{
- return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain);
-}
-
-/**
- * @brief Send a set_cam_shutter message
- * @param chan MAVLink channel to send the message
- *
- * @param cam_no Camera id
- * @param cam_mode Camera mode: 0 = auto, 1 = manual
- * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly
- * @param interval Shutter interval, in microseconds
- * @param exposure Exposure time, in microseconds
- * @param gain Camera gain
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[11];
- _mav_put_uint8_t(buf, 0, cam_no);
- _mav_put_uint8_t(buf, 1, cam_mode);
- _mav_put_uint8_t(buf, 2, trigger_pin);
- _mav_put_uint16_t(buf, 3, interval);
- _mav_put_uint16_t(buf, 5, exposure);
- _mav_put_float(buf, 7, gain);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, 11);
-#else
- mavlink_set_cam_shutter_t packet;
- packet.cam_no = cam_no;
- packet.cam_mode = cam_mode;
- packet.trigger_pin = trigger_pin;
- packet.interval = interval;
- packet.exposure = exposure;
- packet.gain = gain;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, 11);
-#endif
-}
-
-#endif
-
-// MESSAGE SET_CAM_SHUTTER UNPACKING
-
-
-/**
- * @brief Get field cam_no from set_cam_shutter message
- *
- * @return Camera id
- */
-static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field cam_mode from set_cam_shutter message
- *
- * @return Camera mode: 0 = auto, 1 = manual
- */
-static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 1);
-}
-
-/**
- * @brief Get field trigger_pin from set_cam_shutter message
- *
- * @return Trigger pin, 0-3 for PtGrey FireFly
- */
-static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 2);
-}
-
-/**
- * @brief Get field interval from set_cam_shutter message
- *
- * @return Shutter interval, in microseconds
- */
-static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 3);
-}
-
-/**
- * @brief Get field exposure from set_cam_shutter message
- *
- * @return Exposure time, in microseconds
- */
-static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 5);
-}
-
-/**
- * @brief Get field gain from set_cam_shutter message
- *
- * @return Camera gain
- */
-static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 7);
-}
-
-/**
- * @brief Decode a set_cam_shutter message into a struct
- *
- * @param msg The message to decode
- * @param set_cam_shutter C-struct to decode the message contents into
- */
-static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg);
- set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg);
- set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg);
- set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg);
- set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg);
- set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg);
-#else
- memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), 11);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h
deleted file mode 100644
index d2b4fbefb..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vicon_position_estimate.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE VICON_POSITION_ESTIMATE PACKING
-
-#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 157
-
-typedef struct __mavlink_vicon_position_estimate_t
-{
- uint64_t usec; ///< Timestamp (milliseconds)
- float x; ///< Global X position
- float y; ///< Global Y position
- float z; ///< Global Z position
- float roll; ///< Roll angle in rad
- float pitch; ///< Pitch angle in rad
- float yaw; ///< Yaw angle in rad
-} mavlink_vicon_position_estimate_t;
-
-#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32
-#define MAVLINK_MSG_ID_157_LEN 32
-
-
-
-#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \
- "VICON_POSITION_ESTIMATE", \
- 7, \
- { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a vicon_position_estimate 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 usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
-#else
- mavlink_vicon_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
- return mavlink_finalize_message(msg, system_id, component_id, 32);
-}
-
-/**
- * @brief Pack a vicon_position_estimate 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
-#else
- mavlink_vicon_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
-}
-
-/**
- * @brief Encode a vicon_position_estimate struct into a 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 vicon_position_estimate C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
-{
- return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
-}
-
-/**
- * @brief Send a vicon_position_estimate message
- * @param chan MAVLink channel to send the message
- *
- * @param usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32);
-#else
- mavlink_vicon_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32);
-#endif
-}
-
-#endif
-
-// MESSAGE VICON_POSITION_ESTIMATE UNPACKING
-
-
-/**
- * @brief Get field usec from vicon_position_estimate message
- *
- * @return Timestamp (milliseconds)
- */
-static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field x from vicon_position_estimate message
- *
- * @return Global X position
- */
-static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field y from vicon_position_estimate message
- *
- * @return Global Y position
- */
-static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field z from vicon_position_estimate message
- *
- * @return Global Z position
- */
-static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field roll from vicon_position_estimate message
- *
- * @return Roll angle in rad
- */
-static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field pitch from vicon_position_estimate message
- *
- * @return Pitch angle in rad
- */
-static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field yaw from vicon_position_estimate message
- *
- * @return Yaw angle in rad
- */
-static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Decode a vicon_position_estimate message into a struct
- *
- * @param msg The message to decode
- * @param vicon_position_estimate C-struct to decode the message contents into
- */
-static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg);
- vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg);
- vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg);
- vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg);
- vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg);
- vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg);
- vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg);
-#else
- memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), 32);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h
deleted file mode 100644
index d257972b7..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_position_estimate.h
+++ /dev/null
@@ -1,276 +0,0 @@
-// MESSAGE VISION_POSITION_ESTIMATE PACKING
-
-#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 156
-
-typedef struct __mavlink_vision_position_estimate_t
-{
- uint64_t usec; ///< Timestamp (milliseconds)
- float x; ///< Global X position
- float y; ///< Global Y position
- float z; ///< Global Z position
- float roll; ///< Roll angle in rad
- float pitch; ///< Pitch angle in rad
- float yaw; ///< Yaw angle in rad
-} mavlink_vision_position_estimate_t;
-
-#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32
-#define MAVLINK_MSG_ID_156_LEN 32
-
-
-
-#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \
- "VISION_POSITION_ESTIMATE", \
- 7, \
- { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \
- { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \
- { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \
- { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \
- } \
-}
-
-
-/**
- * @brief Pack a vision_position_estimate 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 usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
-#else
- mavlink_vision_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
- return mavlink_finalize_message(msg, system_id, component_id, 32);
-}
-
-/**
- * @brief Pack a vision_position_estimate 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
-#else
- mavlink_vision_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
-}
-
-/**
- * @brief Encode a vision_position_estimate struct into a 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 vision_position_estimate C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
-{
- return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
-}
-
-/**
- * @brief Send a vision_position_estimate message
- * @param chan MAVLink channel to send the message
- *
- * @param usec Timestamp (milliseconds)
- * @param x Global X position
- * @param y Global Y position
- * @param z Global Z position
- * @param roll Roll angle in rad
- * @param pitch Pitch angle in rad
- * @param yaw Yaw angle in rad
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[32];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
- _mav_put_float(buf, 20, roll);
- _mav_put_float(buf, 24, pitch);
- _mav_put_float(buf, 28, yaw);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32);
-#else
- mavlink_vision_position_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
- packet.roll = roll;
- packet.pitch = pitch;
- packet.yaw = yaw;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32);
-#endif
-}
-
-#endif
-
-// MESSAGE VISION_POSITION_ESTIMATE UNPACKING
-
-
-/**
- * @brief Get field usec from vision_position_estimate message
- *
- * @return Timestamp (milliseconds)
- */
-static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field x from vision_position_estimate message
- *
- * @return Global X position
- */
-static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field y from vision_position_estimate message
- *
- * @return Global Y position
- */
-static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field z from vision_position_estimate message
- *
- * @return Global Z position
- */
-static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Get field roll from vision_position_estimate message
- *
- * @return Roll angle in rad
- */
-static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 20);
-}
-
-/**
- * @brief Get field pitch from vision_position_estimate message
- *
- * @return Pitch angle in rad
- */
-static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 24);
-}
-
-/**
- * @brief Get field yaw from vision_position_estimate message
- *
- * @return Yaw angle in rad
- */
-static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 28);
-}
-
-/**
- * @brief Decode a vision_position_estimate message into a struct
- *
- * @param msg The message to decode
- * @param vision_position_estimate C-struct to decode the message contents into
- */
-static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);
- vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg);
- vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg);
- vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg);
- vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg);
- vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg);
- vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg);
-#else
- memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), 32);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h
deleted file mode 100644
index 22929dd21..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_vision_speed_estimate.h
+++ /dev/null
@@ -1,210 +0,0 @@
-// MESSAGE VISION_SPEED_ESTIMATE PACKING
-
-#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 158
-
-typedef struct __mavlink_vision_speed_estimate_t
-{
- uint64_t usec; ///< Timestamp (milliseconds)
- float x; ///< Global X speed
- float y; ///< Global Y speed
- float z; ///< Global Z speed
-} mavlink_vision_speed_estimate_t;
-
-#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
-#define MAVLINK_MSG_ID_158_LEN 20
-
-
-
-#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
- "VISION_SPEED_ESTIMATE", \
- 4, \
- { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
- { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
- { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
- { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
- } \
-}
-
-
-/**
- * @brief Pack a vision_speed_estimate 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 usec Timestamp (milliseconds)
- * @param x Global X speed
- * @param y Global Y speed
- * @param z Global Z speed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t usec, float x, float y, float z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
-#else
- mavlink_vision_speed_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
- return mavlink_finalize_message(msg, system_id, component_id, 20);
-}
-
-/**
- * @brief Pack a vision_speed_estimate 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param usec Timestamp (milliseconds)
- * @param x Global X speed
- * @param y Global Y speed
- * @param z Global Z speed
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint64_t usec,float x,float y,float z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
-#else
- mavlink_vision_speed_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20);
-}
-
-/**
- * @brief Encode a vision_speed_estimate struct into a 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 vision_speed_estimate C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
-{
- return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
-}
-
-/**
- * @brief Send a vision_speed_estimate message
- * @param chan MAVLink channel to send the message
- *
- * @param usec Timestamp (milliseconds)
- * @param x Global X speed
- * @param y Global Y speed
- * @param z Global Z speed
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[20];
- _mav_put_uint64_t(buf, 0, usec);
- _mav_put_float(buf, 8, x);
- _mav_put_float(buf, 12, y);
- _mav_put_float(buf, 16, z);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20);
-#else
- mavlink_vision_speed_estimate_t packet;
- packet.usec = usec;
- packet.x = x;
- packet.y = y;
- packet.z = z;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20);
-#endif
-}
-
-#endif
-
-// MESSAGE VISION_SPEED_ESTIMATE UNPACKING
-
-
-/**
- * @brief Get field usec from vision_speed_estimate message
- *
- * @return Timestamp (milliseconds)
- */
-static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint64_t(msg, 0);
-}
-
-/**
- * @brief Get field x from vision_speed_estimate message
- *
- * @return Global X speed
- */
-static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 8);
-}
-
-/**
- * @brief Get field y from vision_speed_estimate message
- *
- * @return Global Y speed
- */
-static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 12);
-}
-
-/**
- * @brief Get field z from vision_speed_estimate message
- *
- * @return Global Z speed
- */
-static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_float(msg, 16);
-}
-
-/**
- * @brief Decode a vision_speed_estimate message into a struct
- *
- * @param msg The message to decode
- * @param vision_speed_estimate C-struct to decode the message contents into
- */
-static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
- vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
- vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
- vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
-#else
- memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), 20);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_command.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_command.h
deleted file mode 100644
index a3ffe71ad..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_command.h
+++ /dev/null
@@ -1,210 +0,0 @@
-// MESSAGE WATCHDOG_COMMAND PACKING
-
-#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 183
-
-typedef struct __mavlink_watchdog_command_t
-{
- uint8_t target_system_id; ///< Target system ID
- uint16_t watchdog_id; ///< Watchdog ID
- uint16_t process_id; ///< Process ID
- uint8_t command_id; ///< Command ID
-} mavlink_watchdog_command_t;
-
-#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN 6
-#define MAVLINK_MSG_ID_183_LEN 6
-
-
-
-#define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \
- "WATCHDOG_COMMAND", \
- 4, \
- { { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_watchdog_command_t, target_system_id) }, \
- { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 1, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \
- { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_watchdog_command_t, process_id) }, \
- { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_command_t, command_id) }, \
- } \
-}
-
-
-/**
- * @brief Pack a watchdog_command 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_id Target system ID
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param command_id Command ID
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[6];
- _mav_put_uint8_t(buf, 0, target_system_id);
- _mav_put_uint16_t(buf, 1, watchdog_id);
- _mav_put_uint16_t(buf, 3, process_id);
- _mav_put_uint8_t(buf, 5, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
-#else
- mavlink_watchdog_command_t packet;
- packet.target_system_id = target_system_id;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
- return mavlink_finalize_message(msg, system_id, component_id, 6);
-}
-
-/**
- * @brief Pack a watchdog_command 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param target_system_id Target system ID
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param command_id Command ID
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint8_t target_system_id,uint16_t watchdog_id,uint16_t process_id,uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[6];
- _mav_put_uint8_t(buf, 0, target_system_id);
- _mav_put_uint16_t(buf, 1, watchdog_id);
- _mav_put_uint16_t(buf, 3, process_id);
- _mav_put_uint8_t(buf, 5, command_id);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
-#else
- mavlink_watchdog_command_t packet;
- packet.target_system_id = target_system_id;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.command_id = command_id;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6);
-}
-
-/**
- * @brief Encode a watchdog_command struct into a 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 watchdog_command C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command)
-{
- return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id);
-}
-
-/**
- * @brief Send a watchdog_command message
- * @param chan MAVLink channel to send the message
- *
- * @param target_system_id Target system ID
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param command_id Command ID
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[6];
- _mav_put_uint8_t(buf, 0, target_system_id);
- _mav_put_uint16_t(buf, 1, watchdog_id);
- _mav_put_uint16_t(buf, 3, process_id);
- _mav_put_uint8_t(buf, 5, command_id);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, 6);
-#else
- mavlink_watchdog_command_t packet;
- packet.target_system_id = target_system_id;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.command_id = command_id;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, 6);
-#endif
-}
-
-#endif
-
-// MESSAGE WATCHDOG_COMMAND UNPACKING
-
-
-/**
- * @brief Get field target_system_id from watchdog_command message
- *
- * @return Target system ID
- */
-static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 0);
-}
-
-/**
- * @brief Get field watchdog_id from watchdog_command message
- *
- * @return Watchdog ID
- */
-static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 1);
-}
-
-/**
- * @brief Get field process_id from watchdog_command message
- *
- * @return Process ID
- */
-static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 3);
-}
-
-/**
- * @brief Get field command_id from watchdog_command message
- *
- * @return Command ID
- */
-static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Decode a watchdog_command message into a struct
- *
- * @param msg The message to decode
- * @param watchdog_command C-struct to decode the message contents into
- */
-static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg);
- watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg);
- watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg);
- watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg);
-#else
- memcpy(watchdog_command, _MAV_PAYLOAD(msg), 6);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h
deleted file mode 100644
index 6dbe21104..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_heartbeat.h
+++ /dev/null
@@ -1,166 +0,0 @@
-// MESSAGE WATCHDOG_HEARTBEAT PACKING
-
-#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 180
-
-typedef struct __mavlink_watchdog_heartbeat_t
-{
- uint16_t watchdog_id; ///< Watchdog ID
- uint16_t process_count; ///< Number of processes
-} mavlink_watchdog_heartbeat_t;
-
-#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN 4
-#define MAVLINK_MSG_ID_180_LEN 4
-
-
-
-#define MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT { \
- "WATCHDOG_HEARTBEAT", \
- 2, \
- { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_heartbeat_t, watchdog_id) }, \
- { "process_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_heartbeat_t, process_count) }, \
- } \
-}
-
-
-/**
- * @brief Pack a watchdog_heartbeat 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 watchdog_id Watchdog ID
- * @param process_count Number of processes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t watchdog_id, uint16_t process_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[4];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_count);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
-#else
- mavlink_watchdog_heartbeat_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_count = process_count;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
- return mavlink_finalize_message(msg, system_id, component_id, 4);
-}
-
-/**
- * @brief Pack a watchdog_heartbeat 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param watchdog_id Watchdog ID
- * @param process_count Number of processes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t watchdog_id,uint16_t process_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[4];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_count);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
-#else
- mavlink_watchdog_heartbeat_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_count = process_count;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
-}
-
-/**
- * @brief Encode a watchdog_heartbeat struct into a 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 watchdog_heartbeat C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
-{
- return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count);
-}
-
-/**
- * @brief Send a watchdog_heartbeat message
- * @param chan MAVLink channel to send the message
- *
- * @param watchdog_id Watchdog ID
- * @param process_count Number of processes
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[4];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_count);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, 4);
-#else
- mavlink_watchdog_heartbeat_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_count = process_count;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, 4);
-#endif
-}
-
-#endif
-
-// MESSAGE WATCHDOG_HEARTBEAT UNPACKING
-
-
-/**
- * @brief Get field watchdog_id from watchdog_heartbeat message
- *
- * @return Watchdog ID
- */
-static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field process_count from watchdog_heartbeat message
- *
- * @return Number of processes
- */
-static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Decode a watchdog_heartbeat message into a struct
- *
- * @param msg The message to decode
- * @param watchdog_heartbeat C-struct to decode the message contents into
- */
-static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg);
- watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg);
-#else
- memcpy(watchdog_heartbeat, _MAV_PAYLOAD(msg), 4);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h
deleted file mode 100644
index 42e896692..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_info.h
+++ /dev/null
@@ -1,227 +0,0 @@
-// MESSAGE WATCHDOG_PROCESS_INFO PACKING
-
-#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 181
-
-typedef struct __mavlink_watchdog_process_info_t
-{
- uint16_t watchdog_id; ///< Watchdog ID
- uint16_t process_id; ///< Process ID
- char name[100]; ///< Process name
- char arguments[147]; ///< Process arguments
- int32_t timeout; ///< Timeout (seconds)
-} mavlink_watchdog_process_info_t;
-
-#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN 255
-#define MAVLINK_MSG_ID_181_LEN 255
-
-#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100
-#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147
-
-#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO { \
- "WATCHDOG_PROCESS_INFO", \
- 5, \
- { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_process_info_t, watchdog_id) }, \
- { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_process_info_t, process_id) }, \
- { "name", NULL, MAVLINK_TYPE_CHAR, 100, 4, offsetof(mavlink_watchdog_process_info_t, name) }, \
- { "arguments", NULL, MAVLINK_TYPE_CHAR, 147, 104, offsetof(mavlink_watchdog_process_info_t, arguments) }, \
- { "timeout", NULL, MAVLINK_TYPE_INT32_T, 0, 251, offsetof(mavlink_watchdog_process_info_t, timeout) }, \
- } \
-}
-
-
-/**
- * @brief Pack a watchdog_process_info 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 watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param name Process name
- * @param arguments Process arguments
- * @param timeout Timeout (seconds)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_int32_t(buf, 251, timeout);
- _mav_put_char_array(buf, 4, name, 100);
- _mav_put_char_array(buf, 104, arguments, 147);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255);
-#else
- mavlink_watchdog_process_info_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.timeout = timeout;
- mav_array_memcpy(packet.name, name, sizeof(char)*100);
- mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
- return mavlink_finalize_message(msg, system_id, component_id, 255);
-}
-
-/**
- * @brief Pack a watchdog_process_info 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param name Process name
- * @param arguments Process arguments
- * @param timeout Timeout (seconds)
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t watchdog_id,uint16_t process_id,const char *name,const char *arguments,int32_t timeout)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_int32_t(buf, 251, timeout);
- _mav_put_char_array(buf, 4, name, 100);
- _mav_put_char_array(buf, 104, arguments, 147);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 255);
-#else
- mavlink_watchdog_process_info_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.timeout = timeout;
- mav_array_memcpy(packet.name, name, sizeof(char)*100);
- mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 255);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 255);
-}
-
-/**
- * @brief Encode a watchdog_process_info struct into a 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 watchdog_process_info C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info)
-{
- return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout);
-}
-
-/**
- * @brief Send a watchdog_process_info message
- * @param chan MAVLink channel to send the message
- *
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param name Process name
- * @param arguments Process arguments
- * @param timeout Timeout (seconds)
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[255];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_int32_t(buf, 251, timeout);
- _mav_put_char_array(buf, 4, name, 100);
- _mav_put_char_array(buf, 104, arguments, 147);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, 255);
-#else
- mavlink_watchdog_process_info_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.timeout = timeout;
- mav_array_memcpy(packet.name, name, sizeof(char)*100);
- mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, 255);
-#endif
-}
-
-#endif
-
-// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING
-
-
-/**
- * @brief Get field watchdog_id from watchdog_process_info message
- *
- * @return Watchdog ID
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field process_id from watchdog_process_info message
- *
- * @return Process ID
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Get field name from watchdog_process_info message
- *
- * @return Process name
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, char *name)
-{
- return _MAV_RETURN_char_array(msg, name, 100, 4);
-}
-
-/**
- * @brief Get field arguments from watchdog_process_info message
- *
- * @return Process arguments
- */
-static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, char *arguments)
-{
- return _MAV_RETURN_char_array(msg, arguments, 147, 104);
-}
-
-/**
- * @brief Get field timeout from watchdog_process_info message
- *
- * @return Timeout (seconds)
- */
-static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 251);
-}
-
-/**
- * @brief Decode a watchdog_process_info message into a struct
- *
- * @param msg The message to decode
- * @param watchdog_process_info C-struct to decode the message contents into
- */
-static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg);
- watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg);
- mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name);
- mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments);
- watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg);
-#else
- memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), 255);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h b/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h
deleted file mode 100644
index de5c7b2b2..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/mavlink_msg_watchdog_process_status.h
+++ /dev/null
@@ -1,254 +0,0 @@
-// MESSAGE WATCHDOG_PROCESS_STATUS PACKING
-
-#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 182
-
-typedef struct __mavlink_watchdog_process_status_t
-{
- uint16_t watchdog_id; ///< Watchdog ID
- uint16_t process_id; ///< Process ID
- uint8_t state; ///< Is running / finished / suspended / crashed
- uint8_t muted; ///< Is muted
- int32_t pid; ///< PID
- uint16_t crashes; ///< Number of crashes
-} mavlink_watchdog_process_status_t;
-
-#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12
-#define MAVLINK_MSG_ID_182_LEN 12
-
-
-
-#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \
- "WATCHDOG_PROCESS_STATUS", \
- 6, \
- { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \
- { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_process_status_t, process_id) }, \
- { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, state) }, \
- { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_process_status_t, muted) }, \
- { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, pid) }, \
- { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, crashes) }, \
- } \
-}
-
-
-/**
- * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param state Is running / finished / suspended / crashed
- * @param muted Is muted
- * @param pid PID
- * @param crashes Number of crashes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_uint8_t(buf, 4, state);
- _mav_put_uint8_t(buf, 5, muted);
- _mav_put_int32_t(buf, 6, pid);
- _mav_put_uint16_t(buf, 10, crashes);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
-#else
- mavlink_watchdog_process_status_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.state = state;
- packet.muted = muted;
- packet.pid = pid;
- packet.crashes = crashes;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
- return mavlink_finalize_message(msg, system_id, component_id, 12);
-}
-
-/**
- * @brief Pack a watchdog_process_status 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 was sent over
- * @param msg The MAVLink message to compress the data into
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param state Is running / finished / suspended / crashed
- * @param muted Is muted
- * @param pid PID
- * @param crashes Number of crashes
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint16_t watchdog_id,uint16_t process_id,uint8_t state,uint8_t muted,int32_t pid,uint16_t crashes)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_uint8_t(buf, 4, state);
- _mav_put_uint8_t(buf, 5, muted);
- _mav_put_int32_t(buf, 6, pid);
- _mav_put_uint16_t(buf, 10, crashes);
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
-#else
- mavlink_watchdog_process_status_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.state = state;
- packet.muted = muted;
- packet.pid = pid;
- packet.crashes = crashes;
-
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
-#endif
-
- msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
-}
-
-/**
- * @brief Encode a watchdog_process_status struct into a 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 watchdog_process_status C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
-{
- return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
-}
-
-/**
- * @brief Send a watchdog_process_status message
- * @param chan MAVLink channel to send the message
- *
- * @param watchdog_id Watchdog ID
- * @param process_id Process ID
- * @param state Is running / finished / suspended / crashed
- * @param muted Is muted
- * @param pid PID
- * @param crashes Number of crashes
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[12];
- _mav_put_uint16_t(buf, 0, watchdog_id);
- _mav_put_uint16_t(buf, 2, process_id);
- _mav_put_uint8_t(buf, 4, state);
- _mav_put_uint8_t(buf, 5, muted);
- _mav_put_int32_t(buf, 6, pid);
- _mav_put_uint16_t(buf, 10, crashes);
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, 12);
-#else
- mavlink_watchdog_process_status_t packet;
- packet.watchdog_id = watchdog_id;
- packet.process_id = process_id;
- packet.state = state;
- packet.muted = muted;
- packet.pid = pid;
- packet.crashes = crashes;
-
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, 12);
-#endif
-}
-
-#endif
-
-// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING
-
-
-/**
- * @brief Get field watchdog_id from watchdog_process_status message
- *
- * @return Watchdog ID
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 0);
-}
-
-/**
- * @brief Get field process_id from watchdog_process_status message
- *
- * @return Process ID
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 2);
-}
-
-/**
- * @brief Get field state from watchdog_process_status message
- *
- * @return Is running / finished / suspended / crashed
- */
-static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 4);
-}
-
-/**
- * @brief Get field muted from watchdog_process_status message
- *
- * @return Is muted
- */
-static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint8_t(msg, 5);
-}
-
-/**
- * @brief Get field pid from watchdog_process_status message
- *
- * @return PID
- */
-static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_int32_t(msg, 6);
-}
-
-/**
- * @brief Get field crashes from watchdog_process_status message
- *
- * @return Number of crashes
- */
-static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg)
-{
- return _MAV_RETURN_uint16_t(msg, 10);
-}
-
-/**
- * @brief Decode a watchdog_process_status message into a struct
- *
- * @param msg The message to decode
- * @param watchdog_process_status C-struct to decode the message contents into
- */
-static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status)
-{
-#if MAVLINK_NEED_BYTE_SWAP
- watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg);
- watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg);
- watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg);
- watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg);
- watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg);
- watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg);
-#else
- memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), 12);
-#endif
-}
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/pixhawk.h b/mavlink/include/mavlink/v0.9/pixhawk/pixhawk.h
deleted file mode 100644
index feb759ef9..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/pixhawk.h
+++ /dev/null
@@ -1,86 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol generated from pixhawk.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef PIXHAWK_H
-#define PIXHAWK_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-// MESSAGE LENGTHS AND CRCS
-
-#ifndef MAVLINK_MESSAGE_LENGTHS
-#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 11, 52, 1, 92, 0, 32, 32, 20, 20, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 8, 255, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
-#endif
-
-#ifndef MAVLINK_MESSAGE_CRCS
-#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 86, 95, 49, 0, 158, 56, 208, 218, 115, 0, 0, 0, 0, 0, 0, 0, 0, 0, 220, 136, 140, 0, 0, 0, 0, 0, 0, 0, 153, 110, 92, 188, 0, 0, 0, 0, 0, 0, 106, 154, 83, 98, 223, 254, 0, 0, 0, 0, 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, 178, 224, 60, 106, 7}
-#endif
-
-#ifndef MAVLINK_MESSAGE_INFO
-#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, 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}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_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}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, 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, {"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_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, 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_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT_SET, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_OFFSET_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"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_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
-#endif
-
-#include "../protocol.h"
-
-#define MAVLINK_ENABLED_PIXHAWK
-
-#include "../common/common.h"
-
-// MAVLINK VERSION
-
-#ifndef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-#if (MAVLINK_VERSION == 0)
-#undef MAVLINK_VERSION
-#define MAVLINK_VERSION 2
-#endif
-
-// ENUM DEFINITIONS
-
-
-/** @brief Content Types for data transmission handshake */
-#ifndef HAVE_ENUM_DATA_TYPES
-#define HAVE_ENUM_DATA_TYPES
-enum DATA_TYPES
-{
- DATA_TYPE_JPEG_IMAGE=1, /* | */
- DATA_TYPE_RAW_IMAGE=2, /* | */
- DATA_TYPE_KINECT=3, /* | */
- DATA_TYPES_ENUM_END=4, /* | */
-};
-#endif
-
-// MESSAGE DEFINITIONS
-#include "./mavlink_msg_set_cam_shutter.h"
-#include "./mavlink_msg_image_triggered.h"
-#include "./mavlink_msg_image_trigger_control.h"
-#include "./mavlink_msg_image_available.h"
-#include "./mavlink_msg_vision_position_estimate.h"
-#include "./mavlink_msg_vicon_position_estimate.h"
-#include "./mavlink_msg_vision_speed_estimate.h"
-#include "./mavlink_msg_position_control_setpoint_set.h"
-#include "./mavlink_msg_position_control_offset_set.h"
-#include "./mavlink_msg_position_control_setpoint.h"
-#include "./mavlink_msg_marker.h"
-#include "./mavlink_msg_raw_aux.h"
-#include "./mavlink_msg_watchdog_heartbeat.h"
-#include "./mavlink_msg_watchdog_process_info.h"
-#include "./mavlink_msg_watchdog_process_status.h"
-#include "./mavlink_msg_watchdog_command.h"
-#include "./mavlink_msg_pattern_detected.h"
-#include "./mavlink_msg_point_of_interest.h"
-#include "./mavlink_msg_point_of_interest_connection.h"
-#include "./mavlink_msg_data_transmission_handshake.h"
-#include "./mavlink_msg_encapsulated_data.h"
-#include "./mavlink_msg_brief_feature.h"
-#include "./mavlink_msg_attitude_control.h"
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // PIXHAWK_H
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/testsuite.h b/mavlink/include/mavlink/v0.9/pixhawk/testsuite.h
deleted file mode 100644
index 3e18abc82..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/testsuite.h
+++ /dev/null
@@ -1,1312 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol testsuite generated from pixhawk.xml
- * @see http://qgroundcontrol.org/mavlink/
- */
-#ifndef PIXHAWK_TESTSUITE_H
-#define PIXHAWK_TESTSUITE_H
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-#ifndef MAVLINK_TEST_ALL
-#define MAVLINK_TEST_ALL
-static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
-static void mavlink_test_pixhawk(uint8_t, uint8_t, mavlink_message_t *last_msg);
-
-static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_common(system_id, component_id, last_msg);
- mavlink_test_pixhawk(system_id, component_id, last_msg);
-}
-#endif
-
-#include "../common/testsuite.h"
-
-
-static void mavlink_test_set_cam_shutter(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_cam_shutter_t packet_in = {
- 5,
- 72,
- 139,
- 17391,
- 17495,
- 66.0,
- };
- mavlink_set_cam_shutter_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.cam_no = packet_in.cam_no;
- packet1.cam_mode = packet_in.cam_mode;
- packet1.trigger_pin = packet_in.trigger_pin;
- packet1.interval = packet_in.interval;
- packet1.exposure = packet_in.exposure;
- packet1.gain = packet_in.gain;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_cam_shutter_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_set_cam_shutter_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_cam_shutter_pack(system_id, component_id, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain );
- mavlink_msg_set_cam_shutter_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_cam_shutter_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain );
- mavlink_msg_set_cam_shutter_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_cam_shutter_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_set_cam_shutter_send(MAVLINK_COMM_1 , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain );
- mavlink_msg_set_cam_shutter_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_image_triggered(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_image_triggered_t packet_in = {
- 93372036854775807ULL,
- 963497880,
- 101.0,
- 129.0,
- 157.0,
- 185.0,
- 213.0,
- 241.0,
- 269.0,
- 297.0,
- 325.0,
- 353.0,
- };
- mavlink_image_triggered_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.timestamp = packet_in.timestamp;
- packet1.seq = packet_in.seq;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.local_z = packet_in.local_z;
- packet1.lat = packet_in.lat;
- packet1.lon = packet_in.lon;
- packet1.alt = packet_in.alt;
- packet1.ground_x = packet_in.ground_x;
- packet1.ground_y = packet_in.ground_y;
- packet1.ground_z = packet_in.ground_z;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_triggered_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_image_triggered_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_triggered_pack(system_id, component_id, &msg , packet1.timestamp , packet1.seq , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_triggered_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_triggered_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.seq , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_triggered_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_image_triggered_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_triggered_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.seq , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_triggered_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_image_trigger_control(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_image_trigger_control_t packet_in = {
- 5,
- };
- mavlink_image_trigger_control_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.enable = packet_in.enable;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_trigger_control_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_image_trigger_control_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_trigger_control_pack(system_id, component_id, &msg , packet1.enable );
- mavlink_msg_image_trigger_control_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_trigger_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.enable );
- mavlink_msg_image_trigger_control_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_image_trigger_control_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_trigger_control_send(MAVLINK_COMM_1 , packet1.enable );
- mavlink_msg_image_trigger_control_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_image_available(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_image_available_t packet_in = {
- 93372036854775807ULL,
- 29,
- 93372036854776374ULL,
- 93372036854776878ULL,
- 963498764,
- 963498972,
- 18951,
- 19055,
- 19159,
- 58,
- 963499544,
- 963499752,
- 353.0,
- 381.0,
- 409.0,
- 437.0,
- 465.0,
- 493.0,
- 521.0,
- 549.0,
- 577.0,
- 605.0,
- 633.0,
- };
- mavlink_image_available_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.cam_id = packet_in.cam_id;
- packet1.cam_no = packet_in.cam_no;
- packet1.timestamp = packet_in.timestamp;
- packet1.valid_until = packet_in.valid_until;
- packet1.img_seq = packet_in.img_seq;
- packet1.img_buf_index = packet_in.img_buf_index;
- packet1.width = packet_in.width;
- packet1.height = packet_in.height;
- packet1.depth = packet_in.depth;
- packet1.channels = packet_in.channels;
- packet1.key = packet_in.key;
- packet1.exposure = packet_in.exposure;
- packet1.gain = packet_in.gain;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.local_z = packet_in.local_z;
- packet1.lat = packet_in.lat;
- packet1.lon = packet_in.lon;
- packet1.alt = packet_in.alt;
- packet1.ground_x = packet_in.ground_x;
- packet1.ground_y = packet_in.ground_y;
- packet1.ground_z = packet_in.ground_z;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_available_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_image_available_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_available_pack(system_id, component_id, &msg , packet1.cam_id , packet1.cam_no , packet1.timestamp , packet1.valid_until , packet1.img_seq , packet1.img_buf_index , packet1.width , packet1.height , packet1.depth , packet1.channels , packet1.key , packet1.exposure , packet1.gain , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_available_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_available_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cam_id , packet1.cam_no , packet1.timestamp , packet1.valid_until , packet1.img_seq , packet1.img_buf_index , packet1.width , packet1.height , packet1.depth , packet1.channels , packet1.key , packet1.exposure , packet1.gain , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_available_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_image_available_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_image_available_send(MAVLINK_COMM_1 , packet1.cam_id , packet1.cam_no , packet1.timestamp , packet1.valid_until , packet1.img_seq , packet1.img_buf_index , packet1.width , packet1.height , packet1.depth , packet1.channels , packet1.key , packet1.exposure , packet1.gain , packet1.roll , packet1.pitch , packet1.yaw , packet1.local_z , packet1.lat , packet1.lon , packet1.alt , packet1.ground_x , packet1.ground_y , packet1.ground_z );
- mavlink_msg_image_available_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_vision_position_estimate(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_vision_position_estimate_t packet_in = {
- 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;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vision_position_estimate_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_vision_position_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vision_position_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_vicon_position_estimate(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_vicon_position_estimate_t packet_in = {
- 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;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vicon_position_estimate_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_vicon_position_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vicon_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_vicon_position_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_vision_speed_estimate(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_vision_speed_estimate_t packet_in = {
- 93372036854775807ULL,
- 73.0,
- 101.0,
- 129.0,
- };
- mavlink_vision_speed_estimate_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.usec = packet_in.usec;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
- mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
- mavlink_msg_vision_speed_estimate_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_vision_speed_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_vision_speed_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z );
- mavlink_msg_vision_speed_estimate_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_position_control_setpoint_set(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_control_setpoint_set_t packet_in = {
- 5,
- 72,
- 17339,
- 45.0,
- 73.0,
- 101.0,
- 129.0,
- };
- mavlink_position_control_setpoint_set_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.target_system = packet_in.target_system;
- packet1.target_component = packet_in.target_component;
- packet1.id = packet_in.id;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_set_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_position_control_setpoint_set_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_set_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_set_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_control_setpoint_set_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_set_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_set_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_position_control_offset_set(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_control_offset_set_t packet_in = {
- 5,
- 72,
- 31.0,
- 59.0,
- 87.0,
- 115.0,
- };
- mavlink_position_control_offset_set_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.target_system = packet_in.target_system;
- packet1.target_component = packet_in.target_component;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_offset_set_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_position_control_offset_set_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_offset_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_offset_set_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_offset_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_offset_set_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_control_offset_set_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_offset_set_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_offset_set_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_position_control_setpoint(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_control_setpoint_t packet_in = {
- 17235,
- 31.0,
- 59.0,
- 87.0,
- 115.0,
- };
- mavlink_position_control_setpoint_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.id = packet_in.id;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_position_control_setpoint_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_pack(system_id, component_id, &msg , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_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_control_setpoint_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_position_control_setpoint_send(MAVLINK_COMM_1 , packet1.id , packet1.x , packet1.y , packet1.z , packet1.yaw );
- mavlink_msg_position_control_setpoint_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_marker(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_marker_t packet_in = {
- 17235,
- 31.0,
- 59.0,
- 87.0,
- 115.0,
- 143.0,
- 171.0,
- };
- mavlink_marker_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.id = packet_in.id;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_marker_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_marker_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_marker_pack(system_id, component_id, &msg , packet1.id , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_marker_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_marker_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_marker_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_marker_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_marker_send(MAVLINK_COMM_1 , packet1.id , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
- mavlink_msg_marker_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_raw_aux(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_raw_aux_t packet_in = {
- 17235,
- 17339,
- 17443,
- 17547,
- 17651,
- 17755,
- 963498088,
- };
- mavlink_raw_aux_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.adc1 = packet_in.adc1;
- packet1.adc2 = packet_in.adc2;
- packet1.adc3 = packet_in.adc3;
- packet1.adc4 = packet_in.adc4;
- packet1.vbat = packet_in.vbat;
- packet1.temp = packet_in.temp;
- packet1.baro = packet_in.baro;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_aux_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_raw_aux_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_aux_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.vbat , packet1.temp , packet1.baro );
- mavlink_msg_raw_aux_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_aux_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.vbat , packet1.temp , packet1.baro );
- mavlink_msg_raw_aux_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_raw_aux_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_raw_aux_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.vbat , packet1.temp , packet1.baro );
- mavlink_msg_raw_aux_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_watchdog_heartbeat(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_watchdog_heartbeat_t packet_in = {
- 17235,
- 17339,
- };
- mavlink_watchdog_heartbeat_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.watchdog_id = packet_in.watchdog_id;
- packet1.process_count = packet_in.process_count;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_heartbeat_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_watchdog_heartbeat_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, &msg , packet1.watchdog_id , packet1.process_count );
- mavlink_msg_watchdog_heartbeat_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.watchdog_id , packet1.process_count );
- mavlink_msg_watchdog_heartbeat_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_watchdog_heartbeat_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_heartbeat_send(MAVLINK_COMM_1 , packet1.watchdog_id , packet1.process_count );
- mavlink_msg_watchdog_heartbeat_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_watchdog_process_info(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_watchdog_process_info_t packet_in = {
- 17235,
- 17339,
- "EFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXY",
- "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOP",
- 963510516,
- };
- mavlink_watchdog_process_info_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.watchdog_id = packet_in.watchdog_id;
- packet1.process_id = packet_in.process_id;
- packet1.timeout = packet_in.timeout;
-
- mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*100);
- mav_array_memcpy(packet1.arguments, packet_in.arguments, sizeof(char)*147);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_info_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_watchdog_process_info_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_info_pack(system_id, component_id, &msg , packet1.watchdog_id , packet1.process_id , packet1.name , packet1.arguments , packet1.timeout );
- mavlink_msg_watchdog_process_info_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.watchdog_id , packet1.process_id , packet1.name , packet1.arguments , packet1.timeout );
- mavlink_msg_watchdog_process_info_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_watchdog_process_info_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_info_send(MAVLINK_COMM_1 , packet1.watchdog_id , packet1.process_id , packet1.name , packet1.arguments , packet1.timeout );
- mavlink_msg_watchdog_process_info_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_watchdog_process_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_watchdog_process_status_t packet_in = {
- 17235,
- 17339,
- 17,
- 84,
- 963497776,
- 17755,
- };
- mavlink_watchdog_process_status_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.watchdog_id = packet_in.watchdog_id;
- packet1.process_id = packet_in.process_id;
- packet1.state = packet_in.state;
- packet1.muted = packet_in.muted;
- packet1.pid = packet_in.pid;
- packet1.crashes = packet_in.crashes;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_status_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_watchdog_process_status_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_status_pack(system_id, component_id, &msg , packet1.watchdog_id , packet1.process_id , packet1.state , packet1.muted , packet1.pid , packet1.crashes );
- mavlink_msg_watchdog_process_status_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.watchdog_id , packet1.process_id , packet1.state , packet1.muted , packet1.pid , packet1.crashes );
- mavlink_msg_watchdog_process_status_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_watchdog_process_status_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_process_status_send(MAVLINK_COMM_1 , packet1.watchdog_id , packet1.process_id , packet1.state , packet1.muted , packet1.pid , packet1.crashes );
- mavlink_msg_watchdog_process_status_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_watchdog_command(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_watchdog_command_t packet_in = {
- 5,
- 17287,
- 17391,
- 84,
- };
- mavlink_watchdog_command_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.target_system_id = packet_in.target_system_id;
- packet1.watchdog_id = packet_in.watchdog_id;
- packet1.process_id = packet_in.process_id;
- packet1.command_id = packet_in.command_id;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_command_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_watchdog_command_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_command_pack(system_id, component_id, &msg , packet1.target_system_id , packet1.watchdog_id , packet1.process_id , packet1.command_id );
- mavlink_msg_watchdog_command_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_command_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system_id , packet1.watchdog_id , packet1.process_id , packet1.command_id );
- mavlink_msg_watchdog_command_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_watchdog_command_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_watchdog_command_send(MAVLINK_COMM_1 , packet1.target_system_id , packet1.watchdog_id , packet1.process_id , packet1.command_id );
- mavlink_msg_watchdog_command_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_pattern_detected(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_pattern_detected_t packet_in = {
- 5,
- 24.0,
- "FGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZ",
- 128,
- };
- mavlink_pattern_detected_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.type = packet_in.type;
- packet1.confidence = packet_in.confidence;
- packet1.detected = packet_in.detected;
-
- mav_array_memcpy(packet1.file, packet_in.file, sizeof(char)*100);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pattern_detected_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_pattern_detected_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pattern_detected_pack(system_id, component_id, &msg , packet1.type , packet1.confidence , packet1.file , packet1.detected );
- mavlink_msg_pattern_detected_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pattern_detected_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.confidence , packet1.file , packet1.detected );
- mavlink_msg_pattern_detected_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_pattern_detected_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_pattern_detected_send(MAVLINK_COMM_1 , packet1.type , packet1.confidence , packet1.file , packet1.detected );
- mavlink_msg_pattern_detected_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_point_of_interest(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_point_of_interest_t packet_in = {
- 5,
- 72,
- 139,
- 17391,
- 52.0,
- 80.0,
- 108.0,
- "RSTUVWXYZABCDEFGHIJKLMNOP",
- };
- mavlink_point_of_interest_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.type = packet_in.type;
- packet1.color = packet_in.color;
- packet1.coordinate_system = packet_in.coordinate_system;
- packet1.timeout = packet_in.timeout;
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
-
- mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*26);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_point_of_interest_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_pack(system_id, component_id, &msg , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.x , packet1.y , packet1.z , packet1.name );
- mavlink_msg_point_of_interest_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.x , packet1.y , packet1.z , packet1.name );
- mavlink_msg_point_of_interest_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_point_of_interest_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_send(MAVLINK_COMM_1 , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.x , packet1.y , packet1.z , packet1.name );
- mavlink_msg_point_of_interest_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_point_of_interest_connection(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_point_of_interest_connection_t packet_in = {
- 5,
- 72,
- 139,
- 17391,
- 52.0,
- 80.0,
- 108.0,
- 136.0,
- 164.0,
- 192.0,
- "DEFGHIJKLMNOPQRSTUVWXYZAB",
- };
- mavlink_point_of_interest_connection_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.type = packet_in.type;
- packet1.color = packet_in.color;
- packet1.coordinate_system = packet_in.coordinate_system;
- packet1.timeout = packet_in.timeout;
- packet1.xp1 = packet_in.xp1;
- packet1.yp1 = packet_in.yp1;
- packet1.zp1 = packet_in.zp1;
- packet1.xp2 = packet_in.xp2;
- packet1.yp2 = packet_in.yp2;
- packet1.zp2 = packet_in.zp2;
-
- mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*26);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_connection_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_point_of_interest_connection_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_connection_pack(system_id, component_id, &msg , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.xp1 , packet1.yp1 , packet1.zp1 , packet1.xp2 , packet1.yp2 , packet1.zp2 , packet1.name );
- mavlink_msg_point_of_interest_connection_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_connection_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.xp1 , packet1.yp1 , packet1.zp1 , packet1.xp2 , packet1.yp2 , packet1.zp2 , packet1.name );
- mavlink_msg_point_of_interest_connection_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_point_of_interest_connection_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_point_of_interest_connection_send(MAVLINK_COMM_1 , packet1.type , packet1.color , packet1.coordinate_system , packet1.timeout , packet1.xp1 , packet1.yp1 , packet1.zp1 , packet1.xp2 , packet1.yp2 , packet1.zp2 , packet1.name );
- mavlink_msg_point_of_interest_connection_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_data_transmission_handshake(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_data_transmission_handshake_t packet_in = {
- 5,
- 963497516,
- 84,
- 151,
- 218,
- };
- mavlink_data_transmission_handshake_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.type = packet_in.type;
- packet1.size = packet_in.size;
- packet1.packets = packet_in.packets;
- packet1.payload = packet_in.payload;
- packet1.jpg_quality = packet_in.jpg_quality;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_data_transmission_handshake_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_data_transmission_handshake_pack(system_id, component_id, &msg , packet1.type , packet1.size , packet1.packets , packet1.payload , packet1.jpg_quality );
- mavlink_msg_data_transmission_handshake_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.size , packet1.packets , packet1.payload , packet1.jpg_quality );
- mavlink_msg_data_transmission_handshake_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_data_transmission_handshake_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_data_transmission_handshake_send(MAVLINK_COMM_1 , packet1.type , packet1.size , packet1.packets , packet1.payload , packet1.jpg_quality );
- mavlink_msg_data_transmission_handshake_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_encapsulated_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_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 },
- };
- mavlink_encapsulated_data_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.seqnr = packet_in.seqnr;
-
- mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*253);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_encapsulated_data_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_encapsulated_data_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_encapsulated_data_pack(system_id, component_id, &msg , packet1.seqnr , packet1.data );
- mavlink_msg_encapsulated_data_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seqnr , packet1.data );
- mavlink_msg_encapsulated_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_encapsulated_data_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_encapsulated_data_send(MAVLINK_COMM_1 , packet1.seqnr , packet1.data );
- mavlink_msg_encapsulated_data_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_brief_feature(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_brief_feature_t packet_in = {
- 17.0,
- 45.0,
- 73.0,
- 41,
- 17911,
- 18015,
- { 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 },
- 360.0,
- };
- mavlink_brief_feature_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.x = packet_in.x;
- packet1.y = packet_in.y;
- packet1.z = packet_in.z;
- packet1.orientation_assignment = packet_in.orientation_assignment;
- packet1.size = packet_in.size;
- packet1.orientation = packet_in.orientation;
- packet1.response = packet_in.response;
-
- mav_array_memcpy(packet1.descriptor, packet_in.descriptor, sizeof(uint8_t)*32);
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_brief_feature_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_brief_feature_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_brief_feature_pack(system_id, component_id, &msg , packet1.x , packet1.y , packet1.z , packet1.orientation_assignment , packet1.size , packet1.orientation , packet1.descriptor , packet1.response );
- mavlink_msg_brief_feature_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_brief_feature_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.x , packet1.y , packet1.z , packet1.orientation_assignment , packet1.size , packet1.orientation , packet1.descriptor , packet1.response );
- mavlink_msg_brief_feature_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_brief_feature_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_brief_feature_send(MAVLINK_COMM_1 , packet1.x , packet1.y , packet1.z , packet1.orientation_assignment , packet1.size , packet1.orientation , packet1.descriptor , packet1.response );
- mavlink_msg_brief_feature_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_attitude_control(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_control_t packet_in = {
- 5,
- 24.0,
- 52.0,
- 80.0,
- 108.0,
- 120,
- 187,
- 254,
- 65,
- };
- mavlink_attitude_control_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.target = packet_in.target;
- packet1.roll = packet_in.roll;
- packet1.pitch = packet_in.pitch;
- packet1.yaw = packet_in.yaw;
- packet1.thrust = packet_in.thrust;
- packet1.roll_manual = packet_in.roll_manual;
- packet1.pitch_manual = packet_in.pitch_manual;
- packet1.yaw_manual = packet_in.yaw_manual;
- packet1.thrust_manual = packet_in.thrust_manual;
-
-
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_control_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_attitude_control_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_control_pack(system_id, component_id, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
- mavlink_msg_attitude_control_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
- mavlink_msg_attitude_control_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_control_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_attitude_control_send(MAVLINK_COMM_1 , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
- mavlink_msg_attitude_control_decode(last_msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-}
-
-static void mavlink_test_pixhawk(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
-{
- mavlink_test_set_cam_shutter(system_id, component_id, last_msg);
- mavlink_test_image_triggered(system_id, component_id, last_msg);
- mavlink_test_image_trigger_control(system_id, component_id, last_msg);
- mavlink_test_image_available(system_id, component_id, last_msg);
- mavlink_test_vision_position_estimate(system_id, component_id, last_msg);
- mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
- mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
- mavlink_test_position_control_setpoint_set(system_id, component_id, last_msg);
- mavlink_test_position_control_offset_set(system_id, component_id, last_msg);
- mavlink_test_position_control_setpoint(system_id, component_id, last_msg);
- mavlink_test_marker(system_id, component_id, last_msg);
- mavlink_test_raw_aux(system_id, component_id, last_msg);
- mavlink_test_watchdog_heartbeat(system_id, component_id, last_msg);
- mavlink_test_watchdog_process_info(system_id, component_id, last_msg);
- mavlink_test_watchdog_process_status(system_id, component_id, last_msg);
- mavlink_test_watchdog_command(system_id, component_id, last_msg);
- mavlink_test_pattern_detected(system_id, component_id, last_msg);
- mavlink_test_point_of_interest(system_id, component_id, last_msg);
- mavlink_test_point_of_interest_connection(system_id, component_id, last_msg);
- mavlink_test_data_transmission_handshake(system_id, component_id, last_msg);
- mavlink_test_encapsulated_data(system_id, component_id, last_msg);
- mavlink_test_brief_feature(system_id, component_id, last_msg);
- mavlink_test_attitude_control(system_id, component_id, last_msg);
-}
-
-#ifdef __cplusplus
-}
-#endif // __cplusplus
-#endif // PIXHAWK_TESTSUITE_H
diff --git a/mavlink/include/mavlink/v0.9/pixhawk/version.h b/mavlink/include/mavlink/v0.9/pixhawk/version.h
deleted file mode 100644
index e13db0762..000000000
--- a/mavlink/include/mavlink/v0.9/pixhawk/version.h
+++ /dev/null
@@ -1,12 +0,0 @@
-/** @file
- * @brief MAVLink comm protocol built from pixhawk.xml
- * @see http://pixhawk.ethz.ch/software/mavlink
- */
-#ifndef MAVLINK_VERSION_H
-#define MAVLINK_VERSION_H
-
-#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:50 2012"
-#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
-#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
-
-#endif // MAVLINK_VERSION_H