GCS_MAVLink: re-generate headers

This commit is contained in:
Andrew Tridgell 2015-01-29 20:00:20 +11:00
parent 3b2332a0c7
commit 01325b701a
5 changed files with 69 additions and 19 deletions

View File

@ -16,11 +16,11 @@ extern "C" {
// MESSAGE LENGTHS AND CRCS
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 0, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 60, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 40, 0, 40, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 37, 0, 0, 0, 27, 25, 0, 0, 0, 0, 0, 68, 26, 185, 181, 42, 6, 4, 0, 11, 18, 0, 0, 37, 20, 35, 33, 3, 0, 0, 0, 22, 39, 37, 53, 51, 53, 51, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 44, 64, 84, 9, 254, 16, 0, 36, 44, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 18, 43, 8, 22, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 60, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 45, 4, 40, 0, 42, 26, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 254, 36, 30, 18, 18, 51, 9, 0}
#endif
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 0, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 195, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 178, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 229, 0, 160, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 78, 0, 0, 0, 15, 3, 0, 0, 0, 0, 0, 153, 183, 51, 82, 118, 148, 21, 0, 243, 124, 0, 0, 38, 20, 158, 152, 143, 0, 0, 0, 106, 49, 22, 143, 140, 5, 150, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 138, 108, 32, 185, 84, 34, 0, 124, 237, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 6, 229, 203, 1, 195, 0, 0, 0, 0, 0, 0, 0, 0, 0, 154, 178, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 189, 52, 174, 229, 0, 90, 239, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 204, 49, 170, 44, 83, 46, 0}
#endif
#ifndef MAVLINK_MESSAGE_INFO

View File

@ -14,19 +14,21 @@ typedef struct __mavlink_gimbal_report_t
float joint_roll; ///< Joint roll, radians
float joint_pitch; ///< Joint pitch, radians
float joint_yaw; ///< Joint yaw, radians
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_gimbal_report_t;
#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 40
#define MAVLINK_MSG_ID_184_LEN 40
#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42
#define MAVLINK_MSG_ID_184_LEN 42
#define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 160
#define MAVLINK_MSG_ID_184_CRC 160
#define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 90
#define MAVLINK_MSG_ID_184_CRC 90
#define MAVLINK_MESSAGE_INFO_GIMBAL_REPORT { \
"GIMBAL_REPORT", \
10, \
12, \
{ { "counter", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_report_t, counter) }, \
{ "delta_angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_report_t, delta_angle_x) }, \
{ "delta_angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_report_t, delta_angle_y) }, \
@ -37,6 +39,8 @@ typedef struct __mavlink_gimbal_report_t
{ "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \
{ "joint_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_pitch) }, \
{ "joint_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_yaw) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
} \
}
@ -47,6 +51,8 @@ typedef struct __mavlink_gimbal_report_t
* @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 counter Report counter
* @param delta_angle_x Delta angle X, radians
* @param delta_angle_y Delta angle Y, radians
@ -60,7 +66,7 @@ typedef struct __mavlink_gimbal_report_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
uint8_t target_system, uint8_t target_component, uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -74,6 +80,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch);
_mav_put_float(buf, 36, joint_yaw);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#else
@ -88,6 +96,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch;
packet.joint_yaw = joint_yaw;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#endif
@ -106,6 +116,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param counter Report counter
* @param delta_angle_x Delta angle X, radians
* @param delta_angle_y Delta angle Y, radians
@ -120,7 +132,7 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
*/
static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t counter,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_pitch,float joint_yaw)
uint8_t target_system,uint8_t target_component,uint32_t counter,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_pitch,float joint_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -134,6 +146,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, ui
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch);
_mav_put_float(buf, 36, joint_yaw);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#else
@ -148,6 +162,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, ui
packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch;
packet.joint_yaw = joint_yaw;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#endif
@ -170,7 +186,7 @@ static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, ui
*/
static inline uint16_t mavlink_msg_gimbal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
{
return mavlink_msg_gimbal_report_pack(system_id, component_id, msg, gimbal_report->counter, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_pitch, gimbal_report->joint_yaw);
return mavlink_msg_gimbal_report_pack(system_id, component_id, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->counter, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_pitch, gimbal_report->joint_yaw);
}
/**
@ -184,13 +200,15 @@ static inline uint16_t mavlink_msg_gimbal_report_encode(uint8_t system_id, uint8
*/
static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
{
return mavlink_msg_gimbal_report_pack_chan(system_id, component_id, chan, msg, gimbal_report->counter, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_pitch, gimbal_report->joint_yaw);
return mavlink_msg_gimbal_report_pack_chan(system_id, component_id, chan, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->counter, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_pitch, gimbal_report->joint_yaw);
}
/**
* @brief Send a gimbal_report message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param counter Report counter
* @param delta_angle_x Delta angle X, radians
* @param delta_angle_y Delta angle Y, radians
@ -204,7 +222,7 @@ static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id,
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -218,6 +236,8 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint32
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch);
_mav_put_float(buf, 36, joint_yaw);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
@ -236,6 +256,8 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint32
packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch;
packet.joint_yaw = joint_yaw;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
@ -253,7 +275,7 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint32
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t counter, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_pitch, float joint_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -267,6 +289,8 @@ static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf,
_mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch);
_mav_put_float(buf, 36, joint_yaw);
_mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
@ -285,6 +309,8 @@ static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf,
packet->joint_roll = joint_roll;
packet->joint_pitch = joint_pitch;
packet->joint_yaw = joint_yaw;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
@ -300,6 +326,26 @@ static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf,
// MESSAGE GIMBAL_REPORT UNPACKING
/**
* @brief Get field target_system from gimbal_report message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_report_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field target_component from gimbal_report message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_report_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
/**
* @brief Get field counter from gimbal_report message
*
@ -419,6 +465,8 @@ static inline void mavlink_msg_gimbal_report_decode(const mavlink_message_t* msg
gimbal_report->joint_roll = mavlink_msg_gimbal_report_get_joint_roll(msg);
gimbal_report->joint_pitch = mavlink_msg_gimbal_report_get_joint_pitch(msg);
gimbal_report->joint_yaw = mavlink_msg_gimbal_report_get_joint_yaw(msg);
gimbal_report->target_system = mavlink_msg_gimbal_report_get_target_system(msg);
gimbal_report->target_component = mavlink_msg_gimbal_report_get_target_component(msg);
#else
memcpy(gimbal_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
#endif

View File

@ -1574,7 +1574,7 @@ static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id,
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gimbal_report_t packet_in = {
963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0
963497464,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192
};
mavlink_gimbal_report_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
@ -1588,6 +1588,8 @@ static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id,
packet1.joint_roll = packet_in.joint_roll;
packet1.joint_pitch = packet_in.joint_pitch;
packet1.joint_yaw = packet_in.joint_yaw;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
@ -1597,12 +1599,12 @@ static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_pack(system_id, component_id, &msg , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@ -1615,7 +1617,7 @@ static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id,
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_send(MAVLINK_COMM_1 , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.counter , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_pitch , packet1.joint_yaw );
mavlink_msg_gimbal_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Jan 29 08:58:35 2015"
#define MAVLINK_BUILD_DATE "Thu Jan 29 19:15:50 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Thu Jan 29 08:58:40 2015"
#define MAVLINK_BUILD_DATE "Thu Jan 29 19:15:52 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255