GCS_MAVLink: re-ran generate.sh

This commit is contained in:
Andrew Tridgell 2015-04-06 16:30:16 -07:00
parent 73b8890bd3
commit 33824e0b2f
8 changed files with 323 additions and 343 deletions

File diff suppressed because one or more lines are too long

View File

@ -1,38 +1,32 @@
// MESSAGE GIMBAL_CONTROL PACKING // MESSAGE GIMBAL_CONTROL PACKING
#define MAVLINK_MSG_ID_GIMBAL_CONTROL 185 #define MAVLINK_MSG_ID_GIMBAL_CONTROL 201
typedef struct __mavlink_gimbal_control_t typedef struct __mavlink_gimbal_control_t
{ {
float demanded_rate_x; ///< Demanded angular rate X, radians/s float demanded_rate_x; ///< Demanded angular rate X (rad/s)
float demanded_rate_y; ///< Demanded angular rate Y, radians/s float demanded_rate_y; ///< Demanded angular rate Y (rad/s)
float demanded_rate_z; ///< Demanded angular rate Z, radians/s float demanded_rate_z; ///< Demanded angular rate Z (rad/s)
float gyro_bias_x; ///< Gyro bias X, radians/s
float gyro_bias_y; ///< Gyro bias Y, radians/s
float gyro_bias_z; ///< Gyro bias Z, radians/s
uint8_t target_system; ///< System ID uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID uint8_t target_component; ///< Component ID
} mavlink_gimbal_control_t; } mavlink_gimbal_control_t;
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN 26 #define MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN 14
#define MAVLINK_MSG_ID_185_LEN 26 #define MAVLINK_MSG_ID_201_LEN 14
#define MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC 239 #define MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC 205
#define MAVLINK_MSG_ID_185_CRC 239 #define MAVLINK_MSG_ID_201_CRC 205
#define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \ #define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \
"GIMBAL_CONTROL", \ "GIMBAL_CONTROL", \
8, \ 5, \
{ { "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \ { { "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \
{ "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \ { "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \
{ "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \ { "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \
{ "gyro_bias_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_control_t, gyro_bias_x) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_control_t, target_system) }, \
{ "gyro_bias_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_control_t, gyro_bias_y) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gimbal_control_t, target_component) }, \
{ "gyro_bias_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_control_t, gyro_bias_z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_gimbal_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_gimbal_control_t, target_component) }, \
} \ } \
} }
@ -45,27 +39,21 @@ typedef struct __mavlink_gimbal_control_t
* *
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param demanded_rate_x Demanded angular rate X, radians/s * @param demanded_rate_x Demanded angular rate X (rad/s)
* @param demanded_rate_y Demanded angular rate Y, radians/s * @param demanded_rate_y Demanded angular rate Y (rad/s)
* @param demanded_rate_z Demanded angular rate Z, radians/s * @param demanded_rate_z Demanded angular rate Z (rad/s)
* @param gyro_bias_x Gyro bias X, radians/s
* @param gyro_bias_y Gyro bias Y, radians/s
* @param gyro_bias_z Gyro bias Z, radians/s
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
*/ */
static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z) uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x); _mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y); _mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z); _mav_put_float(buf, 8, demanded_rate_z);
_mav_put_float(buf, 12, gyro_bias_x); _mav_put_uint8_t(buf, 12, target_system);
_mav_put_float(buf, 16, gyro_bias_y); _mav_put_uint8_t(buf, 13, target_component);
_mav_put_float(buf, 20, gyro_bias_z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#else #else
@ -73,9 +61,6 @@ static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_
packet.demanded_rate_x = demanded_rate_x; packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y; packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z; packet.demanded_rate_z = demanded_rate_z;
packet.gyro_bias_x = gyro_bias_x;
packet.gyro_bias_y = gyro_bias_y;
packet.gyro_bias_z = gyro_bias_z;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -98,28 +83,22 @@ static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_
* @param msg The MAVLink message to compress the data into * @param msg The MAVLink message to compress the data into
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param demanded_rate_x Demanded angular rate X, radians/s * @param demanded_rate_x Demanded angular rate X (rad/s)
* @param demanded_rate_y Demanded angular rate Y, radians/s * @param demanded_rate_y Demanded angular rate Y (rad/s)
* @param demanded_rate_z Demanded angular rate Z, radians/s * @param demanded_rate_z Demanded angular rate Z (rad/s)
* @param gyro_bias_x Gyro bias X, radians/s
* @param gyro_bias_y Gyro bias Y, radians/s
* @param gyro_bias_z Gyro bias Z, radians/s
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
*/ */
static inline uint16_t mavlink_msg_gimbal_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, static inline uint16_t mavlink_msg_gimbal_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg, mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,float demanded_rate_x,float demanded_rate_y,float demanded_rate_z,float gyro_bias_x,float gyro_bias_y,float gyro_bias_z) uint8_t target_system,uint8_t target_component,float demanded_rate_x,float demanded_rate_y,float demanded_rate_z)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x); _mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y); _mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z); _mav_put_float(buf, 8, demanded_rate_z);
_mav_put_float(buf, 12, gyro_bias_x); _mav_put_uint8_t(buf, 12, target_system);
_mav_put_float(buf, 16, gyro_bias_y); _mav_put_uint8_t(buf, 13, target_component);
_mav_put_float(buf, 20, gyro_bias_z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
#else #else
@ -127,9 +106,6 @@ static inline uint16_t mavlink_msg_gimbal_control_pack_chan(uint8_t system_id, u
packet.demanded_rate_x = demanded_rate_x; packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y; packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z; packet.demanded_rate_z = demanded_rate_z;
packet.gyro_bias_x = gyro_bias_x;
packet.gyro_bias_y = gyro_bias_y;
packet.gyro_bias_z = gyro_bias_z;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -154,7 +130,7 @@ static inline uint16_t mavlink_msg_gimbal_control_pack_chan(uint8_t system_id, u
*/ */
static inline uint16_t mavlink_msg_gimbal_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control) static inline uint16_t mavlink_msg_gimbal_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
{ {
return mavlink_msg_gimbal_control_pack(system_id, component_id, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z, gimbal_control->gyro_bias_x, gimbal_control->gyro_bias_y, gimbal_control->gyro_bias_z); return mavlink_msg_gimbal_control_pack(system_id, component_id, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
} }
/** /**
@ -168,7 +144,7 @@ static inline uint16_t mavlink_msg_gimbal_control_encode(uint8_t system_id, uint
*/ */
static inline uint16_t mavlink_msg_gimbal_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control) static inline uint16_t mavlink_msg_gimbal_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
{ {
return mavlink_msg_gimbal_control_pack_chan(system_id, component_id, chan, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z, gimbal_control->gyro_bias_x, gimbal_control->gyro_bias_y, gimbal_control->gyro_bias_z); return mavlink_msg_gimbal_control_pack_chan(system_id, component_id, chan, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
} }
/** /**
@ -177,27 +153,21 @@ static inline uint16_t mavlink_msg_gimbal_control_encode_chan(uint8_t system_id,
* *
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param demanded_rate_x Demanded angular rate X, radians/s * @param demanded_rate_x Demanded angular rate X (rad/s)
* @param demanded_rate_y Demanded angular rate Y, radians/s * @param demanded_rate_y Demanded angular rate Y (rad/s)
* @param demanded_rate_z Demanded angular rate Z, radians/s * @param demanded_rate_z Demanded angular rate Z (rad/s)
* @param gyro_bias_x Gyro bias X, radians/s
* @param gyro_bias_y Gyro bias Y, radians/s
* @param gyro_bias_z Gyro bias Z, radians/s
*/ */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z) static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
_mav_put_float(buf, 0, demanded_rate_x); _mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y); _mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z); _mav_put_float(buf, 8, demanded_rate_z);
_mav_put_float(buf, 12, gyro_bias_x); _mav_put_uint8_t(buf, 12, target_system);
_mav_put_float(buf, 16, gyro_bias_y); _mav_put_uint8_t(buf, 13, target_component);
_mav_put_float(buf, 20, gyro_bias_z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
#if MAVLINK_CRC_EXTRA #if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
@ -209,9 +179,6 @@ static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8
packet.demanded_rate_x = demanded_rate_x; packet.demanded_rate_x = demanded_rate_x;
packet.demanded_rate_y = demanded_rate_y; packet.demanded_rate_y = demanded_rate_y;
packet.demanded_rate_z = demanded_rate_z; packet.demanded_rate_z = demanded_rate_z;
packet.gyro_bias_x = gyro_bias_x;
packet.gyro_bias_y = gyro_bias_y;
packet.gyro_bias_z = gyro_bias_z;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -231,18 +198,15 @@ static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8
is usually the receive buffer for the channel, and allows a reply to an is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage. incoming message with minimum stack space usage.
*/ */
static inline void mavlink_msg_gimbal_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z, float gyro_bias_x, float gyro_bias_y, float gyro_bias_z) static inline void mavlink_msg_gimbal_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf; char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, demanded_rate_x); _mav_put_float(buf, 0, demanded_rate_x);
_mav_put_float(buf, 4, demanded_rate_y); _mav_put_float(buf, 4, demanded_rate_y);
_mav_put_float(buf, 8, demanded_rate_z); _mav_put_float(buf, 8, demanded_rate_z);
_mav_put_float(buf, 12, gyro_bias_x); _mav_put_uint8_t(buf, 12, target_system);
_mav_put_float(buf, 16, gyro_bias_y); _mav_put_uint8_t(buf, 13, target_component);
_mav_put_float(buf, 20, gyro_bias_z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
#if MAVLINK_CRC_EXTRA #if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
@ -254,9 +218,6 @@ static inline void mavlink_msg_gimbal_control_send_buf(mavlink_message_t *msgbuf
packet->demanded_rate_x = demanded_rate_x; packet->demanded_rate_x = demanded_rate_x;
packet->demanded_rate_y = demanded_rate_y; packet->demanded_rate_y = demanded_rate_y;
packet->demanded_rate_z = demanded_rate_z; packet->demanded_rate_z = demanded_rate_z;
packet->gyro_bias_x = gyro_bias_x;
packet->gyro_bias_y = gyro_bias_y;
packet->gyro_bias_z = gyro_bias_z;
packet->target_system = target_system; packet->target_system = target_system;
packet->target_component = target_component; packet->target_component = target_component;
@ -281,7 +242,7 @@ static inline void mavlink_msg_gimbal_control_send_buf(mavlink_message_t *msgbuf
*/ */
static inline uint8_t mavlink_msg_gimbal_control_get_target_system(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_gimbal_control_get_target_system(const mavlink_message_t* msg)
{ {
return _MAV_RETURN_uint8_t(msg, 24); return _MAV_RETURN_uint8_t(msg, 12);
} }
/** /**
@ -291,13 +252,13 @@ static inline uint8_t mavlink_msg_gimbal_control_get_target_system(const mavlink
*/ */
static inline uint8_t mavlink_msg_gimbal_control_get_target_component(const mavlink_message_t* msg) static inline uint8_t mavlink_msg_gimbal_control_get_target_component(const mavlink_message_t* msg)
{ {
return _MAV_RETURN_uint8_t(msg, 25); return _MAV_RETURN_uint8_t(msg, 13);
} }
/** /**
* @brief Get field demanded_rate_x from gimbal_control message * @brief Get field demanded_rate_x from gimbal_control message
* *
* @return Demanded angular rate X, radians/s * @return Demanded angular rate X (rad/s)
*/ */
static inline float mavlink_msg_gimbal_control_get_demanded_rate_x(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_control_get_demanded_rate_x(const mavlink_message_t* msg)
{ {
@ -307,7 +268,7 @@ static inline float mavlink_msg_gimbal_control_get_demanded_rate_x(const mavlink
/** /**
* @brief Get field demanded_rate_y from gimbal_control message * @brief Get field demanded_rate_y from gimbal_control message
* *
* @return Demanded angular rate Y, radians/s * @return Demanded angular rate Y (rad/s)
*/ */
static inline float mavlink_msg_gimbal_control_get_demanded_rate_y(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_control_get_demanded_rate_y(const mavlink_message_t* msg)
{ {
@ -317,43 +278,13 @@ static inline float mavlink_msg_gimbal_control_get_demanded_rate_y(const mavlink
/** /**
* @brief Get field demanded_rate_z from gimbal_control message * @brief Get field demanded_rate_z from gimbal_control message
* *
* @return Demanded angular rate Z, radians/s * @return Demanded angular rate Z (rad/s)
*/ */
static inline float mavlink_msg_gimbal_control_get_demanded_rate_z(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_control_get_demanded_rate_z(const mavlink_message_t* msg)
{ {
return _MAV_RETURN_float(msg, 8); return _MAV_RETURN_float(msg, 8);
} }
/**
* @brief Get field gyro_bias_x from gimbal_control message
*
* @return Gyro bias X, radians/s
*/
static inline float mavlink_msg_gimbal_control_get_gyro_bias_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field gyro_bias_y from gimbal_control message
*
* @return Gyro bias Y, radians/s
*/
static inline float mavlink_msg_gimbal_control_get_gyro_bias_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field gyro_bias_z from gimbal_control message
*
* @return Gyro bias Z, radians/s
*/
static inline float mavlink_msg_gimbal_control_get_gyro_bias_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/** /**
* @brief Decode a gimbal_control message into a struct * @brief Decode a gimbal_control message into a struct
* *
@ -366,9 +297,6 @@ static inline void mavlink_msg_gimbal_control_decode(const mavlink_message_t* ms
gimbal_control->demanded_rate_x = mavlink_msg_gimbal_control_get_demanded_rate_x(msg); gimbal_control->demanded_rate_x = mavlink_msg_gimbal_control_get_demanded_rate_x(msg);
gimbal_control->demanded_rate_y = mavlink_msg_gimbal_control_get_demanded_rate_y(msg); gimbal_control->demanded_rate_y = mavlink_msg_gimbal_control_get_demanded_rate_y(msg);
gimbal_control->demanded_rate_z = mavlink_msg_gimbal_control_get_demanded_rate_z(msg); gimbal_control->demanded_rate_z = mavlink_msg_gimbal_control_get_demanded_rate_z(msg);
gimbal_control->gyro_bias_x = mavlink_msg_gimbal_control_get_gyro_bias_x(msg);
gimbal_control->gyro_bias_y = mavlink_msg_gimbal_control_get_gyro_bias_y(msg);
gimbal_control->gyro_bias_z = mavlink_msg_gimbal_control_get_gyro_bias_z(msg);
gimbal_control->target_system = mavlink_msg_gimbal_control_get_target_system(msg); gimbal_control->target_system = mavlink_msg_gimbal_control_get_target_system(msg);
gimbal_control->target_component = mavlink_msg_gimbal_control_get_target_component(msg); gimbal_control->target_component = mavlink_msg_gimbal_control_get_target_component(msg);
#else #else

View File

@ -1,28 +1,28 @@
// MESSAGE GIMBAL_REPORT PACKING // MESSAGE GIMBAL_REPORT PACKING
#define MAVLINK_MSG_ID_GIMBAL_REPORT 184 #define MAVLINK_MSG_ID_GIMBAL_REPORT 200
typedef struct __mavlink_gimbal_report_t typedef struct __mavlink_gimbal_report_t
{ {
float delta_time; ///< Time since last update (seconds) float delta_time; ///< Time since last update (seconds)
float delta_angle_x; ///< Delta angle X, radians float delta_angle_x; ///< Delta angle X (radians)
float delta_angle_y; ///< Delta angle Y, radians float delta_angle_y; ///< Delta angle Y (radians)
float delta_angle_z; ///< Delta angle Z, radians float delta_angle_z; ///< Delta angle X (radians)
float delta_velocity_x; ///< Delta velocity X, m/s float delta_velocity_x; ///< Delta velocity X (m/s)
float delta_velocity_y; ///< Delta velocity Y, m/s float delta_velocity_y; ///< Delta velocity Y (m/s)
float delta_velocity_z; ///< Delta velocity Z, m/s float delta_velocity_z; ///< Delta velocity Z (m/s)
float joint_roll; ///< Joint roll, radians float joint_roll; ///< Joint ROLL (radians)
float joint_pitch; ///< Joint pitch, radians float joint_el; ///< Joint EL (radians)
float joint_yaw; ///< Joint yaw, radians float joint_az; ///< Joint AZ (radians)
uint8_t target_system; ///< System ID uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID uint8_t target_component; ///< Component ID
} mavlink_gimbal_report_t; } mavlink_gimbal_report_t;
#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42 #define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42
#define MAVLINK_MSG_ID_184_LEN 42 #define MAVLINK_MSG_ID_200_LEN 42
#define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 97 #define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 134
#define MAVLINK_MSG_ID_184_CRC 97 #define MAVLINK_MSG_ID_200_CRC 134
@ -37,8 +37,8 @@ typedef struct __mavlink_gimbal_report_t
{ "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \ { "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \
{ "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \ { "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \
{ "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \ { "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_el", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_el) }, \
{ "joint_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_yaw) }, \ { "joint_az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_az) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \ { "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) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
} \ } \
@ -54,19 +54,19 @@ typedef struct __mavlink_gimbal_report_t
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param delta_time Time since last update (seconds) * @param delta_time Time since last update (seconds)
* @param delta_angle_x Delta angle X, radians * @param delta_angle_x Delta angle X (radians)
* @param delta_angle_y Delta angle Y, radians * @param delta_angle_y Delta angle Y (radians)
* @param delta_angle_z Delta angle Z, radians * @param delta_angle_z Delta angle X (radians)
* @param delta_velocity_x Delta velocity X, m/s * @param delta_velocity_x Delta velocity X (m/s)
* @param delta_velocity_y Delta velocity Y, m/s * @param delta_velocity_y Delta velocity Y (m/s)
* @param delta_velocity_z Delta velocity Z, m/s * @param delta_velocity_z Delta velocity Z (m/s)
* @param joint_roll Joint roll, radians * @param joint_roll Joint ROLL (radians)
* @param joint_pitch Joint pitch, radians * @param joint_el Joint EL (radians)
* @param joint_yaw Joint yaw, radians * @param joint_az Joint AZ (radians)
* @return length of the message in bytes (excluding serial stream start sign) * @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, static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float delta_time, 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, float delta_time, 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_el, float joint_az)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -78,8 +78,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
_mav_put_float(buf, 20, delta_velocity_y); _mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z); _mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll); _mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch); _mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_yaw); _mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system); _mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component); _mav_put_uint8_t(buf, 41, target_component);
@ -94,8 +94,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
packet.delta_velocity_y = delta_velocity_y; packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z; packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll; packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch; packet.joint_el = joint_el;
packet.joint_yaw = joint_yaw; packet.joint_az = joint_az;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -119,20 +119,20 @@ static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param delta_time Time since last update (seconds) * @param delta_time Time since last update (seconds)
* @param delta_angle_x Delta angle X, radians * @param delta_angle_x Delta angle X (radians)
* @param delta_angle_y Delta angle Y, radians * @param delta_angle_y Delta angle Y (radians)
* @param delta_angle_z Delta angle Z, radians * @param delta_angle_z Delta angle X (radians)
* @param delta_velocity_x Delta velocity X, m/s * @param delta_velocity_x Delta velocity X (m/s)
* @param delta_velocity_y Delta velocity Y, m/s * @param delta_velocity_y Delta velocity Y (m/s)
* @param delta_velocity_z Delta velocity Z, m/s * @param delta_velocity_z Delta velocity Z (m/s)
* @param joint_roll Joint roll, radians * @param joint_roll Joint ROLL (radians)
* @param joint_pitch Joint pitch, radians * @param joint_el Joint EL (radians)
* @param joint_yaw Joint yaw, radians * @param joint_az Joint AZ (radians)
* @return length of the message in bytes (excluding serial stream start sign) * @return length of the message in bytes (excluding serial stream start sign)
*/ */
static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 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, mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,float delta_time,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,float delta_time,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_el,float joint_az)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -144,8 +144,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, ui
_mav_put_float(buf, 20, delta_velocity_y); _mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z); _mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll); _mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch); _mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_yaw); _mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system); _mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component); _mav_put_uint8_t(buf, 41, target_component);
@ -160,8 +160,8 @@ static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, ui
packet.delta_velocity_y = delta_velocity_y; packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z; packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll; packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch; packet.joint_el = joint_el;
packet.joint_yaw = joint_yaw; packet.joint_az = joint_az;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -186,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) 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->target_system, gimbal_report->target_component, gimbal_report->delta_time, 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->delta_time, 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_el, gimbal_report->joint_az);
} }
/** /**
@ -200,7 +200,7 @@ 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) 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->target_system, gimbal_report->target_component, gimbal_report->delta_time, 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->delta_time, 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_el, gimbal_report->joint_az);
} }
/** /**
@ -210,19 +210,19 @@ static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id,
* @param target_system System ID * @param target_system System ID
* @param target_component Component ID * @param target_component Component ID
* @param delta_time Time since last update (seconds) * @param delta_time Time since last update (seconds)
* @param delta_angle_x Delta angle X, radians * @param delta_angle_x Delta angle X (radians)
* @param delta_angle_y Delta angle Y, radians * @param delta_angle_y Delta angle Y (radians)
* @param delta_angle_z Delta angle Z, radians * @param delta_angle_z Delta angle X (radians)
* @param delta_velocity_x Delta velocity X, m/s * @param delta_velocity_x Delta velocity X (m/s)
* @param delta_velocity_y Delta velocity Y, m/s * @param delta_velocity_y Delta velocity Y (m/s)
* @param delta_velocity_z Delta velocity Z, m/s * @param delta_velocity_z Delta velocity Z (m/s)
* @param joint_roll Joint roll, radians * @param joint_roll Joint ROLL (radians)
* @param joint_pitch Joint pitch, radians * @param joint_el Joint EL (radians)
* @param joint_yaw Joint yaw, radians * @param joint_az Joint AZ (radians)
*/ */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float delta_time, 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, float delta_time, 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_el, float joint_az)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN]; char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
@ -234,8 +234,8 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_
_mav_put_float(buf, 20, delta_velocity_y); _mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z); _mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll); _mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch); _mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_yaw); _mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system); _mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component); _mav_put_uint8_t(buf, 41, target_component);
@ -254,8 +254,8 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_
packet.delta_velocity_y = delta_velocity_y; packet.delta_velocity_y = delta_velocity_y;
packet.delta_velocity_z = delta_velocity_z; packet.delta_velocity_z = delta_velocity_z;
packet.joint_roll = joint_roll; packet.joint_roll = joint_roll;
packet.joint_pitch = joint_pitch; packet.joint_el = joint_el;
packet.joint_yaw = joint_yaw; packet.joint_az = joint_az;
packet.target_system = target_system; packet.target_system = target_system;
packet.target_component = target_component; packet.target_component = target_component;
@ -275,7 +275,7 @@ static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_
is usually the receive buffer for the channel, and allows a reply to an is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage. incoming message with minimum stack space usage.
*/ */
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, float delta_time, 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, float delta_time, 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_el, float joint_az)
{ {
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf; char *buf = (char *)msgbuf;
@ -287,8 +287,8 @@ static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf,
_mav_put_float(buf, 20, delta_velocity_y); _mav_put_float(buf, 20, delta_velocity_y);
_mav_put_float(buf, 24, delta_velocity_z); _mav_put_float(buf, 24, delta_velocity_z);
_mav_put_float(buf, 28, joint_roll); _mav_put_float(buf, 28, joint_roll);
_mav_put_float(buf, 32, joint_pitch); _mav_put_float(buf, 32, joint_el);
_mav_put_float(buf, 36, joint_yaw); _mav_put_float(buf, 36, joint_az);
_mav_put_uint8_t(buf, 40, target_system); _mav_put_uint8_t(buf, 40, target_system);
_mav_put_uint8_t(buf, 41, target_component); _mav_put_uint8_t(buf, 41, target_component);
@ -307,8 +307,8 @@ static inline void mavlink_msg_gimbal_report_send_buf(mavlink_message_t *msgbuf,
packet->delta_velocity_y = delta_velocity_y; packet->delta_velocity_y = delta_velocity_y;
packet->delta_velocity_z = delta_velocity_z; packet->delta_velocity_z = delta_velocity_z;
packet->joint_roll = joint_roll; packet->joint_roll = joint_roll;
packet->joint_pitch = joint_pitch; packet->joint_el = joint_el;
packet->joint_yaw = joint_yaw; packet->joint_az = joint_az;
packet->target_system = target_system; packet->target_system = target_system;
packet->target_component = target_component; packet->target_component = target_component;
@ -359,7 +359,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_time(const mavlink_messa
/** /**
* @brief Get field delta_angle_x from gimbal_report message * @brief Get field delta_angle_x from gimbal_report message
* *
* @return Delta angle X, radians * @return Delta angle X (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_angle_x(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_angle_x(const mavlink_message_t* msg)
{ {
@ -369,7 +369,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_angle_x(const mavlink_me
/** /**
* @brief Get field delta_angle_y from gimbal_report message * @brief Get field delta_angle_y from gimbal_report message
* *
* @return Delta angle Y, radians * @return Delta angle Y (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_angle_y(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_angle_y(const mavlink_message_t* msg)
{ {
@ -379,7 +379,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_angle_y(const mavlink_me
/** /**
* @brief Get field delta_angle_z from gimbal_report message * @brief Get field delta_angle_z from gimbal_report message
* *
* @return Delta angle Z, radians * @return Delta angle X (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_angle_z(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_angle_z(const mavlink_message_t* msg)
{ {
@ -389,7 +389,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_angle_z(const mavlink_me
/** /**
* @brief Get field delta_velocity_x from gimbal_report message * @brief Get field delta_velocity_x from gimbal_report message
* *
* @return Delta velocity X, m/s * @return Delta velocity X (m/s)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_velocity_x(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_velocity_x(const mavlink_message_t* msg)
{ {
@ -399,7 +399,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_velocity_x(const mavlink
/** /**
* @brief Get field delta_velocity_y from gimbal_report message * @brief Get field delta_velocity_y from gimbal_report message
* *
* @return Delta velocity Y, m/s * @return Delta velocity Y (m/s)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_velocity_y(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_velocity_y(const mavlink_message_t* msg)
{ {
@ -409,7 +409,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_velocity_y(const mavlink
/** /**
* @brief Get field delta_velocity_z from gimbal_report message * @brief Get field delta_velocity_z from gimbal_report message
* *
* @return Delta velocity Z, m/s * @return Delta velocity Z (m/s)
*/ */
static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink_message_t* msg)
{ {
@ -419,7 +419,7 @@ static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink
/** /**
* @brief Get field joint_roll from gimbal_report message * @brief Get field joint_roll from gimbal_report message
* *
* @return Joint roll, radians * @return Joint ROLL (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_message_t* msg)
{ {
@ -427,21 +427,21 @@ static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_messa
} }
/** /**
* @brief Get field joint_pitch from gimbal_report message * @brief Get field joint_el from gimbal_report message
* *
* @return Joint pitch, radians * @return Joint EL (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_joint_pitch(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_joint_el(const mavlink_message_t* msg)
{ {
return _MAV_RETURN_float(msg, 32); return _MAV_RETURN_float(msg, 32);
} }
/** /**
* @brief Get field joint_yaw from gimbal_report message * @brief Get field joint_az from gimbal_report message
* *
* @return Joint yaw, radians * @return Joint AZ (radians)
*/ */
static inline float mavlink_msg_gimbal_report_get_joint_yaw(const mavlink_message_t* msg) static inline float mavlink_msg_gimbal_report_get_joint_az(const mavlink_message_t* msg)
{ {
return _MAV_RETURN_float(msg, 36); return _MAV_RETURN_float(msg, 36);
} }
@ -463,8 +463,8 @@ static inline void mavlink_msg_gimbal_report_decode(const mavlink_message_t* msg
gimbal_report->delta_velocity_y = mavlink_msg_gimbal_report_get_delta_velocity_y(msg); gimbal_report->delta_velocity_y = mavlink_msg_gimbal_report_get_delta_velocity_y(msg);
gimbal_report->delta_velocity_z = mavlink_msg_gimbal_report_get_delta_velocity_z(msg); gimbal_report->delta_velocity_z = mavlink_msg_gimbal_report_get_delta_velocity_z(msg);
gimbal_report->joint_roll = mavlink_msg_gimbal_report_get_joint_roll(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_el = mavlink_msg_gimbal_report_get_joint_el(msg);
gimbal_report->joint_yaw = mavlink_msg_gimbal_report_get_joint_yaw(msg); gimbal_report->joint_az = mavlink_msg_gimbal_report_get_joint_az(msg);
gimbal_report->target_system = mavlink_msg_gimbal_report_get_target_system(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); gimbal_report->target_component = mavlink_msg_gimbal_report_get_target_component(msg);
#else #else

View File

@ -1612,110 +1612,6 @@ static void mavlink_test_autopilot_version_request(uint8_t system_id, uint8_t co
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gimbal_report_t packet_in = {
17.0,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));
packet1.delta_time = packet_in.delta_time;
packet1.delta_angle_x = packet_in.delta_angle_x;
packet1.delta_angle_y = packet_in.delta_angle_y;
packet1.delta_angle_z = packet_in.delta_angle_z;
packet1.delta_velocity_x = packet_in.delta_velocity_x;
packet1.delta_velocity_y = packet_in.delta_velocity_y;
packet1.delta_velocity_z = packet_in.delta_velocity_z;
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;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_encode(system_id, component_id, &msg, &packet1);
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(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.delta_time , 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.target_system , packet1.target_component , packet1.delta_time , 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_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_gimbal_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.delta_time , 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);
}
static void mavlink_test_gimbal_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_gimbal_control_t packet_in = {
17.0,45.0,73.0,101.0,129.0,157.0,77,144
};
mavlink_gimbal_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.demanded_rate_x = packet_in.demanded_rate_x;
packet1.demanded_rate_y = packet_in.demanded_rate_y;
packet1.demanded_rate_z = packet_in.demanded_rate_z;
packet1.gyro_bias_x = packet_in.gyro_bias_x;
packet1.gyro_bias_y = packet_in.gyro_bias_y;
packet1.gyro_bias_z = packet_in.gyro_bias_z;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gimbal_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z );
mavlink_msg_gimbal_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z );
mavlink_msg_gimbal_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_gimbal_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z , packet1.gyro_bias_x , packet1.gyro_bias_y , packet1.gyro_bias_z );
mavlink_msg_gimbal_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_led_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_led_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_message_t msg; mavlink_message_t msg;
@ -1812,6 +1708,107 @@ static void mavlink_test_ekf_status_report(uint8_t system_id, uint8_t component_
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
} }
static void mavlink_test_gimbal_report(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gimbal_report_t packet_in = {
17.0,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));
packet1.delta_time = packet_in.delta_time;
packet1.delta_angle_x = packet_in.delta_angle_x;
packet1.delta_angle_y = packet_in.delta_angle_y;
packet1.delta_angle_z = packet_in.delta_angle_z;
packet1.delta_velocity_x = packet_in.delta_velocity_x;
packet1.delta_velocity_y = packet_in.delta_velocity_y;
packet1.delta_velocity_z = packet_in.delta_velocity_z;
packet1.joint_roll = packet_in.joint_roll;
packet1.joint_el = packet_in.joint_el;
packet1.joint_az = packet_in.joint_az;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_encode(system_id, component_id, &msg, &packet1);
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(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.delta_time , 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_el , packet1.joint_az );
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.target_system , packet1.target_component , packet1.delta_time , 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_el , packet1.joint_az );
mavlink_msg_gimbal_report_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gimbal_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_report_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.delta_time , 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_el , packet1.joint_az );
mavlink_msg_gimbal_report_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_gimbal_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_gimbal_control_t packet_in = {
17.0,45.0,73.0,41,108
};
mavlink_gimbal_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.demanded_rate_x = packet_in.demanded_rate_x;
packet1.demanded_rate_y = packet_in.demanded_rate_y;
packet1.demanded_rate_z = packet_in.demanded_rate_z;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gimbal_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z );
mavlink_msg_gimbal_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z );
mavlink_msg_gimbal_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_gimbal_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gimbal_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z );
mavlink_msg_gimbal_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{ {
mavlink_test_sensor_offsets(system_id, component_id, last_msg); mavlink_test_sensor_offsets(system_id, component_id, last_msg);
@ -1847,10 +1844,10 @@ static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id,
mavlink_test_battery2(system_id, component_id, last_msg); mavlink_test_battery2(system_id, component_id, last_msg);
mavlink_test_ahrs3(system_id, component_id, last_msg); mavlink_test_ahrs3(system_id, component_id, last_msg);
mavlink_test_autopilot_version_request(system_id, component_id, last_msg); mavlink_test_autopilot_version_request(system_id, component_id, last_msg);
mavlink_test_gimbal_report(system_id, component_id, last_msg);
mavlink_test_gimbal_control(system_id, component_id, last_msg);
mavlink_test_led_control(system_id, component_id, last_msg); mavlink_test_led_control(system_id, component_id, last_msg);
mavlink_test_ekf_status_report(system_id, component_id, last_msg); mavlink_test_ekf_status_report(system_id, component_id, last_msg);
mavlink_test_gimbal_report(system_id, component_id, last_msg);
mavlink_test_gimbal_control(system_id, component_id, last_msg);
} }
#ifdef __cplusplus #ifdef __cplusplus

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Mar 11 01:59:47 2015" #define MAVLINK_BUILD_DATE "Mon Apr 6 16:29:12 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H #ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H #define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Wed Mar 11 01:59:49 2015" #define MAVLINK_BUILD_DATE "Mon Apr 6 16:29:14 2015"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@ -206,8 +206,8 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
/** /**
* This is a convenience function which handles the complete MAVLink parsing. * This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once * the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. Checksum and other failures will be silently * it could be successfully decoded. This function will return 0, 1 or
* ignored. * 2 (MAVLINK_FRAMING_INCOMPLETE, MAVLINK_FRAMING_OK or MAVLINK_FRAMING_BAD_CRC)
* *
* Messages are parsed into an internal buffer (one for each channel). When a complete * Messages are parsed into an internal buffer (one for each channel). When a complete
* message is received it is copies into *returnMsg and the channel's status is * message is received it is copies into *returnMsg and the channel's status is
@ -221,7 +221,7 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
* *
* @param returnMsg NULL if no message could be decoded, the message data else * @param returnMsg NULL if no message could be decoded, the message data else
* @param returnStats if a message was decoded, this is filled with the channel's stats * @param returnStats if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded, 1 else * @return 0 if no message could be decoded, 1 on good message and CRC, 2 on bad CRC
* *
* A typical use scenario of this function call is: * A typical use scenario of this function call is:
* *
@ -235,7 +235,7 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
* while(serial.bytesAvailable > 0) * while(serial.bytesAvailable > 0)
* { * {
* uint8_t byte = serial.getNextByte(); * uint8_t byte = serial.getNextByte();
* if (mavlink_parse_char(chan, byte, &msg)) * if (mavlink_frame_char(chan, byte, &msg) != MAVLINK_FRAMING_INCOMPLETE)
* { * {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* } * }
@ -244,7 +244,7 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
* *
* @endcode * @endcode
*/ */
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{ {
/* /*
default message crc function. You can override this per-system to default message crc function. You can override this per-system to
@ -274,7 +274,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0; int bufferIndex = 0;
status->msg_received = 0; status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
switch (status->parse_state) switch (status->parse_state)
{ {
@ -366,51 +366,31 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
#endif #endif
if (c != (rxmsg->checksum & 0xFF)) { if (c != (rxmsg->checksum & 0xFF)) {
// Check first checksum byte status->parse_state = MAVLINK_PARSE_STATE_GOT_BAD_CRC1;
status->parse_error++; } else {
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
} }
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
break; break;
case MAVLINK_PARSE_STATE_GOT_CRC1: case MAVLINK_PARSE_STATE_GOT_CRC1:
if (c != (rxmsg->checksum >> 8)) { case MAVLINK_PARSE_STATE_GOT_BAD_CRC1:
// Check second checksum byte if (status->parse_state == MAVLINK_PARSE_STATE_GOT_BAD_CRC1 || c != (rxmsg->checksum >> 8)) {
status->parse_error++; // got a bad CRC message
status->msg_received = 0; status->msg_received = MAVLINK_FRAMING_BAD_CRC;
status->parse_state = MAVLINK_PARSE_STATE_IDLE; } else {
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
// Successfully got message // Successfully got message
status->msg_received = 1; status->msg_received = MAVLINK_FRAMING_OK;
}
status->parse_state = MAVLINK_PARSE_STATE_IDLE; status->parse_state = MAVLINK_PARSE_STATE_IDLE;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
break; break;
} }
bufferIndex++; bufferIndex++;
// If a message has been sucessfully decoded, check index // If a message has been sucessfully decoded, check index
if (status->msg_received == 1) if (status->msg_received == MAVLINK_FRAMING_OK)
{ {
//while(status->current_seq != rxmsg->seq) //while(status->current_seq != rxmsg->seq)
//{ //{
@ -431,9 +411,83 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
r_mavlink_status->packet_rx_drop_count = status->parse_error; r_mavlink_status->packet_rx_drop_count = status->parse_error;
status->parse_error = 0; status->parse_error = 0;
if (status->msg_received == MAVLINK_FRAMING_BAD_CRC) {
/*
the CRC came out wrong. We now need to overwrite the
msg CRC with the one on the wire so that if the
caller decides to forward the message anyway that
mavlink_msg_to_send_buffer() won't overwrite the
checksum
*/
r_message->checksum = _MAV_PAYLOAD(rxmsg)[status->packet_idx] | (_MAV_PAYLOAD(rxmsg)[status->packet_idx+1]<<8);
}
return status->msg_received; return status->msg_received;
} }
/**
* This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. This function will return 0 or 1.
*
* Messages are parsed into an internal buffer (one for each channel). When a complete
* message is received it is copies into *returnMsg and the channel's status is
* copied into *returnStats.
*
* @param chan ID of the current channel. This allows to parse different channels with this function.
* a channel is not a physical message channel like a serial port, but a logic partition of
* the communication streams in this case. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
* @param c The char to parse
*
* @param returnMsg NULL if no message could be decoded, the message data else
* @param returnStats if a message was decoded, this is filled with the channel's stats
* @return 0 if no message could be decoded or bad CRC, 1 on good message and CRC
*
* A typical use scenario of this function call is:
*
* @code
* #include <mavlink.h>
*
* mavlink_message_t msg;
* int chan = 0;
*
*
* while(serial.bytesAvailable > 0)
* {
* uint8_t byte = serial.getNextByte();
* if (mavlink_parse_char(chan, byte, &msg))
* {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* }
* }
*
*
* @endcode
*/
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
uint8_t msg_received = mavlink_frame_char(chan, c, r_message, r_mavlink_status);
if (msg_received == MAVLINK_FRAMING_BAD_CRC) {
// we got a bad CRC. Treat as a parse failure
mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan);
mavlink_status_t* status = mavlink_get_channel_status(chan);
status->parse_error++;
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
return 0;
}
return msg_received;
}
/** /**
* @brief Put a bitfield of length 1-32 bit into the buffer * @brief Put a bitfield of length 1-32 bit into the buffer
* *

View File

@ -65,6 +65,7 @@
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_frame_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
uint8_t* r_bit_index, uint8_t* buffer); uint8_t* r_bit_index, uint8_t* buffer);