Updated MAVLink version, included omnidirectional flow message

This commit is contained in:
Lorenz Meier
2013-01-09 16:38:18 +01:00
parent 16e49c447d
commit fd75f19374
54 changed files with 8762 additions and 192 deletions

File diff suppressed because one or more lines are too long

View File

@@ -4,7 +4,7 @@
typedef struct __mavlink_wind_t
{
float direction; ///< wind direction (degrees)
float direction; ///< wind direction that wind is coming from (degrees)
float speed; ///< wind speed in ground plane (m/s)
float speed_z; ///< vertical wind speed (m/s)
} mavlink_wind_t;
@@ -30,7 +30,7 @@ typedef struct __mavlink_wind_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param direction wind direction (degrees)
* @param direction wind direction that wind is coming from (degrees)
* @param speed wind speed in ground plane (m/s)
* @param speed_z vertical wind speed (m/s)
* @return length of the message in bytes (excluding serial stream start sign)
@@ -64,7 +64,7 @@ static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t componen
* @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 direction wind direction (degrees)
* @param direction wind direction that wind is coming from (degrees)
* @param speed wind speed in ground plane (m/s)
* @param speed_z vertical wind speed (m/s)
* @return length of the message in bytes (excluding serial stream start sign)
@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t compon
* @brief Send a wind message
* @param chan MAVLink channel to send the message
*
* @param direction wind direction (degrees)
* @param direction wind direction that wind is coming from (degrees)
* @param speed wind speed in ground plane (m/s)
* @param speed_z vertical wind speed (m/s)
*/
@@ -143,7 +143,7 @@ static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction
/**
* @brief Get field direction from wind message
*
* @return wind direction (degrees)
* @return wind direction that wind is coming from (degrees)
*/
static inline float mavlink_msg_wind_get_direction(const mavlink_message_t* msg)
{

View File

@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:05:58 2012"
#define MAVLINK_BUILD_DATE "Wed Jan 9 16:17:57 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

View File

@@ -15,6 +15,7 @@ extern "C" {
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
#ifndef HAVE_CRC_ACCUMULATE
/**
* @brief Accumulate the X.25 CRC by adding one char at a time.
*
@@ -33,6 +34,7 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
}
#endif
/**
* @brief Initiliaze the buffer for the X.25 CRC

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,276 @@
// MESSAGE 6DOF_SETPOINT PACKING
#define MAVLINK_MSG_ID_6DOF_SETPOINT 149
typedef struct __mavlink_6dof_setpoint_t
{
float trans_x; ///< Translational Component in x
float trans_y; ///< Translational Component in y
float trans_z; ///< Translational Component in z
float rot_x; ///< Rotational Component in x
float rot_y; ///< Rotational Component in y
float rot_z; ///< Rotational Component in z
uint8_t target_system; ///< System ID
} mavlink_6dof_setpoint_t;
#define MAVLINK_MSG_ID_6DOF_SETPOINT_LEN 25
#define MAVLINK_MSG_ID_149_LEN 25
#define MAVLINK_MESSAGE_INFO_6DOF_SETPOINT { \
"6DOF_SETPOINT", \
7, \
{ { "trans_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_6dof_setpoint_t, trans_x) }, \
{ "trans_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_6dof_setpoint_t, trans_y) }, \
{ "trans_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_6dof_setpoint_t, trans_z) }, \
{ "rot_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_6dof_setpoint_t, rot_x) }, \
{ "rot_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_6dof_setpoint_t, rot_y) }, \
{ "rot_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_6dof_setpoint_t, rot_z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_6dof_setpoint_t, target_system) }, \
} \
}
/**
* @brief Pack a 6dof_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 target_system System ID
* @param trans_x Translational Component in x
* @param trans_y Translational Component in y
* @param trans_z Translational Component in z
* @param rot_x Rotational Component in x
* @param rot_y Rotational Component in y
* @param rot_z Rotational Component in z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_6dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
_mav_put_float(buf, 12, rot_x);
_mav_put_float(buf, 16, rot_y);
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_6dof_setpoint_t packet;
packet.trans_x = trans_x;
packet.trans_y = trans_y;
packet.trans_z = trans_z;
packet.rot_x = rot_x;
packet.rot_y = rot_y;
packet.rot_z = rot_z;
packet.target_system = target_system;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 25, 144);
}
/**
* @brief Pack a 6dof_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 target_system System ID
* @param trans_x Translational Component in x
* @param trans_y Translational Component in y
* @param trans_z Translational Component in z
* @param rot_x Rotational Component in x
* @param rot_y Rotational Component in y
* @param rot_z Rotational Component in z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_6dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
_mav_put_float(buf, 12, rot_x);
_mav_put_float(buf, 16, rot_y);
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_6dof_setpoint_t packet;
packet.trans_x = trans_x;
packet.trans_y = trans_y;
packet.trans_z = trans_z;
packet.rot_x = rot_x;
packet.rot_y = rot_y;
packet.rot_z = rot_z;
packet.target_system = target_system;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
msg->msgid = MAVLINK_MSG_ID_6DOF_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 144);
}
/**
* @brief Encode a 6dof_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 6dof_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_6dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_6dof_setpoint_t* 6dof_setpoint)
{
return mavlink_msg_6dof_setpoint_pack(system_id, component_id, msg, 6dof_setpoint->target_system, 6dof_setpoint->trans_x, 6dof_setpoint->trans_y, 6dof_setpoint->trans_z, 6dof_setpoint->rot_x, 6dof_setpoint->rot_y, 6dof_setpoint->rot_z);
}
/**
* @brief Send a 6dof_setpoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param trans_x Translational Component in x
* @param trans_y Translational Component in y
* @param trans_z Translational Component in z
* @param rot_x Rotational Component in x
* @param rot_y Rotational Component in y
* @param rot_z Rotational Component in z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_6dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, trans_x);
_mav_put_float(buf, 4, trans_y);
_mav_put_float(buf, 8, trans_z);
_mav_put_float(buf, 12, rot_x);
_mav_put_float(buf, 16, rot_y);
_mav_put_float(buf, 20, rot_z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, buf, 25, 144);
#else
mavlink_6dof_setpoint_t packet;
packet.trans_x = trans_x;
packet.trans_y = trans_y;
packet.trans_z = trans_z;
packet.rot_x = rot_x;
packet.rot_y = rot_y;
packet.rot_z = rot_z;
packet.target_system = target_system;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_6DOF_SETPOINT, (const char *)&packet, 25, 144);
#endif
}
#endif
// MESSAGE 6DOF_SETPOINT UNPACKING
/**
* @brief Get field target_system from 6dof_setpoint message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_6dof_setpoint_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
/**
* @brief Get field trans_x from 6dof_setpoint message
*
* @return Translational Component in x
*/
static inline float mavlink_msg_6dof_setpoint_get_trans_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field trans_y from 6dof_setpoint message
*
* @return Translational Component in y
*/
static inline float mavlink_msg_6dof_setpoint_get_trans_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field trans_z from 6dof_setpoint message
*
* @return Translational Component in z
*/
static inline float mavlink_msg_6dof_setpoint_get_trans_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field rot_x from 6dof_setpoint message
*
* @return Rotational Component in x
*/
static inline float mavlink_msg_6dof_setpoint_get_rot_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field rot_y from 6dof_setpoint message
*
* @return Rotational Component in y
*/
static inline float mavlink_msg_6dof_setpoint_get_rot_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field rot_z from 6dof_setpoint message
*
* @return Rotational Component in z
*/
static inline float mavlink_msg_6dof_setpoint_get_rot_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a 6dof_setpoint message into a struct
*
* @param msg The message to decode
* @param 6dof_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_6dof_setpoint_decode(const mavlink_message_t* msg, mavlink_6dof_setpoint_t* 6dof_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
6dof_setpoint->trans_x = mavlink_msg_6dof_setpoint_get_trans_x(msg);
6dof_setpoint->trans_y = mavlink_msg_6dof_setpoint_get_trans_y(msg);
6dof_setpoint->trans_z = mavlink_msg_6dof_setpoint_get_trans_z(msg);
6dof_setpoint->rot_x = mavlink_msg_6dof_setpoint_get_rot_x(msg);
6dof_setpoint->rot_y = mavlink_msg_6dof_setpoint_get_rot_y(msg);
6dof_setpoint->rot_z = mavlink_msg_6dof_setpoint_get_rot_z(msg);
6dof_setpoint->target_system = mavlink_msg_6dof_setpoint_get_target_system(msg);
#else
memcpy(6dof_setpoint, _MAV_PAYLOAD(msg), 25);
#endif
}

View File

@@ -0,0 +1,320 @@
// MESSAGE 8DOF_SETPOINT PACKING
#define MAVLINK_MSG_ID_8DOF_SETPOINT 148
typedef struct __mavlink_8dof_setpoint_t
{
float val1; ///< Value 1
float val2; ///< Value 2
float val3; ///< Value 3
float val4; ///< Value 4
float val5; ///< Value 5
float val6; ///< Value 6
float val7; ///< Value 7
float val8; ///< Value 8
uint8_t target_system; ///< System ID
} mavlink_8dof_setpoint_t;
#define MAVLINK_MSG_ID_8DOF_SETPOINT_LEN 33
#define MAVLINK_MSG_ID_148_LEN 33
#define MAVLINK_MESSAGE_INFO_8DOF_SETPOINT { \
"8DOF_SETPOINT", \
9, \
{ { "val1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_8dof_setpoint_t, val1) }, \
{ "val2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_8dof_setpoint_t, val2) }, \
{ "val3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_8dof_setpoint_t, val3) }, \
{ "val4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_8dof_setpoint_t, val4) }, \
{ "val5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_8dof_setpoint_t, val5) }, \
{ "val6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_8dof_setpoint_t, val6) }, \
{ "val7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_8dof_setpoint_t, val7) }, \
{ "val8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_8dof_setpoint_t, val8) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_8dof_setpoint_t, target_system) }, \
} \
}
/**
* @brief Pack a 8dof_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 target_system System ID
* @param val1 Value 1
* @param val2 Value 2
* @param val3 Value 3
* @param val4 Value 4
* @param val5 Value 5
* @param val6 Value 6
* @param val7 Value 7
* @param val8 Value 8
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_8dof_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, val1);
_mav_put_float(buf, 4, val2);
_mav_put_float(buf, 8, val3);
_mav_put_float(buf, 12, val4);
_mav_put_float(buf, 16, val5);
_mav_put_float(buf, 20, val6);
_mav_put_float(buf, 24, val7);
_mav_put_float(buf, 28, val8);
_mav_put_uint8_t(buf, 32, target_system);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_8dof_setpoint_t packet;
packet.val1 = val1;
packet.val2 = val2;
packet.val3 = val3;
packet.val4 = val4;
packet.val5 = val5;
packet.val6 = val6;
packet.val7 = val7;
packet.val8 = val8;
packet.target_system = target_system;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 33, 42);
}
/**
* @brief Pack a 8dof_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 target_system System ID
* @param val1 Value 1
* @param val2 Value 2
* @param val3 Value 3
* @param val4 Value 4
* @param val5 Value 5
* @param val6 Value 6
* @param val7 Value 7
* @param val8 Value 8
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_8dof_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, val1);
_mav_put_float(buf, 4, val2);
_mav_put_float(buf, 8, val3);
_mav_put_float(buf, 12, val4);
_mav_put_float(buf, 16, val5);
_mav_put_float(buf, 20, val6);
_mav_put_float(buf, 24, val7);
_mav_put_float(buf, 28, val8);
_mav_put_uint8_t(buf, 32, target_system);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_8dof_setpoint_t packet;
packet.val1 = val1;
packet.val2 = val2;
packet.val3 = val3;
packet.val4 = val4;
packet.val5 = val5;
packet.val6 = val6;
packet.val7 = val7;
packet.val8 = val8;
packet.target_system = target_system;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
msg->msgid = MAVLINK_MSG_ID_8DOF_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 42);
}
/**
* @brief Encode a 8dof_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 8dof_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_8dof_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_8dof_setpoint_t* 8dof_setpoint)
{
return mavlink_msg_8dof_setpoint_pack(system_id, component_id, msg, 8dof_setpoint->target_system, 8dof_setpoint->val1, 8dof_setpoint->val2, 8dof_setpoint->val3, 8dof_setpoint->val4, 8dof_setpoint->val5, 8dof_setpoint->val6, 8dof_setpoint->val7, 8dof_setpoint->val8);
}
/**
* @brief Send a 8dof_setpoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param val1 Value 1
* @param val2 Value 2
* @param val3 Value 3
* @param val4 Value 4
* @param val5 Value 5
* @param val6 Value 6
* @param val7 Value 7
* @param val8 Value 8
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_8dof_setpoint_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, val1);
_mav_put_float(buf, 4, val2);
_mav_put_float(buf, 8, val3);
_mav_put_float(buf, 12, val4);
_mav_put_float(buf, 16, val5);
_mav_put_float(buf, 20, val6);
_mav_put_float(buf, 24, val7);
_mav_put_float(buf, 28, val8);
_mav_put_uint8_t(buf, 32, target_system);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, buf, 33, 42);
#else
mavlink_8dof_setpoint_t packet;
packet.val1 = val1;
packet.val2 = val2;
packet.val3 = val3;
packet.val4 = val4;
packet.val5 = val5;
packet.val6 = val6;
packet.val7 = val7;
packet.val8 = val8;
packet.target_system = target_system;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_8DOF_SETPOINT, (const char *)&packet, 33, 42);
#endif
}
#endif
// MESSAGE 8DOF_SETPOINT UNPACKING
/**
* @brief Get field target_system from 8dof_setpoint message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_8dof_setpoint_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field val1 from 8dof_setpoint message
*
* @return Value 1
*/
static inline float mavlink_msg_8dof_setpoint_get_val1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field val2 from 8dof_setpoint message
*
* @return Value 2
*/
static inline float mavlink_msg_8dof_setpoint_get_val2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field val3 from 8dof_setpoint message
*
* @return Value 3
*/
static inline float mavlink_msg_8dof_setpoint_get_val3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field val4 from 8dof_setpoint message
*
* @return Value 4
*/
static inline float mavlink_msg_8dof_setpoint_get_val4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field val5 from 8dof_setpoint message
*
* @return Value 5
*/
static inline float mavlink_msg_8dof_setpoint_get_val5(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field val6 from 8dof_setpoint message
*
* @return Value 6
*/
static inline float mavlink_msg_8dof_setpoint_get_val6(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field val7 from 8dof_setpoint message
*
* @return Value 7
*/
static inline float mavlink_msg_8dof_setpoint_get_val7(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field val8 from 8dof_setpoint message
*
* @return Value 8
*/
static inline float mavlink_msg_8dof_setpoint_get_val8(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a 8dof_setpoint message into a struct
*
* @param msg The message to decode
* @param 8dof_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_8dof_setpoint_decode(const mavlink_message_t* msg, mavlink_8dof_setpoint_t* 8dof_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
8dof_setpoint->val1 = mavlink_msg_8dof_setpoint_get_val1(msg);
8dof_setpoint->val2 = mavlink_msg_8dof_setpoint_get_val2(msg);
8dof_setpoint->val3 = mavlink_msg_8dof_setpoint_get_val3(msg);
8dof_setpoint->val4 = mavlink_msg_8dof_setpoint_get_val4(msg);
8dof_setpoint->val5 = mavlink_msg_8dof_setpoint_get_val5(msg);
8dof_setpoint->val6 = mavlink_msg_8dof_setpoint_get_val6(msg);
8dof_setpoint->val7 = mavlink_msg_8dof_setpoint_get_val7(msg);
8dof_setpoint->val8 = mavlink_msg_8dof_setpoint_get_val8(msg);
8dof_setpoint->target_system = mavlink_msg_8dof_setpoint_get_target_system(msg);
#else
memcpy(8dof_setpoint, _MAV_PAYLOAD(msg), 33);
#endif
}

View File

@@ -0,0 +1,249 @@
// MESSAGE OMNIDIRECTIONAL_FLOW PACKING
#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106
typedef struct __mavlink_omnidirectional_flow_t
{
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
float front_distance_m; ///< Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance
int16_t left[10]; ///< Flow in deci pixels (1 = 0.1 pixel) on left hemisphere
int16_t right[10]; ///< Flow in deci pixels (1 = 0.1 pixel) on right hemisphere
uint8_t sensor_id; ///< Sensor ID
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
} mavlink_omnidirectional_flow_t;
#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54
#define MAVLINK_MSG_ID_106_LEN 54
#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_LEFT_LEN 10
#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_RIGHT_LEN 10
#define MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW { \
"OMNIDIRECTIONAL_FLOW", \
6, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_omnidirectional_flow_t, time_usec) }, \
{ "front_distance_m", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_omnidirectional_flow_t, front_distance_m) }, \
{ "left", NULL, MAVLINK_TYPE_INT16_T, 10, 12, offsetof(mavlink_omnidirectional_flow_t, left) }, \
{ "right", NULL, MAVLINK_TYPE_INT16_T, 10, 32, offsetof(mavlink_omnidirectional_flow_t, right) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_omnidirectional_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_omnidirectional_flow_t, quality) }, \
} \
}
/**
* @brief Pack a omnidirectional_flow message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere
* @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
packet.front_distance_m = front_distance_m;
packet.sensor_id = sensor_id;
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
#endif
msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
return mavlink_finalize_message(msg, system_id, component_id, 54, 211);
}
/**
* @brief Pack a omnidirectional_flow 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 time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere
* @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t sensor_id,const int16_t *left,const int16_t *right,uint8_t quality,float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
packet.front_distance_m = front_distance_m;
packet.sensor_id = sensor_id;
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
#endif
msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 211);
}
/**
* @brief Encode a omnidirectional_flow 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 omnidirectional_flow C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_omnidirectional_flow_t* omnidirectional_flow)
{
return mavlink_msg_omnidirectional_flow_pack(system_id, component_id, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m);
}
/**
* @brief Send a omnidirectional_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere
* @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, front_distance_m);
_mav_put_uint8_t(buf, 52, sensor_id);
_mav_put_uint8_t(buf, 53, quality);
_mav_put_int16_t_array(buf, 12, left, 10);
_mav_put_int16_t_array(buf, 32, right, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, 54, 211);
#else
mavlink_omnidirectional_flow_t packet;
packet.time_usec = time_usec;
packet.front_distance_m = front_distance_m;
packet.sensor_id = sensor_id;
packet.quality = quality;
mav_array_memcpy(packet.left, left, sizeof(int16_t)*10);
mav_array_memcpy(packet.right, right, sizeof(int16_t)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, 54, 211);
#endif
}
#endif
// MESSAGE OMNIDIRECTIONAL_FLOW UNPACKING
/**
* @brief Get field time_usec from omnidirectional_flow message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_omnidirectional_flow_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field sensor_id from omnidirectional_flow message
*
* @return Sensor ID
*/
static inline uint8_t mavlink_msg_omnidirectional_flow_get_sensor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 52);
}
/**
* @brief Get field left from omnidirectional_flow message
*
* @return Flow in deci pixels (1 = 0.1 pixel) on left hemisphere
*/
static inline uint16_t mavlink_msg_omnidirectional_flow_get_left(const mavlink_message_t* msg, int16_t *left)
{
return _MAV_RETURN_int16_t_array(msg, left, 10, 12);
}
/**
* @brief Get field right from omnidirectional_flow message
*
* @return Flow in deci pixels (1 = 0.1 pixel) on right hemisphere
*/
static inline uint16_t mavlink_msg_omnidirectional_flow_get_right(const mavlink_message_t* msg, int16_t *right)
{
return _MAV_RETURN_int16_t_array(msg, right, 10, 32);
}
/**
* @brief Get field quality from omnidirectional_flow message
*
* @return Optical flow quality / confidence. 0: bad, 255: maximum quality
*/
static inline uint8_t mavlink_msg_omnidirectional_flow_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 53);
}
/**
* @brief Get field front_distance_m from omnidirectional_flow message
*
* @return Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance
*/
static inline float mavlink_msg_omnidirectional_flow_get_front_distance_m(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Decode a omnidirectional_flow message into a struct
*
* @param msg The message to decode
* @param omnidirectional_flow C-struct to decode the message contents into
*/
static inline void mavlink_msg_omnidirectional_flow_decode(const mavlink_message_t* msg, mavlink_omnidirectional_flow_t* omnidirectional_flow)
{
#if MAVLINK_NEED_BYTE_SWAP
omnidirectional_flow->time_usec = mavlink_msg_omnidirectional_flow_get_time_usec(msg);
omnidirectional_flow->front_distance_m = mavlink_msg_omnidirectional_flow_get_front_distance_m(msg);
mavlink_msg_omnidirectional_flow_get_left(msg, omnidirectional_flow->left);
mavlink_msg_omnidirectional_flow_get_right(msg, omnidirectional_flow->right);
omnidirectional_flow->sensor_id = mavlink_msg_omnidirectional_flow_get_sensor_id(msg);
omnidirectional_flow->quality = mavlink_msg_omnidirectional_flow_get_quality(msg);
#else
memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), 54);
#endif
}

View File

@@ -4,7 +4,7 @@
typedef struct __mavlink_servo_output_raw_t
{
uint32_t time_boot_ms; ///< Timestamp (microseconds since system boot)
uint32_t time_usec; ///< Timestamp (microseconds since system boot)
uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
@@ -24,7 +24,7 @@ typedef struct __mavlink_servo_output_raw_t
#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \
"SERVO_OUTPUT_RAW", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_boot_ms) }, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \
{ "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \
{ "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \
{ "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \
@@ -44,7 +44,7 @@ typedef struct __mavlink_servo_output_raw_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@@ -57,11 +57,11 @@ typedef struct __mavlink_servo_output_raw_t
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
@@ -75,7 +75,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_servo_output_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
@@ -90,7 +90,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
#endif
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 21, 242);
return mavlink_finalize_message(msg, system_id, component_id, 21, 222);
}
/**
@@ -99,7 +99,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
* @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 time_boot_ms Timestamp (microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@@ -113,11 +113,11 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw)
uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
@@ -131,7 +131,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id,
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_servo_output_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
@@ -146,7 +146,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id,
#endif
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 242);
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 222);
}
/**
@@ -159,14 +159,14 @@ static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id,
*/
static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
{
return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_boot_ms, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
}
/**
* @brief Send a servo_output_raw message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (microseconds since system boot)
* @param time_usec Timestamp (microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
@@ -179,11 +179,11 @@ static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, ui
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
@@ -194,10 +194,10 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin
_mav_put_uint16_t(buf, 18, servo8_raw);
_mav_put_uint8_t(buf, 20, port);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 242);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 222);
#else
mavlink_servo_output_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
@@ -208,7 +208,7 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin
packet.servo8_raw = servo8_raw;
packet.port = port;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 242);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 222);
#endif
}
@@ -218,11 +218,11 @@ static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uin
/**
* @brief Get field time_boot_ms from servo_output_raw message
* @brief Get field time_usec from servo_output_raw message
*
* @return Timestamp (microseconds since system boot)
*/
static inline uint32_t mavlink_msg_servo_output_raw_get_time_boot_ms(const mavlink_message_t* msg)
static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
@@ -326,7 +326,7 @@ static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink
static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
servo_output_raw->time_boot_ms = mavlink_msg_servo_output_raw_get_time_boot_ms(msg);
servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg);
servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);

View File

@@ -1327,7 +1327,7 @@ static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_i
};
mavlink_servo_output_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.time_usec = packet_in.time_usec;
packet1.servo1_raw = packet_in.servo1_raw;
packet1.servo2_raw = packet_in.servo2_raw;
packet1.servo3_raw = packet_in.servo3_raw;
@@ -1346,12 +1346,12 @@ static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_i
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
@@ -1364,7 +1364,7 @@ static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_i
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
@@ -3886,6 +3886,59 @@ static void mavlink_test_highres_imu(uint8_t system_id, uint8_t component_id, ma
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_omnidirectional_flow(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_omnidirectional_flow_t packet_in = {
93372036854775807ULL,
73.0,
{ 17859, 17860, 17861, 17862, 17863, 17864, 17865, 17866, 17867, 17868 },
{ 18899, 18900, 18901, 18902, 18903, 18904, 18905, 18906, 18907, 18908 },
161,
228,
};
mavlink_omnidirectional_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.front_distance_m = packet_in.front_distance_m;
packet1.sensor_id = packet_in.sensor_id;
packet1.quality = packet_in.quality;
mav_array_memcpy(packet1.left, packet_in.left, sizeof(int16_t)*10);
mav_array_memcpy(packet1.right, packet_in.right, sizeof(int16_t)*10);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_omnidirectional_flow_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_omnidirectional_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_omnidirectional_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
mavlink_msg_omnidirectional_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
mavlink_msg_omnidirectional_flow_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_omnidirectional_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_omnidirectional_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.left , packet1.right , packet1.quality , packet1.front_distance_m );
mavlink_msg_omnidirectional_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
static void mavlink_test_file_transfer_start(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
@@ -4562,6 +4615,7 @@ static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_highres_imu(system_id, component_id, last_msg);
mavlink_test_omnidirectional_flow(system_id, component_id, last_msg);
mavlink_test_file_transfer_start(system_id, component_id, last_msg);
mavlink_test_file_transfer_dir_list(system_id, component_id, last_msg);
mavlink_test_file_transfer_res(system_id, component_id, last_msg);

View File

@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_BUILD_DATE "Wed Jan 9 16:19:41 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,276 @@
// MESSAGE AIRSPEEDS PACKING
#define MAVLINK_MSG_ID_AIRSPEEDS 182
typedef struct __mavlink_airspeeds_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int16_t airspeed_imu; ///< Airspeed estimate from IMU, cm/s
int16_t airspeed_pitot; ///< Pitot measured forward airpseed, cm/s
int16_t airspeed_hot_wire; ///< Hot wire anenometer measured airspeed, cm/s
int16_t airspeed_ultrasonic; ///< Ultrasonic measured airspeed, cm/s
int16_t aoa; ///< Angle of attack sensor, degrees * 10
int16_t aoy; ///< Yaw angle sensor, degrees * 10
} mavlink_airspeeds_t;
#define MAVLINK_MSG_ID_AIRSPEEDS_LEN 16
#define MAVLINK_MSG_ID_182_LEN 16
#define MAVLINK_MESSAGE_INFO_AIRSPEEDS { \
"AIRSPEEDS", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_airspeeds_t, time_boot_ms) }, \
{ "airspeed_imu", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_airspeeds_t, airspeed_imu) }, \
{ "airspeed_pitot", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_airspeeds_t, airspeed_pitot) }, \
{ "airspeed_hot_wire", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_airspeeds_t, airspeed_hot_wire) }, \
{ "airspeed_ultrasonic", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_airspeeds_t, airspeed_ultrasonic) }, \
{ "aoa", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_airspeeds_t, aoa) }, \
{ "aoy", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_airspeeds_t, aoy) }, \
} \
}
/**
* @brief Pack a airspeeds message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param airspeed_imu Airspeed estimate from IMU, cm/s
* @param airspeed_pitot Pitot measured forward airpseed, cm/s
* @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s
* @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s
* @param aoa Angle of attack sensor, degrees * 10
* @param aoy Yaw angle sensor, degrees * 10
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeeds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, airspeed_imu);
_mav_put_int16_t(buf, 6, airspeed_pitot);
_mav_put_int16_t(buf, 8, airspeed_hot_wire);
_mav_put_int16_t(buf, 10, airspeed_ultrasonic);
_mav_put_int16_t(buf, 12, aoa);
_mav_put_int16_t(buf, 14, aoy);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_airspeeds_t packet;
packet.time_boot_ms = time_boot_ms;
packet.airspeed_imu = airspeed_imu;
packet.airspeed_pitot = airspeed_pitot;
packet.airspeed_hot_wire = airspeed_hot_wire;
packet.airspeed_ultrasonic = airspeed_ultrasonic;
packet.aoa = aoa;
packet.aoy = aoy;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
msg->msgid = MAVLINK_MSG_ID_AIRSPEEDS;
return mavlink_finalize_message(msg, system_id, component_id, 16, 154);
}
/**
* @brief Pack a airspeeds 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 time_boot_ms Timestamp (milliseconds since system boot)
* @param airspeed_imu Airspeed estimate from IMU, cm/s
* @param airspeed_pitot Pitot measured forward airpseed, cm/s
* @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s
* @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s
* @param aoa Angle of attack sensor, degrees * 10
* @param aoy Yaw angle sensor, degrees * 10
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,int16_t airspeed_imu,int16_t airspeed_pitot,int16_t airspeed_hot_wire,int16_t airspeed_ultrasonic,int16_t aoa,int16_t aoy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, airspeed_imu);
_mav_put_int16_t(buf, 6, airspeed_pitot);
_mav_put_int16_t(buf, 8, airspeed_hot_wire);
_mav_put_int16_t(buf, 10, airspeed_ultrasonic);
_mav_put_int16_t(buf, 12, aoa);
_mav_put_int16_t(buf, 14, aoy);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_airspeeds_t packet;
packet.time_boot_ms = time_boot_ms;
packet.airspeed_imu = airspeed_imu;
packet.airspeed_pitot = airspeed_pitot;
packet.airspeed_hot_wire = airspeed_hot_wire;
packet.airspeed_ultrasonic = airspeed_ultrasonic;
packet.aoa = aoa;
packet.aoy = aoy;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
msg->msgid = MAVLINK_MSG_ID_AIRSPEEDS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 154);
}
/**
* @brief Encode a airspeeds 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 airspeeds C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_airspeeds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeeds_t* airspeeds)
{
return mavlink_msg_airspeeds_pack(system_id, component_id, msg, airspeeds->time_boot_ms, airspeeds->airspeed_imu, airspeeds->airspeed_pitot, airspeeds->airspeed_hot_wire, airspeeds->airspeed_ultrasonic, airspeeds->aoa, airspeeds->aoy);
}
/**
* @brief Send a airspeeds message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param airspeed_imu Airspeed estimate from IMU, cm/s
* @param airspeed_pitot Pitot measured forward airpseed, cm/s
* @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s
* @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s
* @param aoa Angle of attack sensor, degrees * 10
* @param aoy Yaw angle sensor, degrees * 10
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, airspeed_imu);
_mav_put_int16_t(buf, 6, airspeed_pitot);
_mav_put_int16_t(buf, 8, airspeed_hot_wire);
_mav_put_int16_t(buf, 10, airspeed_ultrasonic);
_mav_put_int16_t(buf, 12, aoa);
_mav_put_int16_t(buf, 14, aoy);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, 16, 154);
#else
mavlink_airspeeds_t packet;
packet.time_boot_ms = time_boot_ms;
packet.airspeed_imu = airspeed_imu;
packet.airspeed_pitot = airspeed_pitot;
packet.airspeed_hot_wire = airspeed_hot_wire;
packet.airspeed_ultrasonic = airspeed_ultrasonic;
packet.aoa = aoa;
packet.aoy = aoy;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, 16, 154);
#endif
}
#endif
// MESSAGE AIRSPEEDS UNPACKING
/**
* @brief Get field time_boot_ms from airspeeds message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_airspeeds_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field airspeed_imu from airspeeds message
*
* @return Airspeed estimate from IMU, cm/s
*/
static inline int16_t mavlink_msg_airspeeds_get_airspeed_imu(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Get field airspeed_pitot from airspeeds message
*
* @return Pitot measured forward airpseed, cm/s
*/
static inline int16_t mavlink_msg_airspeeds_get_airspeed_pitot(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
/**
* @brief Get field airspeed_hot_wire from airspeeds message
*
* @return Hot wire anenometer measured airspeed, cm/s
*/
static inline int16_t mavlink_msg_airspeeds_get_airspeed_hot_wire(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field airspeed_ultrasonic from airspeeds message
*
* @return Ultrasonic measured airspeed, cm/s
*/
static inline int16_t mavlink_msg_airspeeds_get_airspeed_ultrasonic(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
/**
* @brief Get field aoa from airspeeds message
*
* @return Angle of attack sensor, degrees * 10
*/
static inline int16_t mavlink_msg_airspeeds_get_aoa(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
/**
* @brief Get field aoy from airspeeds message
*
* @return Yaw angle sensor, degrees * 10
*/
static inline int16_t mavlink_msg_airspeeds_get_aoy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
/**
* @brief Decode a airspeeds message into a struct
*
* @param msg The message to decode
* @param airspeeds C-struct to decode the message contents into
*/
static inline void mavlink_msg_airspeeds_decode(const mavlink_message_t* msg, mavlink_airspeeds_t* airspeeds)
{
#if MAVLINK_NEED_BYTE_SWAP
airspeeds->time_boot_ms = mavlink_msg_airspeeds_get_time_boot_ms(msg);
airspeeds->airspeed_imu = mavlink_msg_airspeeds_get_airspeed_imu(msg);
airspeeds->airspeed_pitot = mavlink_msg_airspeeds_get_airspeed_pitot(msg);
airspeeds->airspeed_hot_wire = mavlink_msg_airspeeds_get_airspeed_hot_wire(msg);
airspeeds->airspeed_ultrasonic = mavlink_msg_airspeeds_get_airspeed_ultrasonic(msg);
airspeeds->aoa = mavlink_msg_airspeeds_get_aoa(msg);
airspeeds->aoy = mavlink_msg_airspeeds_get_aoy(msg);
#else
memcpy(airspeeds, _MAV_PAYLOAD(msg), 16);
#endif
}

View File

@@ -0,0 +1,276 @@
// MESSAGE ALTITUDES PACKING
#define MAVLINK_MSG_ID_ALTITUDES 181
typedef struct __mavlink_altitudes_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t alt_gps; ///< GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
int32_t alt_imu; ///< IMU altitude above ground in meters, expressed as * 1000 (millimeters)
int32_t alt_barometric; ///< barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
int32_t alt_optical_flow; ///< Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
int32_t alt_range_finder; ///< Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
int32_t alt_extra; ///< Extra altitude above ground in meters, expressed as * 1000 (millimeters)
} mavlink_altitudes_t;
#define MAVLINK_MSG_ID_ALTITUDES_LEN 28
#define MAVLINK_MSG_ID_181_LEN 28
#define MAVLINK_MESSAGE_INFO_ALTITUDES { \
"ALTITUDES", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_altitudes_t, time_boot_ms) }, \
{ "alt_gps", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_altitudes_t, alt_gps) }, \
{ "alt_imu", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_altitudes_t, alt_imu) }, \
{ "alt_barometric", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_altitudes_t, alt_barometric) }, \
{ "alt_optical_flow", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_altitudes_t, alt_optical_flow) }, \
{ "alt_range_finder", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_altitudes_t, alt_range_finder) }, \
{ "alt_extra", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_altitudes_t, alt_extra) }, \
} \
}
/**
* @brief Pack a altitudes message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, alt_gps);
_mav_put_int32_t(buf, 8, alt_imu);
_mav_put_int32_t(buf, 12, alt_barometric);
_mav_put_int32_t(buf, 16, alt_optical_flow);
_mav_put_int32_t(buf, 20, alt_range_finder);
_mav_put_int32_t(buf, 24, alt_extra);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_altitudes_t packet;
packet.time_boot_ms = time_boot_ms;
packet.alt_gps = alt_gps;
packet.alt_imu = alt_imu;
packet.alt_barometric = alt_barometric;
packet.alt_optical_flow = alt_optical_flow;
packet.alt_range_finder = alt_range_finder;
packet.alt_extra = alt_extra;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
return mavlink_finalize_message(msg, system_id, component_id, 28, 55);
}
/**
* @brief Pack a altitudes 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 time_boot_ms Timestamp (milliseconds since system boot)
* @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,int32_t alt_gps,int32_t alt_imu,int32_t alt_barometric,int32_t alt_optical_flow,int32_t alt_range_finder,int32_t alt_extra)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, alt_gps);
_mav_put_int32_t(buf, 8, alt_imu);
_mav_put_int32_t(buf, 12, alt_barometric);
_mav_put_int32_t(buf, 16, alt_optical_flow);
_mav_put_int32_t(buf, 20, alt_range_finder);
_mav_put_int32_t(buf, 24, alt_extra);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_altitudes_t packet;
packet.time_boot_ms = time_boot_ms;
packet.alt_gps = alt_gps;
packet.alt_imu = alt_imu;
packet.alt_barometric = alt_barometric;
packet.alt_optical_flow = alt_optical_flow;
packet.alt_range_finder = alt_range_finder;
packet.alt_extra = alt_extra;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_ALTITUDES;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 55);
}
/**
* @brief Encode a altitudes 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 altitudes C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes)
{
return mavlink_msg_altitudes_pack(system_id, component_id, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra);
}
/**
* @brief Send a altitudes message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, alt_gps);
_mav_put_int32_t(buf, 8, alt_imu);
_mav_put_int32_t(buf, 12, alt_barometric);
_mav_put_int32_t(buf, 16, alt_optical_flow);
_mav_put_int32_t(buf, 20, alt_range_finder);
_mav_put_int32_t(buf, 24, alt_extra);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, 28, 55);
#else
mavlink_altitudes_t packet;
packet.time_boot_ms = time_boot_ms;
packet.alt_gps = alt_gps;
packet.alt_imu = alt_imu;
packet.alt_barometric = alt_barometric;
packet.alt_optical_flow = alt_optical_flow;
packet.alt_range_finder = alt_range_finder;
packet.alt_extra = alt_extra;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, 28, 55);
#endif
}
#endif
// MESSAGE ALTITUDES UNPACKING
/**
* @brief Get field time_boot_ms from altitudes message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_altitudes_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field alt_gps from altitudes message
*
* @return GPS altitude in meters, expressed as * 1000 (millimeters), above MSL
*/
static inline int32_t mavlink_msg_altitudes_get_alt_gps(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field alt_imu from altitudes message
*
* @return IMU altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_altitudes_get_alt_imu(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field alt_barometric from altitudes message
*
* @return barometeric altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_altitudes_get_alt_barometric(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field alt_optical_flow from altitudes message
*
* @return Optical flow altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_altitudes_get_alt_optical_flow(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field alt_range_finder from altitudes message
*
* @return Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_altitudes_get_alt_range_finder(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field alt_extra from altitudes message
*
* @return Extra altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_altitudes_get_alt_extra(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Decode a altitudes message into a struct
*
* @param msg The message to decode
* @param altitudes C-struct to decode the message contents into
*/
static inline void mavlink_msg_altitudes_decode(const mavlink_message_t* msg, mavlink_altitudes_t* altitudes)
{
#if MAVLINK_NEED_BYTE_SWAP
altitudes->time_boot_ms = mavlink_msg_altitudes_get_time_boot_ms(msg);
altitudes->alt_gps = mavlink_msg_altitudes_get_alt_gps(msg);
altitudes->alt_imu = mavlink_msg_altitudes_get_alt_imu(msg);
altitudes->alt_barometric = mavlink_msg_altitudes_get_alt_barometric(msg);
altitudes->alt_optical_flow = mavlink_msg_altitudes_get_alt_optical_flow(msg);
altitudes->alt_range_finder = mavlink_msg_altitudes_get_alt_range_finder(msg);
altitudes->alt_extra = mavlink_msg_altitudes_get_alt_extra(msg);
#else
memcpy(altitudes, _MAV_PAYLOAD(msg), 28);
#endif
}

View File

@@ -0,0 +1,270 @@
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION 152
typedef struct __mavlink_flexifunction_buffer_function_t
{
uint16_t func_index; ///< Function index
uint16_t func_count; ///< Total count of functions
uint16_t data_address; ///< Address in the flexifunction data, Set to 0xFFFF to use address in target memory
uint16_t data_size; ///< Size of the
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int8_t data[48]; ///< Settings data
} mavlink_flexifunction_buffer_function_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN 58
#define MAVLINK_MSG_ID_152_LEN 58
#define MAVLINK_MSG_FLEXIFUNCTION_BUFFER_FUNCTION_FIELD_DATA_LEN 48
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION { \
"FLEXIFUNCTION_BUFFER_FUNCTION", \
7, \
{ { "func_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_buffer_function_t, func_index) }, \
{ "func_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_buffer_function_t, func_count) }, \
{ "data_address", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_flexifunction_buffer_function_t, data_address) }, \
{ "data_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_flexifunction_buffer_function_t, data_size) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_flexifunction_buffer_function_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_flexifunction_buffer_function_t, target_component) }, \
{ "data", NULL, MAVLINK_TYPE_INT8_T, 48, 10, offsetof(mavlink_flexifunction_buffer_function_t, data) }, \
} \
}
/**
* @brief Pack a flexifunction_buffer_function 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 func_index Function index
* @param func_count Total count of functions
* @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory
* @param data_size Size of the
* @param data Settings data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[58];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, func_count);
_mav_put_uint16_t(buf, 4, data_address);
_mav_put_uint16_t(buf, 6, data_size);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_int8_t_array(buf, 10, data, 48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 58);
#else
mavlink_flexifunction_buffer_function_t packet;
packet.func_index = func_index;
packet.func_count = func_count;
packet.data_address = data_address;
packet.data_size = data_size;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(int8_t)*48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 58);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION;
return mavlink_finalize_message(msg, system_id, component_id, 58, 101);
}
/**
* @brief Pack a flexifunction_buffer_function 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 func_index Function index
* @param func_count Total count of functions
* @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory
* @param data_size Size of the
* @param data Settings data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_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 func_index,uint16_t func_count,uint16_t data_address,uint16_t data_size,const int8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[58];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, func_count);
_mav_put_uint16_t(buf, 4, data_address);
_mav_put_uint16_t(buf, 6, data_size);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_int8_t_array(buf, 10, data, 48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 58);
#else
mavlink_flexifunction_buffer_function_t packet;
packet.func_index = func_index;
packet.func_count = func_count;
packet.data_address = data_address;
packet.data_size = data_size;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(int8_t)*48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 58);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 58, 101);
}
/**
* @brief Encode a flexifunction_buffer_function 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 flexifunction_buffer_function C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function)
{
return mavlink_msg_flexifunction_buffer_function_pack(system_id, component_id, msg, flexifunction_buffer_function->target_system, flexifunction_buffer_function->target_component, flexifunction_buffer_function->func_index, flexifunction_buffer_function->func_count, flexifunction_buffer_function->data_address, flexifunction_buffer_function->data_size, flexifunction_buffer_function->data);
}
/**
* @brief Send a flexifunction_buffer_function message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param func_index Function index
* @param func_count Total count of functions
* @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory
* @param data_size Size of the
* @param data Settings data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[58];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, func_count);
_mav_put_uint16_t(buf, 4, data_address);
_mav_put_uint16_t(buf, 6, data_size);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_int8_t_array(buf, 10, data, 48);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, 58, 101);
#else
mavlink_flexifunction_buffer_function_t packet;
packet.func_index = func_index;
packet.func_count = func_count;
packet.data_address = data_address;
packet.data_size = data_size;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.data, data, sizeof(int8_t)*48);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, 58, 101);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION UNPACKING
/**
* @brief Get field target_system from flexifunction_buffer_function message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_buffer_function_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field target_component from flexifunction_buffer_function message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_buffer_function_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field func_index from flexifunction_buffer_function message
*
* @return Function index
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_func_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field func_count from flexifunction_buffer_function message
*
* @return Total count of functions
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_func_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field data_address from flexifunction_buffer_function message
*
* @return Address in the flexifunction data, Set to 0xFFFF to use address in target memory
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data_address(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field data_size from flexifunction_buffer_function message
*
* @return Size of the
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field data from flexifunction_buffer_function message
*
* @return Settings data
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data(const mavlink_message_t* msg, int8_t *data)
{
return _MAV_RETURN_int8_t_array(msg, data, 48, 10);
}
/**
* @brief Decode a flexifunction_buffer_function message into a struct
*
* @param msg The message to decode
* @param flexifunction_buffer_function C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_buffer_function_decode(const mavlink_message_t* msg, mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_buffer_function->func_index = mavlink_msg_flexifunction_buffer_function_get_func_index(msg);
flexifunction_buffer_function->func_count = mavlink_msg_flexifunction_buffer_function_get_func_count(msg);
flexifunction_buffer_function->data_address = mavlink_msg_flexifunction_buffer_function_get_data_address(msg);
flexifunction_buffer_function->data_size = mavlink_msg_flexifunction_buffer_function_get_data_size(msg);
flexifunction_buffer_function->target_system = mavlink_msg_flexifunction_buffer_function_get_target_system(msg);
flexifunction_buffer_function->target_component = mavlink_msg_flexifunction_buffer_function_get_target_component(msg);
mavlink_msg_flexifunction_buffer_function_get_data(msg, flexifunction_buffer_function->data);
#else
memcpy(flexifunction_buffer_function, _MAV_PAYLOAD(msg), 58);
#endif
}

View File

@@ -0,0 +1,210 @@
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION_ACK PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK 153
typedef struct __mavlink_flexifunction_buffer_function_ack_t
{
uint16_t func_index; ///< Function index
uint16_t result; ///< result of acknowledge, 0=fail, 1=good
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_flexifunction_buffer_function_ack_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN 6
#define MAVLINK_MSG_ID_153_LEN 6
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION_ACK { \
"FLEXIFUNCTION_BUFFER_FUNCTION_ACK", \
4, \
{ { "func_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_buffer_function_ack_t, func_index) }, \
{ "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_buffer_function_ack_t, result) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_buffer_function_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_buffer_function_ack_t, target_component) }, \
} \
}
/**
* @brief Pack a flexifunction_buffer_function_ack 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 func_index Function index
* @param result result of acknowledge, 0=fail, 1=good
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, result);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_flexifunction_buffer_function_ack_t packet;
packet.func_index = func_index;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 6, 109);
}
/**
* @brief Pack a flexifunction_buffer_function_ack 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 func_index Function index
* @param result result of acknowledge, 0=fail, 1=good
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_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 func_index,uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, result);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_flexifunction_buffer_function_ack_t packet;
packet.func_index = func_index;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 109);
}
/**
* @brief Encode a flexifunction_buffer_function_ack 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 flexifunction_buffer_function_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack)
{
return mavlink_msg_flexifunction_buffer_function_ack_pack(system_id, component_id, msg, flexifunction_buffer_function_ack->target_system, flexifunction_buffer_function_ack->target_component, flexifunction_buffer_function_ack->func_index, flexifunction_buffer_function_ack->result);
}
/**
* @brief Send a flexifunction_buffer_function_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param func_index Function index
* @param result result of acknowledge, 0=fail, 1=good
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_buffer_function_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, func_index);
_mav_put_uint16_t(buf, 2, result);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, 6, 109);
#else
mavlink_flexifunction_buffer_function_ack_t packet;
packet.func_index = func_index;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, 6, 109);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION_ACK UNPACKING
/**
* @brief Get field target_system from flexifunction_buffer_function_ack message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_buffer_function_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from flexifunction_buffer_function_ack message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_buffer_function_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field func_index from flexifunction_buffer_function_ack message
*
* @return Function index
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_get_func_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field result from flexifunction_buffer_function_ack message
*
* @return result of acknowledge, 0=fail, 1=good
*/
static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a flexifunction_buffer_function_ack message into a struct
*
* @param msg The message to decode
* @param flexifunction_buffer_function_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_buffer_function_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_buffer_function_ack->func_index = mavlink_msg_flexifunction_buffer_function_ack_get_func_index(msg);
flexifunction_buffer_function_ack->result = mavlink_msg_flexifunction_buffer_function_ack_get_result(msg);
flexifunction_buffer_function_ack->target_system = mavlink_msg_flexifunction_buffer_function_ack_get_target_system(msg);
flexifunction_buffer_function_ack->target_component = mavlink_msg_flexifunction_buffer_function_ack_get_target_component(msg);
#else
memcpy(flexifunction_buffer_function_ack, _MAV_PAYLOAD(msg), 6);
#endif
}

View File

@@ -0,0 +1,188 @@
// MESSAGE FLEXIFUNCTION_COMMAND PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND 157
typedef struct __mavlink_flexifunction_command_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t command_type; ///< Flexifunction command type
} mavlink_flexifunction_command_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN 3
#define MAVLINK_MSG_ID_157_LEN 3
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND { \
"FLEXIFUNCTION_COMMAND", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_command_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_command_t, target_component) }, \
{ "command_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_command_t, command_type) }, \
} \
}
/**
* @brief Pack a flexifunction_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 System ID
* @param target_component Component ID
* @param command_type Flexifunction command type
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_flexifunction_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command_type = command_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND;
return mavlink_finalize_message(msg, system_id, component_id, 3, 133);
}
/**
* @brief Pack a flexifunction_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 System ID
* @param target_component Component ID
* @param command_type Flexifunction command type
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_flexifunction_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command_type = command_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 133);
}
/**
* @brief Encode a flexifunction_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 flexifunction_command C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_command_t* flexifunction_command)
{
return mavlink_msg_flexifunction_command_pack(system_id, component_id, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type);
}
/**
* @brief Send a flexifunction_command message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param command_type Flexifunction command type
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, 3, 133);
#else
mavlink_flexifunction_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command_type = command_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, 3, 133);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_COMMAND UNPACKING
/**
* @brief Get field target_system from flexifunction_command message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_command_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from flexifunction_command message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_command_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field command_type from flexifunction_command message
*
* @return Flexifunction command type
*/
static inline uint8_t mavlink_msg_flexifunction_command_get_command_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a flexifunction_command message into a struct
*
* @param msg The message to decode
* @param flexifunction_command C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_command_decode(const mavlink_message_t* msg, mavlink_flexifunction_command_t* flexifunction_command)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_command->target_system = mavlink_msg_flexifunction_command_get_target_system(msg);
flexifunction_command->target_component = mavlink_msg_flexifunction_command_get_target_component(msg);
flexifunction_command->command_type = mavlink_msg_flexifunction_command_get_command_type(msg);
#else
memcpy(flexifunction_command, _MAV_PAYLOAD(msg), 3);
#endif
}

View File

@@ -0,0 +1,166 @@
// MESSAGE FLEXIFUNCTION_COMMAND_ACK PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK 158
typedef struct __mavlink_flexifunction_command_ack_t
{
uint16_t command_type; ///< Command acknowledged
uint16_t result; ///< result of acknowledge
} mavlink_flexifunction_command_ack_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN 4
#define MAVLINK_MSG_ID_158_LEN 4
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND_ACK { \
"FLEXIFUNCTION_COMMAND_ACK", \
2, \
{ { "command_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_command_ack_t, command_type) }, \
{ "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_command_ack_t, result) }, \
} \
}
/**
* @brief Pack a flexifunction_command_ack 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 command_type Command acknowledged
* @param result result of acknowledge
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t command_type, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, command_type);
_mav_put_uint16_t(buf, 2, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_flexifunction_command_ack_t packet;
packet.command_type = command_type;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 4, 208);
}
/**
* @brief Pack a flexifunction_command_ack 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 command_type Command acknowledged
* @param result result of acknowledge
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t command_type,uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, command_type);
_mav_put_uint16_t(buf, 2, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_flexifunction_command_ack_t packet;
packet.command_type = command_type;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208);
}
/**
* @brief Encode a flexifunction_command_ack 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 flexifunction_command_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_command_ack_t* flexifunction_command_ack)
{
return mavlink_msg_flexifunction_command_ack_pack(system_id, component_id, msg, flexifunction_command_ack->command_type, flexifunction_command_ack->result);
}
/**
* @brief Send a flexifunction_command_ack message
* @param chan MAVLink channel to send the message
*
* @param command_type Command acknowledged
* @param result result of acknowledge
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_command_ack_send(mavlink_channel_t chan, uint16_t command_type, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, command_type);
_mav_put_uint16_t(buf, 2, result);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, 4, 208);
#else
mavlink_flexifunction_command_ack_t packet;
packet.command_type = command_type;
packet.result = result;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, 4, 208);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_COMMAND_ACK UNPACKING
/**
* @brief Get field command_type from flexifunction_command_ack message
*
* @return Command acknowledged
*/
static inline uint16_t mavlink_msg_flexifunction_command_ack_get_command_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field result from flexifunction_command_ack message
*
* @return result of acknowledge
*/
static inline uint16_t mavlink_msg_flexifunction_command_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a flexifunction_command_ack message into a struct
*
* @param msg The message to decode
* @param flexifunction_command_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_command_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_command_ack_t* flexifunction_command_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_command_ack->command_type = mavlink_msg_flexifunction_command_ack_get_command_type(msg);
flexifunction_command_ack->result = mavlink_msg_flexifunction_command_ack_get_result(msg);
#else
memcpy(flexifunction_command_ack, _MAV_PAYLOAD(msg), 4);
#endif
}

View File

@@ -0,0 +1,248 @@
// MESSAGE FLEXIFUNCTION_DIRECTORY PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY 155
typedef struct __mavlink_flexifunction_directory_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t directory_type; ///< 0=inputs, 1=outputs
uint8_t start_index; ///< index of first directory entry to write
uint8_t count; ///< count of directory entries to write
int8_t directory_data[48]; ///< Settings data
} mavlink_flexifunction_directory_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN 53
#define MAVLINK_MSG_ID_155_LEN 53
#define MAVLINK_MSG_FLEXIFUNCTION_DIRECTORY_FIELD_DIRECTORY_DATA_LEN 48
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY { \
"FLEXIFUNCTION_DIRECTORY", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_directory_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_directory_t, target_component) }, \
{ "directory_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_directory_t, directory_type) }, \
{ "start_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_flexifunction_directory_t, start_index) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_directory_t, count) }, \
{ "directory_data", NULL, MAVLINK_TYPE_INT8_T, 48, 5, offsetof(mavlink_flexifunction_directory_t, directory_data) }, \
} \
}
/**
* @brief Pack a flexifunction_directory 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 directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param directory_data Settings data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_directory_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[53];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, directory_type);
_mav_put_uint8_t(buf, 3, start_index);
_mav_put_uint8_t(buf, 4, count);
_mav_put_int8_t_array(buf, 5, directory_data, 48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53);
#else
mavlink_flexifunction_directory_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY;
return mavlink_finalize_message(msg, system_id, component_id, 53, 12);
}
/**
* @brief Pack a flexifunction_directory 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 directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param directory_data Settings data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_directory_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,const int8_t *directory_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[53];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, directory_type);
_mav_put_uint8_t(buf, 3, start_index);
_mav_put_uint8_t(buf, 4, count);
_mav_put_int8_t_array(buf, 5, directory_data, 48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 53);
#else
mavlink_flexifunction_directory_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 53);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 53, 12);
}
/**
* @brief Encode a flexifunction_directory 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 flexifunction_directory C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_directory_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_directory_t* flexifunction_directory)
{
return mavlink_msg_flexifunction_directory_pack(system_id, component_id, msg, flexifunction_directory->target_system, flexifunction_directory->target_component, flexifunction_directory->directory_type, flexifunction_directory->start_index, flexifunction_directory->count, flexifunction_directory->directory_data);
}
/**
* @brief Send a flexifunction_directory message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param directory_data Settings data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_directory_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[53];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, directory_type);
_mav_put_uint8_t(buf, 3, start_index);
_mav_put_uint8_t(buf, 4, count);
_mav_put_int8_t_array(buf, 5, directory_data, 48);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, 53, 12);
#else
mavlink_flexifunction_directory_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, 53, 12);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_DIRECTORY UNPACKING
/**
* @brief Get field target_system from flexifunction_directory message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_directory_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from flexifunction_directory message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_directory_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field directory_type from flexifunction_directory message
*
* @return 0=inputs, 1=outputs
*/
static inline uint8_t mavlink_msg_flexifunction_directory_get_directory_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field start_index from flexifunction_directory message
*
* @return index of first directory entry to write
*/
static inline uint8_t mavlink_msg_flexifunction_directory_get_start_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field count from flexifunction_directory message
*
* @return count of directory entries to write
*/
static inline uint8_t mavlink_msg_flexifunction_directory_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field directory_data from flexifunction_directory message
*
* @return Settings data
*/
static inline uint16_t mavlink_msg_flexifunction_directory_get_directory_data(const mavlink_message_t* msg, int8_t *directory_data)
{
return _MAV_RETURN_int8_t_array(msg, directory_data, 48, 5);
}
/**
* @brief Decode a flexifunction_directory message into a struct
*
* @param msg The message to decode
* @param flexifunction_directory C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_directory_decode(const mavlink_message_t* msg, mavlink_flexifunction_directory_t* flexifunction_directory)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_directory->target_system = mavlink_msg_flexifunction_directory_get_target_system(msg);
flexifunction_directory->target_component = mavlink_msg_flexifunction_directory_get_target_component(msg);
flexifunction_directory->directory_type = mavlink_msg_flexifunction_directory_get_directory_type(msg);
flexifunction_directory->start_index = mavlink_msg_flexifunction_directory_get_start_index(msg);
flexifunction_directory->count = mavlink_msg_flexifunction_directory_get_count(msg);
mavlink_msg_flexifunction_directory_get_directory_data(msg, flexifunction_directory->directory_data);
#else
memcpy(flexifunction_directory, _MAV_PAYLOAD(msg), 53);
#endif
}

View File

@@ -0,0 +1,254 @@
// MESSAGE FLEXIFUNCTION_DIRECTORY_ACK PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK 156
typedef struct __mavlink_flexifunction_directory_ack_t
{
uint16_t result; ///< result of acknowledge, 0=fail, 1=good
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t directory_type; ///< 0=inputs, 1=outputs
uint8_t start_index; ///< index of first directory entry to write
uint8_t count; ///< count of directory entries to write
} mavlink_flexifunction_directory_ack_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN 7
#define MAVLINK_MSG_ID_156_LEN 7
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY_ACK { \
"FLEXIFUNCTION_DIRECTORY_ACK", \
6, \
{ { "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_directory_ack_t, result) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_directory_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_flexifunction_directory_ack_t, target_component) }, \
{ "directory_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_directory_ack_t, directory_type) }, \
{ "start_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_directory_ack_t, start_index) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_flexifunction_directory_ack_t, count) }, \
} \
}
/**
* @brief Pack a flexifunction_directory_ack 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 directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param result result of acknowledge, 0=fail, 1=good
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[7];
_mav_put_uint16_t(buf, 0, result);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, directory_type);
_mav_put_uint8_t(buf, 5, start_index);
_mav_put_uint8_t(buf, 6, count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7);
#else
mavlink_flexifunction_directory_ack_t packet;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 7, 218);
}
/**
* @brief Pack a flexifunction_directory_ack 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 directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param result result of acknowledge, 0=fail, 1=good
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[7];
_mav_put_uint16_t(buf, 0, result);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, directory_type);
_mav_put_uint8_t(buf, 5, start_index);
_mav_put_uint8_t(buf, 6, count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 7);
#else
mavlink_flexifunction_directory_ack_t packet;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 7);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 218);
}
/**
* @brief Encode a flexifunction_directory_ack 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 flexifunction_directory_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack)
{
return mavlink_msg_flexifunction_directory_ack_pack(system_id, component_id, msg, flexifunction_directory_ack->target_system, flexifunction_directory_ack->target_component, flexifunction_directory_ack->directory_type, flexifunction_directory_ack->start_index, flexifunction_directory_ack->count, flexifunction_directory_ack->result);
}
/**
* @brief Send a flexifunction_directory_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param directory_type 0=inputs, 1=outputs
* @param start_index index of first directory entry to write
* @param count count of directory entries to write
* @param result result of acknowledge, 0=fail, 1=good
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[7];
_mav_put_uint16_t(buf, 0, result);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, directory_type);
_mav_put_uint8_t(buf, 5, start_index);
_mav_put_uint8_t(buf, 6, count);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, 7, 218);
#else
mavlink_flexifunction_directory_ack_t packet;
packet.result = result;
packet.target_system = target_system;
packet.target_component = target_component;
packet.directory_type = directory_type;
packet.start_index = start_index;
packet.count = count;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, 7, 218);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_DIRECTORY_ACK UNPACKING
/**
* @brief Get field target_system from flexifunction_directory_ack message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from flexifunction_directory_ack message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field directory_type from flexifunction_directory_ack message
*
* @return 0=inputs, 1=outputs
*/
static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_directory_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field start_index from flexifunction_directory_ack message
*
* @return index of first directory entry to write
*/
static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_start_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field count from flexifunction_directory_ack message
*
* @return count of directory entries to write
*/
static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field result from flexifunction_directory_ack message
*
* @return result of acknowledge, 0=fail, 1=good
*/
static inline uint16_t mavlink_msg_flexifunction_directory_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Decode a flexifunction_directory_ack message into a struct
*
* @param msg The message to decode
* @param flexifunction_directory_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_directory_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_directory_ack->result = mavlink_msg_flexifunction_directory_ack_get_result(msg);
flexifunction_directory_ack->target_system = mavlink_msg_flexifunction_directory_ack_get_target_system(msg);
flexifunction_directory_ack->target_component = mavlink_msg_flexifunction_directory_ack_get_target_component(msg);
flexifunction_directory_ack->directory_type = mavlink_msg_flexifunction_directory_ack_get_directory_type(msg);
flexifunction_directory_ack->start_index = mavlink_msg_flexifunction_directory_ack_get_start_index(msg);
flexifunction_directory_ack->count = mavlink_msg_flexifunction_directory_ack_get_count(msg);
#else
memcpy(flexifunction_directory_ack, _MAV_PAYLOAD(msg), 7);
#endif
}

View File

@@ -0,0 +1,210 @@
// MESSAGE FLEXIFUNCTION_READ_REQ PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ 151
typedef struct __mavlink_flexifunction_read_req_t
{
int16_t read_req_type; ///< Type of flexifunction data requested
int16_t data_index; ///< index into data where needed
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_flexifunction_read_req_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN 6
#define MAVLINK_MSG_ID_151_LEN 6
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_READ_REQ { \
"FLEXIFUNCTION_READ_REQ", \
4, \
{ { "read_req_type", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_flexifunction_read_req_t, read_req_type) }, \
{ "data_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_flexifunction_read_req_t, data_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_read_req_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_read_req_t, target_component) }, \
} \
}
/**
* @brief Pack a flexifunction_read_req 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 read_req_type Type of flexifunction data requested
* @param data_index index into data where needed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_read_req_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, read_req_type);
_mav_put_int16_t(buf, 2, data_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_flexifunction_read_req_t packet;
packet.read_req_type = read_req_type;
packet.data_index = data_index;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ;
return mavlink_finalize_message(msg, system_id, component_id, 6, 26);
}
/**
* @brief Pack a flexifunction_read_req 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 read_req_type Type of flexifunction data requested
* @param data_index index into data where needed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_read_req_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,int16_t read_req_type,int16_t data_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, read_req_type);
_mav_put_int16_t(buf, 2, data_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_flexifunction_read_req_t packet;
packet.read_req_type = read_req_type;
packet.data_index = data_index;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 26);
}
/**
* @brief Encode a flexifunction_read_req 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 flexifunction_read_req C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_read_req_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_read_req_t* flexifunction_read_req)
{
return mavlink_msg_flexifunction_read_req_pack(system_id, component_id, msg, flexifunction_read_req->target_system, flexifunction_read_req->target_component, flexifunction_read_req->read_req_type, flexifunction_read_req->data_index);
}
/**
* @brief Send a flexifunction_read_req message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param read_req_type Type of flexifunction data requested
* @param data_index index into data where needed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_read_req_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, read_req_type);
_mav_put_int16_t(buf, 2, data_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, 6, 26);
#else
mavlink_flexifunction_read_req_t packet;
packet.read_req_type = read_req_type;
packet.data_index = data_index;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, 6, 26);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_READ_REQ UNPACKING
/**
* @brief Get field target_system from flexifunction_read_req message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_read_req_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from flexifunction_read_req message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_read_req_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field read_req_type from flexifunction_read_req message
*
* @return Type of flexifunction data requested
*/
static inline int16_t mavlink_msg_flexifunction_read_req_get_read_req_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
/**
* @brief Get field data_index from flexifunction_read_req message
*
* @return index into data where needed
*/
static inline int16_t mavlink_msg_flexifunction_read_req_get_data_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Decode a flexifunction_read_req message into a struct
*
* @param msg The message to decode
* @param flexifunction_read_req C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_read_req_decode(const mavlink_message_t* msg, mavlink_flexifunction_read_req_t* flexifunction_read_req)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_read_req->read_req_type = mavlink_msg_flexifunction_read_req_get_read_req_type(msg);
flexifunction_read_req->data_index = mavlink_msg_flexifunction_read_req_get_data_index(msg);
flexifunction_read_req->target_system = mavlink_msg_flexifunction_read_req_get_target_system(msg);
flexifunction_read_req->target_component = mavlink_msg_flexifunction_read_req_get_target_component(msg);
#else
memcpy(flexifunction_read_req, _MAV_PAYLOAD(msg), 6);
#endif
}

View File

@@ -0,0 +1,166 @@
// MESSAGE FLEXIFUNCTION_SET PACKING
#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET 150
typedef struct __mavlink_flexifunction_set_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_flexifunction_set_t;
#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN 2
#define MAVLINK_MSG_ID_150_LEN 2
#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_SET { \
"FLEXIFUNCTION_SET", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_set_t, target_component) }, \
} \
}
/**
* @brief Pack a flexifunction_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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_flexifunction_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET;
return mavlink_finalize_message(msg, system_id, component_id, 2, 181);
}
/**
* @brief Pack a flexifunction_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
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flexifunction_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_flexifunction_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 181);
}
/**
* @brief Encode a flexifunction_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 flexifunction_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flexifunction_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_set_t* flexifunction_set)
{
return mavlink_msg_flexifunction_set_pack(system_id, component_id, msg, flexifunction_set->target_system, flexifunction_set->target_component);
}
/**
* @brief Send a flexifunction_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flexifunction_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, 2, 181);
#else
mavlink_flexifunction_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, 2, 181);
#endif
}
#endif
// MESSAGE FLEXIFUNCTION_SET UNPACKING
/**
* @brief Get field target_system from flexifunction_set message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_flexifunction_set_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from flexifunction_set message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_flexifunction_set_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a flexifunction_set message into a struct
*
* @param msg The message to decode
* @param flexifunction_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_flexifunction_set_decode(const mavlink_message_t* msg, mavlink_flexifunction_set_t* flexifunction_set)
{
#if MAVLINK_NEED_BYTE_SWAP
flexifunction_set->target_system = mavlink_msg_flexifunction_set_get_target_system(msg);
flexifunction_set->target_component = mavlink_msg_flexifunction_set_get_target_component(msg);
#else
memcpy(flexifunction_set, _MAV_PAYLOAD(msg), 2);
#endif
}

View File

@@ -0,0 +1,210 @@
// MESSAGE SERIAL_UDB_EXTRA_F13 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13 177
typedef struct __mavlink_serial_udb_extra_f13_t
{
int32_t sue_lat_origin; ///< Serial UDB Extra MP Origin Latitude
int32_t sue_lon_origin; ///< Serial UDB Extra MP Origin Longitude
int32_t sue_alt_origin; ///< Serial UDB Extra MP Origin Altitude Above Sea Level
int16_t sue_week_no; ///< Serial UDB Extra GPS Week Number
} mavlink_serial_udb_extra_f13_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN 14
#define MAVLINK_MSG_ID_177_LEN 14
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F13 { \
"SERIAL_UDB_EXTRA_F13", \
4, \
{ { "sue_lat_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f13_t, sue_lat_origin) }, \
{ "sue_lon_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f13_t, sue_lon_origin) }, \
{ "sue_alt_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_serial_udb_extra_f13_t, sue_alt_origin) }, \
{ "sue_week_no", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_serial_udb_extra_f13_t, sue_week_no) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f13 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 sue_week_no Serial UDB Extra GPS Week Number
* @param sue_lat_origin Serial UDB Extra MP Origin Latitude
* @param sue_lon_origin Serial UDB Extra MP Origin Longitude
* @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, sue_lat_origin);
_mav_put_int32_t(buf, 4, sue_lon_origin);
_mav_put_int32_t(buf, 8, sue_alt_origin);
_mav_put_int16_t(buf, 12, sue_week_no);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_serial_udb_extra_f13_t packet;
packet.sue_lat_origin = sue_lat_origin;
packet.sue_lon_origin = sue_lon_origin;
packet.sue_alt_origin = sue_alt_origin;
packet.sue_week_no = sue_week_no;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13;
return mavlink_finalize_message(msg, system_id, component_id, 14, 249);
}
/**
* @brief Pack a serial_udb_extra_f13 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 sue_week_no Serial UDB Extra GPS Week Number
* @param sue_lat_origin Serial UDB Extra MP Origin Latitude
* @param sue_lon_origin Serial UDB Extra MP Origin Longitude
* @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t sue_week_no,int32_t sue_lat_origin,int32_t sue_lon_origin,int32_t sue_alt_origin)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, sue_lat_origin);
_mav_put_int32_t(buf, 4, sue_lon_origin);
_mav_put_int32_t(buf, 8, sue_alt_origin);
_mav_put_int16_t(buf, 12, sue_week_no);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_serial_udb_extra_f13_t packet;
packet.sue_lat_origin = sue_lat_origin;
packet.sue_lon_origin = sue_lon_origin;
packet.sue_alt_origin = sue_alt_origin;
packet.sue_week_no = sue_week_no;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 249);
}
/**
* @brief Encode a serial_udb_extra_f13 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 serial_udb_extra_f13 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13)
{
return mavlink_msg_serial_udb_extra_f13_pack(system_id, component_id, msg, serial_udb_extra_f13->sue_week_no, serial_udb_extra_f13->sue_lat_origin, serial_udb_extra_f13->sue_lon_origin, serial_udb_extra_f13->sue_alt_origin);
}
/**
* @brief Send a serial_udb_extra_f13 message
* @param chan MAVLink channel to send the message
*
* @param sue_week_no Serial UDB Extra GPS Week Number
* @param sue_lat_origin Serial UDB Extra MP Origin Latitude
* @param sue_lon_origin Serial UDB Extra MP Origin Longitude
* @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f13_send(mavlink_channel_t chan, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, sue_lat_origin);
_mav_put_int32_t(buf, 4, sue_lon_origin);
_mav_put_int32_t(buf, 8, sue_alt_origin);
_mav_put_int16_t(buf, 12, sue_week_no);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, 14, 249);
#else
mavlink_serial_udb_extra_f13_t packet;
packet.sue_lat_origin = sue_lat_origin;
packet.sue_lon_origin = sue_lon_origin;
packet.sue_alt_origin = sue_alt_origin;
packet.sue_week_no = sue_week_no;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, 14, 249);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F13 UNPACKING
/**
* @brief Get field sue_week_no from serial_udb_extra_f13 message
*
* @return Serial UDB Extra GPS Week Number
*/
static inline int16_t mavlink_msg_serial_udb_extra_f13_get_sue_week_no(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
/**
* @brief Get field sue_lat_origin from serial_udb_extra_f13 message
*
* @return Serial UDB Extra MP Origin Latitude
*/
static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_lat_origin(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field sue_lon_origin from serial_udb_extra_f13 message
*
* @return Serial UDB Extra MP Origin Longitude
*/
static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_lon_origin(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field sue_alt_origin from serial_udb_extra_f13 message
*
* @return Serial UDB Extra MP Origin Altitude Above Sea Level
*/
static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_alt_origin(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Decode a serial_udb_extra_f13 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f13 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f13_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f13->sue_lat_origin = mavlink_msg_serial_udb_extra_f13_get_sue_lat_origin(msg);
serial_udb_extra_f13->sue_lon_origin = mavlink_msg_serial_udb_extra_f13_get_sue_lon_origin(msg);
serial_udb_extra_f13->sue_alt_origin = mavlink_msg_serial_udb_extra_f13_get_sue_alt_origin(msg);
serial_udb_extra_f13->sue_week_no = mavlink_msg_serial_udb_extra_f13_get_sue_week_no(msg);
#else
memcpy(serial_udb_extra_f13, _MAV_PAYLOAD(msg), 14);
#endif
}

View File

@@ -0,0 +1,364 @@
// MESSAGE SERIAL_UDB_EXTRA_F14 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14 178
typedef struct __mavlink_serial_udb_extra_f14_t
{
uint32_t sue_TRAP_SOURCE; ///< Serial UDB Extra Type Program Address of Last Trap
int16_t sue_RCON; ///< Serial UDB Extra Reboot Regitster of DSPIC
int16_t sue_TRAP_FLAGS; ///< Serial UDB Extra Last dspic Trap Flags
int16_t sue_osc_fail_count; ///< Serial UDB Extra Number of Ocillator Failures
uint8_t sue_WIND_ESTIMATION; ///< Serial UDB Extra Wind Estimation Enabled
uint8_t sue_GPS_TYPE; ///< Serial UDB Extra Type of GPS Unit
uint8_t sue_DR; ///< Serial UDB Extra Dead Reckoning Enabled
uint8_t sue_BOARD_TYPE; ///< Serial UDB Extra Type of UDB Hardware
uint8_t sue_AIRFRAME; ///< Serial UDB Extra Type of Airframe
uint8_t sue_CLOCK_CONFIG; ///< Serial UDB Extra UDB Internal Clock Configuration
uint8_t sue_FLIGHT_PLAN_TYPE; ///< Serial UDB Extra Type of Flight Plan
} mavlink_serial_udb_extra_f14_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN 17
#define MAVLINK_MSG_ID_178_LEN 17
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F14 { \
"SERIAL_UDB_EXTRA_F14", \
11, \
{ { "sue_TRAP_SOURCE", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f14_t, sue_TRAP_SOURCE) }, \
{ "sue_RCON", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_serial_udb_extra_f14_t, sue_RCON) }, \
{ "sue_TRAP_FLAGS", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_serial_udb_extra_f14_t, sue_TRAP_FLAGS) }, \
{ "sue_osc_fail_count", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_serial_udb_extra_f14_t, sue_osc_fail_count) }, \
{ "sue_WIND_ESTIMATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_serial_udb_extra_f14_t, sue_WIND_ESTIMATION) }, \
{ "sue_GPS_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_serial_udb_extra_f14_t, sue_GPS_TYPE) }, \
{ "sue_DR", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_serial_udb_extra_f14_t, sue_DR) }, \
{ "sue_BOARD_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_serial_udb_extra_f14_t, sue_BOARD_TYPE) }, \
{ "sue_AIRFRAME", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_serial_udb_extra_f14_t, sue_AIRFRAME) }, \
{ "sue_CLOCK_CONFIG", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_serial_udb_extra_f14_t, sue_CLOCK_CONFIG) }, \
{ "sue_FLIGHT_PLAN_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_serial_udb_extra_f14_t, sue_FLIGHT_PLAN_TYPE) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f14 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 sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled
* @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit
* @param sue_DR Serial UDB Extra Dead Reckoning Enabled
* @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware
* @param sue_AIRFRAME Serial UDB Extra Type of Airframe
* @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC
* @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags
* @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap
* @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures
* @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration
* @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE);
_mav_put_int16_t(buf, 4, sue_RCON);
_mav_put_int16_t(buf, 6, sue_TRAP_FLAGS);
_mav_put_int16_t(buf, 8, sue_osc_fail_count);
_mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION);
_mav_put_uint8_t(buf, 11, sue_GPS_TYPE);
_mav_put_uint8_t(buf, 12, sue_DR);
_mav_put_uint8_t(buf, 13, sue_BOARD_TYPE);
_mav_put_uint8_t(buf, 14, sue_AIRFRAME);
_mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG);
_mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_serial_udb_extra_f14_t packet;
packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE;
packet.sue_RCON = sue_RCON;
packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS;
packet.sue_osc_fail_count = sue_osc_fail_count;
packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION;
packet.sue_GPS_TYPE = sue_GPS_TYPE;
packet.sue_DR = sue_DR;
packet.sue_BOARD_TYPE = sue_BOARD_TYPE;
packet.sue_AIRFRAME = sue_AIRFRAME;
packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG;
packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14;
return mavlink_finalize_message(msg, system_id, component_id, 17, 123);
}
/**
* @brief Pack a serial_udb_extra_f14 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 sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled
* @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit
* @param sue_DR Serial UDB Extra Dead Reckoning Enabled
* @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware
* @param sue_AIRFRAME Serial UDB Extra Type of Airframe
* @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC
* @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags
* @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap
* @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures
* @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration
* @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t sue_WIND_ESTIMATION,uint8_t sue_GPS_TYPE,uint8_t sue_DR,uint8_t sue_BOARD_TYPE,uint8_t sue_AIRFRAME,int16_t sue_RCON,int16_t sue_TRAP_FLAGS,uint32_t sue_TRAP_SOURCE,int16_t sue_osc_fail_count,uint8_t sue_CLOCK_CONFIG,uint8_t sue_FLIGHT_PLAN_TYPE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE);
_mav_put_int16_t(buf, 4, sue_RCON);
_mav_put_int16_t(buf, 6, sue_TRAP_FLAGS);
_mav_put_int16_t(buf, 8, sue_osc_fail_count);
_mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION);
_mav_put_uint8_t(buf, 11, sue_GPS_TYPE);
_mav_put_uint8_t(buf, 12, sue_DR);
_mav_put_uint8_t(buf, 13, sue_BOARD_TYPE);
_mav_put_uint8_t(buf, 14, sue_AIRFRAME);
_mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG);
_mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_serial_udb_extra_f14_t packet;
packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE;
packet.sue_RCON = sue_RCON;
packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS;
packet.sue_osc_fail_count = sue_osc_fail_count;
packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION;
packet.sue_GPS_TYPE = sue_GPS_TYPE;
packet.sue_DR = sue_DR;
packet.sue_BOARD_TYPE = sue_BOARD_TYPE;
packet.sue_AIRFRAME = sue_AIRFRAME;
packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG;
packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 123);
}
/**
* @brief Encode a serial_udb_extra_f14 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 serial_udb_extra_f14 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14)
{
return mavlink_msg_serial_udb_extra_f14_pack(system_id, component_id, msg, serial_udb_extra_f14->sue_WIND_ESTIMATION, serial_udb_extra_f14->sue_GPS_TYPE, serial_udb_extra_f14->sue_DR, serial_udb_extra_f14->sue_BOARD_TYPE, serial_udb_extra_f14->sue_AIRFRAME, serial_udb_extra_f14->sue_RCON, serial_udb_extra_f14->sue_TRAP_FLAGS, serial_udb_extra_f14->sue_TRAP_SOURCE, serial_udb_extra_f14->sue_osc_fail_count, serial_udb_extra_f14->sue_CLOCK_CONFIG, serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE);
}
/**
* @brief Send a serial_udb_extra_f14 message
* @param chan MAVLink channel to send the message
*
* @param sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled
* @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit
* @param sue_DR Serial UDB Extra Dead Reckoning Enabled
* @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware
* @param sue_AIRFRAME Serial UDB Extra Type of Airframe
* @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC
* @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags
* @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap
* @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures
* @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration
* @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE);
_mav_put_int16_t(buf, 4, sue_RCON);
_mav_put_int16_t(buf, 6, sue_TRAP_FLAGS);
_mav_put_int16_t(buf, 8, sue_osc_fail_count);
_mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION);
_mav_put_uint8_t(buf, 11, sue_GPS_TYPE);
_mav_put_uint8_t(buf, 12, sue_DR);
_mav_put_uint8_t(buf, 13, sue_BOARD_TYPE);
_mav_put_uint8_t(buf, 14, sue_AIRFRAME);
_mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG);
_mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, 17, 123);
#else
mavlink_serial_udb_extra_f14_t packet;
packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE;
packet.sue_RCON = sue_RCON;
packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS;
packet.sue_osc_fail_count = sue_osc_fail_count;
packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION;
packet.sue_GPS_TYPE = sue_GPS_TYPE;
packet.sue_DR = sue_DR;
packet.sue_BOARD_TYPE = sue_BOARD_TYPE;
packet.sue_AIRFRAME = sue_AIRFRAME;
packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG;
packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, 17, 123);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F14 UNPACKING
/**
* @brief Get field sue_WIND_ESTIMATION from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Wind Estimation Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_WIND_ESTIMATION(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field sue_GPS_TYPE from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Type of GPS Unit
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_GPS_TYPE(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field sue_DR from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Dead Reckoning Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_DR(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field sue_BOARD_TYPE from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Type of UDB Hardware
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_BOARD_TYPE(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field sue_AIRFRAME from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Type of Airframe
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_AIRFRAME(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
/**
* @brief Get field sue_RCON from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Reboot Regitster of DSPIC
*/
static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_RCON(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Get field sue_TRAP_FLAGS from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Last dspic Trap Flags
*/
static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_FLAGS(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
/**
* @brief Get field sue_TRAP_SOURCE from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Type Program Address of Last Trap
*/
static inline uint32_t mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_SOURCE(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field sue_osc_fail_count from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Number of Ocillator Failures
*/
static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_osc_fail_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field sue_CLOCK_CONFIG from serial_udb_extra_f14 message
*
* @return Serial UDB Extra UDB Internal Clock Configuration
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_CLOCK_CONFIG(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 15);
}
/**
* @brief Get field sue_FLIGHT_PLAN_TYPE from serial_udb_extra_f14 message
*
* @return Serial UDB Extra Type of Flight Plan
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_FLIGHT_PLAN_TYPE(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
/**
* @brief Decode a serial_udb_extra_f14 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f14 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f14_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f14->sue_TRAP_SOURCE = mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_SOURCE(msg);
serial_udb_extra_f14->sue_RCON = mavlink_msg_serial_udb_extra_f14_get_sue_RCON(msg);
serial_udb_extra_f14->sue_TRAP_FLAGS = mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_FLAGS(msg);
serial_udb_extra_f14->sue_osc_fail_count = mavlink_msg_serial_udb_extra_f14_get_sue_osc_fail_count(msg);
serial_udb_extra_f14->sue_WIND_ESTIMATION = mavlink_msg_serial_udb_extra_f14_get_sue_WIND_ESTIMATION(msg);
serial_udb_extra_f14->sue_GPS_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_GPS_TYPE(msg);
serial_udb_extra_f14->sue_DR = mavlink_msg_serial_udb_extra_f14_get_sue_DR(msg);
serial_udb_extra_f14->sue_BOARD_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_BOARD_TYPE(msg);
serial_udb_extra_f14->sue_AIRFRAME = mavlink_msg_serial_udb_extra_f14_get_sue_AIRFRAME(msg);
serial_udb_extra_f14->sue_CLOCK_CONFIG = mavlink_msg_serial_udb_extra_f14_get_sue_CLOCK_CONFIG(msg);
serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_FLIGHT_PLAN_TYPE(msg);
#else
memcpy(serial_udb_extra_f14, _MAV_PAYLOAD(msg), 17);
#endif
}

View File

@@ -0,0 +1,167 @@
// MESSAGE SERIAL_UDB_EXTRA_F15 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15 179
typedef struct __mavlink_serial_udb_extra_f15_t
{
uint8_t sue_ID_VEHICLE_MODEL_NAME[40]; ///< Serial UDB Extra Model Name Of Vehicle
uint8_t sue_ID_VEHICLE_REGISTRATION[20]; ///< Serial UDB Extra Registraton Number of Vehicle
} mavlink_serial_udb_extra_f15_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN 60
#define MAVLINK_MSG_ID_179_LEN 60
#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_MODEL_NAME_LEN 40
#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_REGISTRATION_LEN 20
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F15 { \
"SERIAL_UDB_EXTRA_F15", \
2, \
{ { "sue_ID_VEHICLE_MODEL_NAME", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_serial_udb_extra_f15_t, sue_ID_VEHICLE_MODEL_NAME) }, \
{ "sue_ID_VEHICLE_REGISTRATION", NULL, MAVLINK_TYPE_UINT8_T, 20, 40, offsetof(mavlink_serial_udb_extra_f15_t, sue_ID_VEHICLE_REGISTRATION) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f15 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 sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle
* @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60);
#else
mavlink_serial_udb_extra_f15_t packet;
mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15;
return mavlink_finalize_message(msg, system_id, component_id, 60, 7);
}
/**
* @brief Pack a serial_udb_extra_f15 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 sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle
* @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *sue_ID_VEHICLE_MODEL_NAME,const uint8_t *sue_ID_VEHICLE_REGISTRATION)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 60);
#else
mavlink_serial_udb_extra_f15_t packet;
mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 60);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 60, 7);
}
/**
* @brief Encode a serial_udb_extra_f15 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 serial_udb_extra_f15 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15)
{
return mavlink_msg_serial_udb_extra_f15_pack(system_id, component_id, msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION);
}
/**
* @brief Send a serial_udb_extra_f15 message
* @param chan MAVLink channel to send the message
*
* @param sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle
* @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f15_send(mavlink_channel_t chan, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[60];
_mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, 60, 7);
#else
mavlink_serial_udb_extra_f15_t packet;
mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, 60, 7);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F15 UNPACKING
/**
* @brief Get field sue_ID_VEHICLE_MODEL_NAME from serial_udb_extra_f15 message
*
* @return Serial UDB Extra Model Name Of Vehicle
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_MODEL_NAME(const mavlink_message_t* msg, uint8_t *sue_ID_VEHICLE_MODEL_NAME)
{
return _MAV_RETURN_uint8_t_array(msg, sue_ID_VEHICLE_MODEL_NAME, 40, 0);
}
/**
* @brief Get field sue_ID_VEHICLE_REGISTRATION from serial_udb_extra_f15 message
*
* @return Serial UDB Extra Registraton Number of Vehicle
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_REGISTRATION(const mavlink_message_t* msg, uint8_t *sue_ID_VEHICLE_REGISTRATION)
{
return _MAV_RETURN_uint8_t_array(msg, sue_ID_VEHICLE_REGISTRATION, 20, 40);
}
/**
* @brief Decode a serial_udb_extra_f15 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f15 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f15_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_MODEL_NAME(msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME);
mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_REGISTRATION(msg, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION);
#else
memcpy(serial_udb_extra_f15, _MAV_PAYLOAD(msg), 60);
#endif
}

View File

@@ -0,0 +1,167 @@
// MESSAGE SERIAL_UDB_EXTRA_F16 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16 180
typedef struct __mavlink_serial_udb_extra_f16_t
{
uint8_t sue_ID_LEAD_PILOT[40]; ///< Serial UDB Extra Name of Expected Lead Pilot
uint8_t sue_ID_DIY_DRONES_URL[70]; ///< Serial UDB Extra URL of Lead Pilot or Team
} mavlink_serial_udb_extra_f16_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN 110
#define MAVLINK_MSG_ID_180_LEN 110
#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_LEAD_PILOT_LEN 40
#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_DIY_DRONES_URL_LEN 70
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F16 { \
"SERIAL_UDB_EXTRA_F16", \
2, \
{ { "sue_ID_LEAD_PILOT", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_serial_udb_extra_f16_t, sue_ID_LEAD_PILOT) }, \
{ "sue_ID_DIY_DRONES_URL", NULL, MAVLINK_TYPE_UINT8_T, 70, 40, offsetof(mavlink_serial_udb_extra_f16_t, sue_ID_DIY_DRONES_URL) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f16 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 sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot
* @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[110];
_mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 110);
#else
mavlink_serial_udb_extra_f16_t packet;
mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 110);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16;
return mavlink_finalize_message(msg, system_id, component_id, 110, 222);
}
/**
* @brief Pack a serial_udb_extra_f16 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 sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot
* @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *sue_ID_LEAD_PILOT,const uint8_t *sue_ID_DIY_DRONES_URL)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[110];
_mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 110);
#else
mavlink_serial_udb_extra_f16_t packet;
mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 110);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 110, 222);
}
/**
* @brief Encode a serial_udb_extra_f16 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 serial_udb_extra_f16 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16)
{
return mavlink_msg_serial_udb_extra_f16_pack(system_id, component_id, msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL);
}
/**
* @brief Send a serial_udb_extra_f16 message
* @param chan MAVLink channel to send the message
*
* @param sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot
* @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f16_send(mavlink_channel_t chan, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[110];
_mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40);
_mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, 110, 222);
#else
mavlink_serial_udb_extra_f16_t packet;
mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40);
mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, 110, 222);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F16 UNPACKING
/**
* @brief Get field sue_ID_LEAD_PILOT from serial_udb_extra_f16 message
*
* @return Serial UDB Extra Name of Expected Lead Pilot
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f16_get_sue_ID_LEAD_PILOT(const mavlink_message_t* msg, uint8_t *sue_ID_LEAD_PILOT)
{
return _MAV_RETURN_uint8_t_array(msg, sue_ID_LEAD_PILOT, 40, 0);
}
/**
* @brief Get field sue_ID_DIY_DRONES_URL from serial_udb_extra_f16 message
*
* @return Serial UDB Extra URL of Lead Pilot or Team
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f16_get_sue_ID_DIY_DRONES_URL(const mavlink_message_t* msg, uint8_t *sue_ID_DIY_DRONES_URL)
{
return _MAV_RETURN_uint8_t_array(msg, sue_ID_DIY_DRONES_URL, 70, 40);
}
/**
* @brief Decode a serial_udb_extra_f16 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f16 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f16_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_serial_udb_extra_f16_get_sue_ID_LEAD_PILOT(msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT);
mavlink_msg_serial_udb_extra_f16_get_sue_ID_DIY_DRONES_URL(msg, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL);
#else
memcpy(serial_udb_extra_f16, _MAV_PAYLOAD(msg), 110);
#endif
}

View File

@@ -0,0 +1,738 @@
// MESSAGE SERIAL_UDB_EXTRA_F2_A PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A 170
typedef struct __mavlink_serial_udb_extra_f2_a_t
{
uint32_t sue_time; ///< Serial UDB Extra Time
int32_t sue_latitude; ///< Serial UDB Extra Latitude
int32_t sue_longitude; ///< Serial UDB Extra Longitude
int32_t sue_altitude; ///< Serial UDB Extra Altitude
uint16_t sue_waypoint_index; ///< Serial UDB Extra Waypoint Index
int16_t sue_rmat0; ///< Serial UDB Extra Rmat 0
int16_t sue_rmat1; ///< Serial UDB Extra Rmat 1
int16_t sue_rmat2; ///< Serial UDB Extra Rmat 2
int16_t sue_rmat3; ///< Serial UDB Extra Rmat 3
int16_t sue_rmat4; ///< Serial UDB Extra Rmat 4
int16_t sue_rmat5; ///< Serial UDB Extra Rmat 5
int16_t sue_rmat6; ///< Serial UDB Extra Rmat 6
int16_t sue_rmat7; ///< Serial UDB Extra Rmat 7
int16_t sue_rmat8; ///< Serial UDB Extra Rmat 8
uint16_t sue_cog; ///< Serial UDB Extra GPS Course Over Ground
int16_t sue_sog; ///< Serial UDB Extra Speed Over Ground
uint16_t sue_cpu_load; ///< Serial UDB Extra CPU Load
int16_t sue_voltage_milis; ///< Serial UDB Extra Voltage in MilliVolts
uint16_t sue_air_speed_3DIMU; ///< Serial UDB Extra 3D IMU Air Speed
int16_t sue_estimated_wind_0; ///< Serial UDB Extra Estimated Wind 0
int16_t sue_estimated_wind_1; ///< Serial UDB Extra Estimated Wind 1
int16_t sue_estimated_wind_2; ///< Serial UDB Extra Estimated Wind 2
int16_t sue_magFieldEarth0; ///< Serial UDB Extra Magnetic Field Earth 0
int16_t sue_magFieldEarth1; ///< Serial UDB Extra Magnetic Field Earth 1
int16_t sue_magFieldEarth2; ///< Serial UDB Extra Magnetic Field Earth 2
int16_t sue_svs; ///< Serial UDB Extra Number of Sattelites in View
int16_t sue_hdop; ///< Serial UDB Extra GPS Horizontal Dilution of Precision
uint8_t sue_status; ///< Serial UDB Extra Status
} mavlink_serial_udb_extra_f2_a_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN 63
#define MAVLINK_MSG_ID_170_LEN 63
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_A { \
"SERIAL_UDB_EXTRA_F2_A", \
28, \
{ { "sue_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_time) }, \
{ "sue_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_latitude) }, \
{ "sue_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_longitude) }, \
{ "sue_altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_altitude) }, \
{ "sue_waypoint_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_waypoint_index) }, \
{ "sue_rmat0", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat0) }, \
{ "sue_rmat1", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat1) }, \
{ "sue_rmat2", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat2) }, \
{ "sue_rmat3", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat3) }, \
{ "sue_rmat4", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat4) }, \
{ "sue_rmat5", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat5) }, \
{ "sue_rmat6", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat6) }, \
{ "sue_rmat7", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat7) }, \
{ "sue_rmat8", NULL, MAVLINK_TYPE_INT16_T, 0, 34, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat8) }, \
{ "sue_cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_cog) }, \
{ "sue_sog", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_sog) }, \
{ "sue_cpu_load", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_cpu_load) }, \
{ "sue_voltage_milis", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_voltage_milis) }, \
{ "sue_air_speed_3DIMU", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_air_speed_3DIMU) }, \
{ "sue_estimated_wind_0", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_0) }, \
{ "sue_estimated_wind_1", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_1) }, \
{ "sue_estimated_wind_2", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_2) }, \
{ "sue_magFieldEarth0", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth0) }, \
{ "sue_magFieldEarth1", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth1) }, \
{ "sue_magFieldEarth2", NULL, MAVLINK_TYPE_INT16_T, 0, 56, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth2) }, \
{ "sue_svs", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_svs) }, \
{ "sue_hdop", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_hdop) }, \
{ "sue_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_status) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f2_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 sue_time Serial UDB Extra Time
* @param sue_status Serial UDB Extra Status
* @param sue_latitude Serial UDB Extra Latitude
* @param sue_longitude Serial UDB Extra Longitude
* @param sue_altitude Serial UDB Extra Altitude
* @param sue_waypoint_index Serial UDB Extra Waypoint Index
* @param sue_rmat0 Serial UDB Extra Rmat 0
* @param sue_rmat1 Serial UDB Extra Rmat 1
* @param sue_rmat2 Serial UDB Extra Rmat 2
* @param sue_rmat3 Serial UDB Extra Rmat 3
* @param sue_rmat4 Serial UDB Extra Rmat 4
* @param sue_rmat5 Serial UDB Extra Rmat 5
* @param sue_rmat6 Serial UDB Extra Rmat 6
* @param sue_rmat7 Serial UDB Extra Rmat 7
* @param sue_rmat8 Serial UDB Extra Rmat 8
* @param sue_cog Serial UDB Extra GPS Course Over Ground
* @param sue_sog Serial UDB Extra Speed Over Ground
* @param sue_cpu_load Serial UDB Extra CPU Load
* @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts
* @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed
* @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0
* @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1
* @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2
* @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0
* @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1
* @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2
* @param sue_svs Serial UDB Extra Number of Sattelites in View
* @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[63];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_int32_t(buf, 4, sue_latitude);
_mav_put_int32_t(buf, 8, sue_longitude);
_mav_put_int32_t(buf, 12, sue_altitude);
_mav_put_uint16_t(buf, 16, sue_waypoint_index);
_mav_put_int16_t(buf, 18, sue_rmat0);
_mav_put_int16_t(buf, 20, sue_rmat1);
_mav_put_int16_t(buf, 22, sue_rmat2);
_mav_put_int16_t(buf, 24, sue_rmat3);
_mav_put_int16_t(buf, 26, sue_rmat4);
_mav_put_int16_t(buf, 28, sue_rmat5);
_mav_put_int16_t(buf, 30, sue_rmat6);
_mav_put_int16_t(buf, 32, sue_rmat7);
_mav_put_int16_t(buf, 34, sue_rmat8);
_mav_put_uint16_t(buf, 36, sue_cog);
_mav_put_int16_t(buf, 38, sue_sog);
_mav_put_uint16_t(buf, 40, sue_cpu_load);
_mav_put_int16_t(buf, 42, sue_voltage_milis);
_mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU);
_mav_put_int16_t(buf, 46, sue_estimated_wind_0);
_mav_put_int16_t(buf, 48, sue_estimated_wind_1);
_mav_put_int16_t(buf, 50, sue_estimated_wind_2);
_mav_put_int16_t(buf, 52, sue_magFieldEarth0);
_mav_put_int16_t(buf, 54, sue_magFieldEarth1);
_mav_put_int16_t(buf, 56, sue_magFieldEarth2);
_mav_put_int16_t(buf, 58, sue_svs);
_mav_put_int16_t(buf, 60, sue_hdop);
_mav_put_uint8_t(buf, 62, sue_status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 63);
#else
mavlink_serial_udb_extra_f2_a_t packet;
packet.sue_time = sue_time;
packet.sue_latitude = sue_latitude;
packet.sue_longitude = sue_longitude;
packet.sue_altitude = sue_altitude;
packet.sue_waypoint_index = sue_waypoint_index;
packet.sue_rmat0 = sue_rmat0;
packet.sue_rmat1 = sue_rmat1;
packet.sue_rmat2 = sue_rmat2;
packet.sue_rmat3 = sue_rmat3;
packet.sue_rmat4 = sue_rmat4;
packet.sue_rmat5 = sue_rmat5;
packet.sue_rmat6 = sue_rmat6;
packet.sue_rmat7 = sue_rmat7;
packet.sue_rmat8 = sue_rmat8;
packet.sue_cog = sue_cog;
packet.sue_sog = sue_sog;
packet.sue_cpu_load = sue_cpu_load;
packet.sue_voltage_milis = sue_voltage_milis;
packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU;
packet.sue_estimated_wind_0 = sue_estimated_wind_0;
packet.sue_estimated_wind_1 = sue_estimated_wind_1;
packet.sue_estimated_wind_2 = sue_estimated_wind_2;
packet.sue_magFieldEarth0 = sue_magFieldEarth0;
packet.sue_magFieldEarth1 = sue_magFieldEarth1;
packet.sue_magFieldEarth2 = sue_magFieldEarth2;
packet.sue_svs = sue_svs;
packet.sue_hdop = sue_hdop;
packet.sue_status = sue_status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 63);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A;
return mavlink_finalize_message(msg, system_id, component_id, 63, 150);
}
/**
* @brief Pack a serial_udb_extra_f2_a 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 sue_time Serial UDB Extra Time
* @param sue_status Serial UDB Extra Status
* @param sue_latitude Serial UDB Extra Latitude
* @param sue_longitude Serial UDB Extra Longitude
* @param sue_altitude Serial UDB Extra Altitude
* @param sue_waypoint_index Serial UDB Extra Waypoint Index
* @param sue_rmat0 Serial UDB Extra Rmat 0
* @param sue_rmat1 Serial UDB Extra Rmat 1
* @param sue_rmat2 Serial UDB Extra Rmat 2
* @param sue_rmat3 Serial UDB Extra Rmat 3
* @param sue_rmat4 Serial UDB Extra Rmat 4
* @param sue_rmat5 Serial UDB Extra Rmat 5
* @param sue_rmat6 Serial UDB Extra Rmat 6
* @param sue_rmat7 Serial UDB Extra Rmat 7
* @param sue_rmat8 Serial UDB Extra Rmat 8
* @param sue_cog Serial UDB Extra GPS Course Over Ground
* @param sue_sog Serial UDB Extra Speed Over Ground
* @param sue_cpu_load Serial UDB Extra CPU Load
* @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts
* @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed
* @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0
* @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1
* @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2
* @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0
* @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1
* @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2
* @param sue_svs Serial UDB Extra Number of Sattelites in View
* @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t sue_time,uint8_t sue_status,int32_t sue_latitude,int32_t sue_longitude,int32_t sue_altitude,uint16_t sue_waypoint_index,int16_t sue_rmat0,int16_t sue_rmat1,int16_t sue_rmat2,int16_t sue_rmat3,int16_t sue_rmat4,int16_t sue_rmat5,int16_t sue_rmat6,int16_t sue_rmat7,int16_t sue_rmat8,uint16_t sue_cog,int16_t sue_sog,uint16_t sue_cpu_load,int16_t sue_voltage_milis,uint16_t sue_air_speed_3DIMU,int16_t sue_estimated_wind_0,int16_t sue_estimated_wind_1,int16_t sue_estimated_wind_2,int16_t sue_magFieldEarth0,int16_t sue_magFieldEarth1,int16_t sue_magFieldEarth2,int16_t sue_svs,int16_t sue_hdop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[63];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_int32_t(buf, 4, sue_latitude);
_mav_put_int32_t(buf, 8, sue_longitude);
_mav_put_int32_t(buf, 12, sue_altitude);
_mav_put_uint16_t(buf, 16, sue_waypoint_index);
_mav_put_int16_t(buf, 18, sue_rmat0);
_mav_put_int16_t(buf, 20, sue_rmat1);
_mav_put_int16_t(buf, 22, sue_rmat2);
_mav_put_int16_t(buf, 24, sue_rmat3);
_mav_put_int16_t(buf, 26, sue_rmat4);
_mav_put_int16_t(buf, 28, sue_rmat5);
_mav_put_int16_t(buf, 30, sue_rmat6);
_mav_put_int16_t(buf, 32, sue_rmat7);
_mav_put_int16_t(buf, 34, sue_rmat8);
_mav_put_uint16_t(buf, 36, sue_cog);
_mav_put_int16_t(buf, 38, sue_sog);
_mav_put_uint16_t(buf, 40, sue_cpu_load);
_mav_put_int16_t(buf, 42, sue_voltage_milis);
_mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU);
_mav_put_int16_t(buf, 46, sue_estimated_wind_0);
_mav_put_int16_t(buf, 48, sue_estimated_wind_1);
_mav_put_int16_t(buf, 50, sue_estimated_wind_2);
_mav_put_int16_t(buf, 52, sue_magFieldEarth0);
_mav_put_int16_t(buf, 54, sue_magFieldEarth1);
_mav_put_int16_t(buf, 56, sue_magFieldEarth2);
_mav_put_int16_t(buf, 58, sue_svs);
_mav_put_int16_t(buf, 60, sue_hdop);
_mav_put_uint8_t(buf, 62, sue_status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 63);
#else
mavlink_serial_udb_extra_f2_a_t packet;
packet.sue_time = sue_time;
packet.sue_latitude = sue_latitude;
packet.sue_longitude = sue_longitude;
packet.sue_altitude = sue_altitude;
packet.sue_waypoint_index = sue_waypoint_index;
packet.sue_rmat0 = sue_rmat0;
packet.sue_rmat1 = sue_rmat1;
packet.sue_rmat2 = sue_rmat2;
packet.sue_rmat3 = sue_rmat3;
packet.sue_rmat4 = sue_rmat4;
packet.sue_rmat5 = sue_rmat5;
packet.sue_rmat6 = sue_rmat6;
packet.sue_rmat7 = sue_rmat7;
packet.sue_rmat8 = sue_rmat8;
packet.sue_cog = sue_cog;
packet.sue_sog = sue_sog;
packet.sue_cpu_load = sue_cpu_load;
packet.sue_voltage_milis = sue_voltage_milis;
packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU;
packet.sue_estimated_wind_0 = sue_estimated_wind_0;
packet.sue_estimated_wind_1 = sue_estimated_wind_1;
packet.sue_estimated_wind_2 = sue_estimated_wind_2;
packet.sue_magFieldEarth0 = sue_magFieldEarth0;
packet.sue_magFieldEarth1 = sue_magFieldEarth1;
packet.sue_magFieldEarth2 = sue_magFieldEarth2;
packet.sue_svs = sue_svs;
packet.sue_hdop = sue_hdop;
packet.sue_status = sue_status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 63);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 63, 150);
}
/**
* @brief Encode a serial_udb_extra_f2_a 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 serial_udb_extra_f2_a C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a)
{
return mavlink_msg_serial_udb_extra_f2_a_pack(system_id, component_id, msg, serial_udb_extra_f2_a->sue_time, serial_udb_extra_f2_a->sue_status, serial_udb_extra_f2_a->sue_latitude, serial_udb_extra_f2_a->sue_longitude, serial_udb_extra_f2_a->sue_altitude, serial_udb_extra_f2_a->sue_waypoint_index, serial_udb_extra_f2_a->sue_rmat0, serial_udb_extra_f2_a->sue_rmat1, serial_udb_extra_f2_a->sue_rmat2, serial_udb_extra_f2_a->sue_rmat3, serial_udb_extra_f2_a->sue_rmat4, serial_udb_extra_f2_a->sue_rmat5, serial_udb_extra_f2_a->sue_rmat6, serial_udb_extra_f2_a->sue_rmat7, serial_udb_extra_f2_a->sue_rmat8, serial_udb_extra_f2_a->sue_cog, serial_udb_extra_f2_a->sue_sog, serial_udb_extra_f2_a->sue_cpu_load, serial_udb_extra_f2_a->sue_voltage_milis, serial_udb_extra_f2_a->sue_air_speed_3DIMU, serial_udb_extra_f2_a->sue_estimated_wind_0, serial_udb_extra_f2_a->sue_estimated_wind_1, serial_udb_extra_f2_a->sue_estimated_wind_2, serial_udb_extra_f2_a->sue_magFieldEarth0, serial_udb_extra_f2_a->sue_magFieldEarth1, serial_udb_extra_f2_a->sue_magFieldEarth2, serial_udb_extra_f2_a->sue_svs, serial_udb_extra_f2_a->sue_hdop);
}
/**
* @brief Send a serial_udb_extra_f2_a message
* @param chan MAVLink channel to send the message
*
* @param sue_time Serial UDB Extra Time
* @param sue_status Serial UDB Extra Status
* @param sue_latitude Serial UDB Extra Latitude
* @param sue_longitude Serial UDB Extra Longitude
* @param sue_altitude Serial UDB Extra Altitude
* @param sue_waypoint_index Serial UDB Extra Waypoint Index
* @param sue_rmat0 Serial UDB Extra Rmat 0
* @param sue_rmat1 Serial UDB Extra Rmat 1
* @param sue_rmat2 Serial UDB Extra Rmat 2
* @param sue_rmat3 Serial UDB Extra Rmat 3
* @param sue_rmat4 Serial UDB Extra Rmat 4
* @param sue_rmat5 Serial UDB Extra Rmat 5
* @param sue_rmat6 Serial UDB Extra Rmat 6
* @param sue_rmat7 Serial UDB Extra Rmat 7
* @param sue_rmat8 Serial UDB Extra Rmat 8
* @param sue_cog Serial UDB Extra GPS Course Over Ground
* @param sue_sog Serial UDB Extra Speed Over Ground
* @param sue_cpu_load Serial UDB Extra CPU Load
* @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts
* @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed
* @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0
* @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1
* @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2
* @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0
* @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1
* @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2
* @param sue_svs Serial UDB Extra Number of Sattelites in View
* @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[63];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_int32_t(buf, 4, sue_latitude);
_mav_put_int32_t(buf, 8, sue_longitude);
_mav_put_int32_t(buf, 12, sue_altitude);
_mav_put_uint16_t(buf, 16, sue_waypoint_index);
_mav_put_int16_t(buf, 18, sue_rmat0);
_mav_put_int16_t(buf, 20, sue_rmat1);
_mav_put_int16_t(buf, 22, sue_rmat2);
_mav_put_int16_t(buf, 24, sue_rmat3);
_mav_put_int16_t(buf, 26, sue_rmat4);
_mav_put_int16_t(buf, 28, sue_rmat5);
_mav_put_int16_t(buf, 30, sue_rmat6);
_mav_put_int16_t(buf, 32, sue_rmat7);
_mav_put_int16_t(buf, 34, sue_rmat8);
_mav_put_uint16_t(buf, 36, sue_cog);
_mav_put_int16_t(buf, 38, sue_sog);
_mav_put_uint16_t(buf, 40, sue_cpu_load);
_mav_put_int16_t(buf, 42, sue_voltage_milis);
_mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU);
_mav_put_int16_t(buf, 46, sue_estimated_wind_0);
_mav_put_int16_t(buf, 48, sue_estimated_wind_1);
_mav_put_int16_t(buf, 50, sue_estimated_wind_2);
_mav_put_int16_t(buf, 52, sue_magFieldEarth0);
_mav_put_int16_t(buf, 54, sue_magFieldEarth1);
_mav_put_int16_t(buf, 56, sue_magFieldEarth2);
_mav_put_int16_t(buf, 58, sue_svs);
_mav_put_int16_t(buf, 60, sue_hdop);
_mav_put_uint8_t(buf, 62, sue_status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, 63, 150);
#else
mavlink_serial_udb_extra_f2_a_t packet;
packet.sue_time = sue_time;
packet.sue_latitude = sue_latitude;
packet.sue_longitude = sue_longitude;
packet.sue_altitude = sue_altitude;
packet.sue_waypoint_index = sue_waypoint_index;
packet.sue_rmat0 = sue_rmat0;
packet.sue_rmat1 = sue_rmat1;
packet.sue_rmat2 = sue_rmat2;
packet.sue_rmat3 = sue_rmat3;
packet.sue_rmat4 = sue_rmat4;
packet.sue_rmat5 = sue_rmat5;
packet.sue_rmat6 = sue_rmat6;
packet.sue_rmat7 = sue_rmat7;
packet.sue_rmat8 = sue_rmat8;
packet.sue_cog = sue_cog;
packet.sue_sog = sue_sog;
packet.sue_cpu_load = sue_cpu_load;
packet.sue_voltage_milis = sue_voltage_milis;
packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU;
packet.sue_estimated_wind_0 = sue_estimated_wind_0;
packet.sue_estimated_wind_1 = sue_estimated_wind_1;
packet.sue_estimated_wind_2 = sue_estimated_wind_2;
packet.sue_magFieldEarth0 = sue_magFieldEarth0;
packet.sue_magFieldEarth1 = sue_magFieldEarth1;
packet.sue_magFieldEarth2 = sue_magFieldEarth2;
packet.sue_svs = sue_svs;
packet.sue_hdop = sue_hdop;
packet.sue_status = sue_status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, 63, 150);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F2_A UNPACKING
/**
* @brief Get field sue_time from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Time
*/
static inline uint32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field sue_status from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Status
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f2_a_get_sue_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 62);
}
/**
* @brief Get field sue_latitude from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Latitude
*/
static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field sue_longitude from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Longitude
*/
static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field sue_altitude from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Altitude
*/
static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field sue_waypoint_index from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Waypoint Index
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_waypoint_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field sue_rmat0 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 0
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat0(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
/**
* @brief Get field sue_rmat1 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 1
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
/**
* @brief Get field sue_rmat2 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 2
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
/**
* @brief Get field sue_rmat3 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 3
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat3(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
/**
* @brief Get field sue_rmat4 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 4
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat4(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 26);
}
/**
* @brief Get field sue_rmat5 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 5
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat5(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 28);
}
/**
* @brief Get field sue_rmat6 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 6
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat6(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 30);
}
/**
* @brief Get field sue_rmat7 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 7
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat7(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 32);
}
/**
* @brief Get field sue_rmat8 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Rmat 8
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat8(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 34);
}
/**
* @brief Get field sue_cog from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra GPS Course Over Ground
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_cog(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 36);
}
/**
* @brief Get field sue_sog from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Speed Over Ground
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_sog(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 38);
}
/**
* @brief Get field sue_cpu_load from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra CPU Load
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_cpu_load(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 40);
}
/**
* @brief Get field sue_voltage_milis from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Voltage in MilliVolts
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_voltage_milis(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 42);
}
/**
* @brief Get field sue_air_speed_3DIMU from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra 3D IMU Air Speed
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_air_speed_3DIMU(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 44);
}
/**
* @brief Get field sue_estimated_wind_0 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Estimated Wind 0
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_0(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 46);
}
/**
* @brief Get field sue_estimated_wind_1 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Estimated Wind 1
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 48);
}
/**
* @brief Get field sue_estimated_wind_2 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Estimated Wind 2
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 50);
}
/**
* @brief Get field sue_magFieldEarth0 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Magnetic Field Earth 0
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth0(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 52);
}
/**
* @brief Get field sue_magFieldEarth1 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Magnetic Field Earth 1
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 54);
}
/**
* @brief Get field sue_magFieldEarth2 from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Magnetic Field Earth 2
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 56);
}
/**
* @brief Get field sue_svs from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra Number of Sattelites in View
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_svs(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 58);
}
/**
* @brief Get field sue_hdop from serial_udb_extra_f2_a message
*
* @return Serial UDB Extra GPS Horizontal Dilution of Precision
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_hdop(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 60);
}
/**
* @brief Decode a serial_udb_extra_f2_a message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f2_a C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f2_a_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f2_a->sue_time = mavlink_msg_serial_udb_extra_f2_a_get_sue_time(msg);
serial_udb_extra_f2_a->sue_latitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_latitude(msg);
serial_udb_extra_f2_a->sue_longitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_longitude(msg);
serial_udb_extra_f2_a->sue_altitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_altitude(msg);
serial_udb_extra_f2_a->sue_waypoint_index = mavlink_msg_serial_udb_extra_f2_a_get_sue_waypoint_index(msg);
serial_udb_extra_f2_a->sue_rmat0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat0(msg);
serial_udb_extra_f2_a->sue_rmat1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat1(msg);
serial_udb_extra_f2_a->sue_rmat2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat2(msg);
serial_udb_extra_f2_a->sue_rmat3 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat3(msg);
serial_udb_extra_f2_a->sue_rmat4 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat4(msg);
serial_udb_extra_f2_a->sue_rmat5 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat5(msg);
serial_udb_extra_f2_a->sue_rmat6 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat6(msg);
serial_udb_extra_f2_a->sue_rmat7 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat7(msg);
serial_udb_extra_f2_a->sue_rmat8 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat8(msg);
serial_udb_extra_f2_a->sue_cog = mavlink_msg_serial_udb_extra_f2_a_get_sue_cog(msg);
serial_udb_extra_f2_a->sue_sog = mavlink_msg_serial_udb_extra_f2_a_get_sue_sog(msg);
serial_udb_extra_f2_a->sue_cpu_load = mavlink_msg_serial_udb_extra_f2_a_get_sue_cpu_load(msg);
serial_udb_extra_f2_a->sue_voltage_milis = mavlink_msg_serial_udb_extra_f2_a_get_sue_voltage_milis(msg);
serial_udb_extra_f2_a->sue_air_speed_3DIMU = mavlink_msg_serial_udb_extra_f2_a_get_sue_air_speed_3DIMU(msg);
serial_udb_extra_f2_a->sue_estimated_wind_0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_0(msg);
serial_udb_extra_f2_a->sue_estimated_wind_1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_1(msg);
serial_udb_extra_f2_a->sue_estimated_wind_2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_2(msg);
serial_udb_extra_f2_a->sue_magFieldEarth0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth0(msg);
serial_udb_extra_f2_a->sue_magFieldEarth1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth1(msg);
serial_udb_extra_f2_a->sue_magFieldEarth2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth2(msg);
serial_udb_extra_f2_a->sue_svs = mavlink_msg_serial_udb_extra_f2_a_get_sue_svs(msg);
serial_udb_extra_f2_a->sue_hdop = mavlink_msg_serial_udb_extra_f2_a_get_sue_hdop(msg);
serial_udb_extra_f2_a->sue_status = mavlink_msg_serial_udb_extra_f2_a_get_sue_status(msg);
#else
memcpy(serial_udb_extra_f2_a, _MAV_PAYLOAD(msg), 63);
#endif
}

View File

@@ -0,0 +1,848 @@
// MESSAGE SERIAL_UDB_EXTRA_F2_B PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B 171
typedef struct __mavlink_serial_udb_extra_f2_b_t
{
uint32_t sue_time; ///< Serial UDB Extra Time
uint32_t sue_flags; ///< Serial UDB Extra Status Flags
int16_t sue_pwm_input_1; ///< Serial UDB Extra PWM Input Channel 1
int16_t sue_pwm_input_2; ///< Serial UDB Extra PWM Input Channel 2
int16_t sue_pwm_input_3; ///< Serial UDB Extra PWM Input Channel 3
int16_t sue_pwm_input_4; ///< Serial UDB Extra PWM Input Channel 4
int16_t sue_pwm_input_5; ///< Serial UDB Extra PWM Input Channel 5
int16_t sue_pwm_input_6; ///< Serial UDB Extra PWM Input Channel 6
int16_t sue_pwm_input_7; ///< Serial UDB Extra PWM Input Channel 7
int16_t sue_pwm_input_8; ///< Serial UDB Extra PWM Input Channel 8
int16_t sue_pwm_input_9; ///< Serial UDB Extra PWM Input Channel 9
int16_t sue_pwm_input_10; ///< Serial UDB Extra PWM Input Channel 10
int16_t sue_pwm_output_1; ///< Serial UDB Extra PWM Output Channel 1
int16_t sue_pwm_output_2; ///< Serial UDB Extra PWM Output Channel 2
int16_t sue_pwm_output_3; ///< Serial UDB Extra PWM Output Channel 3
int16_t sue_pwm_output_4; ///< Serial UDB Extra PWM Output Channel 4
int16_t sue_pwm_output_5; ///< Serial UDB Extra PWM Output Channel 5
int16_t sue_pwm_output_6; ///< Serial UDB Extra PWM Output Channel 6
int16_t sue_pwm_output_7; ///< Serial UDB Extra PWM Output Channel 7
int16_t sue_pwm_output_8; ///< Serial UDB Extra PWM Output Channel 8
int16_t sue_pwm_output_9; ///< Serial UDB Extra PWM Output Channel 9
int16_t sue_pwm_output_10; ///< Serial UDB Extra PWM Output Channel 10
int16_t sue_imu_location_x; ///< Serial UDB Extra IMU Location X
int16_t sue_imu_location_y; ///< Serial UDB Extra IMU Location Y
int16_t sue_imu_location_z; ///< Serial UDB Extra IMU Location Z
int16_t sue_osc_fails; ///< Serial UDB Extra Oscillator Failure Count
int16_t sue_imu_velocity_x; ///< Serial UDB Extra IMU Velocity X
int16_t sue_imu_velocity_y; ///< Serial UDB Extra IMU Velocity Y
int16_t sue_imu_velocity_z; ///< Serial UDB Extra IMU Velocity Z
int16_t sue_waypoint_goal_x; ///< Serial UDB Extra Current Waypoint Goal X
int16_t sue_waypoint_goal_y; ///< Serial UDB Extra Current Waypoint Goal Y
int16_t sue_waypoint_goal_z; ///< Serial UDB Extra Current Waypoint Goal Z
int16_t sue_memory_stack_free; ///< Serial UDB Extra Stack Memory Free
} mavlink_serial_udb_extra_f2_b_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN 70
#define MAVLINK_MSG_ID_171_LEN 70
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_B { \
"SERIAL_UDB_EXTRA_F2_B", \
33, \
{ { "sue_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_time) }, \
{ "sue_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_flags) }, \
{ "sue_pwm_input_1", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_1) }, \
{ "sue_pwm_input_2", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_2) }, \
{ "sue_pwm_input_3", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_3) }, \
{ "sue_pwm_input_4", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_4) }, \
{ "sue_pwm_input_5", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_5) }, \
{ "sue_pwm_input_6", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_6) }, \
{ "sue_pwm_input_7", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_7) }, \
{ "sue_pwm_input_8", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_8) }, \
{ "sue_pwm_input_9", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_9) }, \
{ "sue_pwm_input_10", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_10) }, \
{ "sue_pwm_output_1", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_1) }, \
{ "sue_pwm_output_2", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_2) }, \
{ "sue_pwm_output_3", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_3) }, \
{ "sue_pwm_output_4", NULL, MAVLINK_TYPE_INT16_T, 0, 34, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_4) }, \
{ "sue_pwm_output_5", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_5) }, \
{ "sue_pwm_output_6", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_6) }, \
{ "sue_pwm_output_7", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_7) }, \
{ "sue_pwm_output_8", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_8) }, \
{ "sue_pwm_output_9", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_9) }, \
{ "sue_pwm_output_10", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_10) }, \
{ "sue_imu_location_x", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_x) }, \
{ "sue_imu_location_y", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_y) }, \
{ "sue_imu_location_z", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_z) }, \
{ "sue_osc_fails", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_osc_fails) }, \
{ "sue_imu_velocity_x", NULL, MAVLINK_TYPE_INT16_T, 0, 56, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_x) }, \
{ "sue_imu_velocity_y", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_y) }, \
{ "sue_imu_velocity_z", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_z) }, \
{ "sue_waypoint_goal_x", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_x) }, \
{ "sue_waypoint_goal_y", NULL, MAVLINK_TYPE_INT16_T, 0, 64, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_y) }, \
{ "sue_waypoint_goal_z", NULL, MAVLINK_TYPE_INT16_T, 0, 66, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_z) }, \
{ "sue_memory_stack_free", NULL, MAVLINK_TYPE_INT16_T, 0, 68, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_memory_stack_free) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f2_b 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 sue_time Serial UDB Extra Time
* @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1
* @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2
* @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3
* @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4
* @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5
* @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6
* @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7
* @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8
* @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9
* @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10
* @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1
* @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2
* @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3
* @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4
* @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5
* @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6
* @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7
* @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8
* @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9
* @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10
* @param sue_imu_location_x Serial UDB Extra IMU Location X
* @param sue_imu_location_y Serial UDB Extra IMU Location Y
* @param sue_imu_location_z Serial UDB Extra IMU Location Z
* @param sue_flags Serial UDB Extra Status Flags
* @param sue_osc_fails Serial UDB Extra Oscillator Failure Count
* @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X
* @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y
* @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z
* @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X
* @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y
* @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z
* @param sue_memory_stack_free Serial UDB Extra Stack Memory Free
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[70];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_uint32_t(buf, 4, sue_flags);
_mav_put_int16_t(buf, 8, sue_pwm_input_1);
_mav_put_int16_t(buf, 10, sue_pwm_input_2);
_mav_put_int16_t(buf, 12, sue_pwm_input_3);
_mav_put_int16_t(buf, 14, sue_pwm_input_4);
_mav_put_int16_t(buf, 16, sue_pwm_input_5);
_mav_put_int16_t(buf, 18, sue_pwm_input_6);
_mav_put_int16_t(buf, 20, sue_pwm_input_7);
_mav_put_int16_t(buf, 22, sue_pwm_input_8);
_mav_put_int16_t(buf, 24, sue_pwm_input_9);
_mav_put_int16_t(buf, 26, sue_pwm_input_10);
_mav_put_int16_t(buf, 28, sue_pwm_output_1);
_mav_put_int16_t(buf, 30, sue_pwm_output_2);
_mav_put_int16_t(buf, 32, sue_pwm_output_3);
_mav_put_int16_t(buf, 34, sue_pwm_output_4);
_mav_put_int16_t(buf, 36, sue_pwm_output_5);
_mav_put_int16_t(buf, 38, sue_pwm_output_6);
_mav_put_int16_t(buf, 40, sue_pwm_output_7);
_mav_put_int16_t(buf, 42, sue_pwm_output_8);
_mav_put_int16_t(buf, 44, sue_pwm_output_9);
_mav_put_int16_t(buf, 46, sue_pwm_output_10);
_mav_put_int16_t(buf, 48, sue_imu_location_x);
_mav_put_int16_t(buf, 50, sue_imu_location_y);
_mav_put_int16_t(buf, 52, sue_imu_location_z);
_mav_put_int16_t(buf, 54, sue_osc_fails);
_mav_put_int16_t(buf, 56, sue_imu_velocity_x);
_mav_put_int16_t(buf, 58, sue_imu_velocity_y);
_mav_put_int16_t(buf, 60, sue_imu_velocity_z);
_mav_put_int16_t(buf, 62, sue_waypoint_goal_x);
_mav_put_int16_t(buf, 64, sue_waypoint_goal_y);
_mav_put_int16_t(buf, 66, sue_waypoint_goal_z);
_mav_put_int16_t(buf, 68, sue_memory_stack_free);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 70);
#else
mavlink_serial_udb_extra_f2_b_t packet;
packet.sue_time = sue_time;
packet.sue_flags = sue_flags;
packet.sue_pwm_input_1 = sue_pwm_input_1;
packet.sue_pwm_input_2 = sue_pwm_input_2;
packet.sue_pwm_input_3 = sue_pwm_input_3;
packet.sue_pwm_input_4 = sue_pwm_input_4;
packet.sue_pwm_input_5 = sue_pwm_input_5;
packet.sue_pwm_input_6 = sue_pwm_input_6;
packet.sue_pwm_input_7 = sue_pwm_input_7;
packet.sue_pwm_input_8 = sue_pwm_input_8;
packet.sue_pwm_input_9 = sue_pwm_input_9;
packet.sue_pwm_input_10 = sue_pwm_input_10;
packet.sue_pwm_output_1 = sue_pwm_output_1;
packet.sue_pwm_output_2 = sue_pwm_output_2;
packet.sue_pwm_output_3 = sue_pwm_output_3;
packet.sue_pwm_output_4 = sue_pwm_output_4;
packet.sue_pwm_output_5 = sue_pwm_output_5;
packet.sue_pwm_output_6 = sue_pwm_output_6;
packet.sue_pwm_output_7 = sue_pwm_output_7;
packet.sue_pwm_output_8 = sue_pwm_output_8;
packet.sue_pwm_output_9 = sue_pwm_output_9;
packet.sue_pwm_output_10 = sue_pwm_output_10;
packet.sue_imu_location_x = sue_imu_location_x;
packet.sue_imu_location_y = sue_imu_location_y;
packet.sue_imu_location_z = sue_imu_location_z;
packet.sue_osc_fails = sue_osc_fails;
packet.sue_imu_velocity_x = sue_imu_velocity_x;
packet.sue_imu_velocity_y = sue_imu_velocity_y;
packet.sue_imu_velocity_z = sue_imu_velocity_z;
packet.sue_waypoint_goal_x = sue_waypoint_goal_x;
packet.sue_waypoint_goal_y = sue_waypoint_goal_y;
packet.sue_waypoint_goal_z = sue_waypoint_goal_z;
packet.sue_memory_stack_free = sue_memory_stack_free;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 70);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B;
return mavlink_finalize_message(msg, system_id, component_id, 70, 169);
}
/**
* @brief Pack a serial_udb_extra_f2_b 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 sue_time Serial UDB Extra Time
* @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1
* @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2
* @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3
* @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4
* @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5
* @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6
* @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7
* @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8
* @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9
* @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10
* @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1
* @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2
* @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3
* @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4
* @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5
* @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6
* @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7
* @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8
* @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9
* @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10
* @param sue_imu_location_x Serial UDB Extra IMU Location X
* @param sue_imu_location_y Serial UDB Extra IMU Location Y
* @param sue_imu_location_z Serial UDB Extra IMU Location Z
* @param sue_flags Serial UDB Extra Status Flags
* @param sue_osc_fails Serial UDB Extra Oscillator Failure Count
* @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X
* @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y
* @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z
* @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X
* @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y
* @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z
* @param sue_memory_stack_free Serial UDB Extra Stack Memory Free
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t sue_time,int16_t sue_pwm_input_1,int16_t sue_pwm_input_2,int16_t sue_pwm_input_3,int16_t sue_pwm_input_4,int16_t sue_pwm_input_5,int16_t sue_pwm_input_6,int16_t sue_pwm_input_7,int16_t sue_pwm_input_8,int16_t sue_pwm_input_9,int16_t sue_pwm_input_10,int16_t sue_pwm_output_1,int16_t sue_pwm_output_2,int16_t sue_pwm_output_3,int16_t sue_pwm_output_4,int16_t sue_pwm_output_5,int16_t sue_pwm_output_6,int16_t sue_pwm_output_7,int16_t sue_pwm_output_8,int16_t sue_pwm_output_9,int16_t sue_pwm_output_10,int16_t sue_imu_location_x,int16_t sue_imu_location_y,int16_t sue_imu_location_z,uint32_t sue_flags,int16_t sue_osc_fails,int16_t sue_imu_velocity_x,int16_t sue_imu_velocity_y,int16_t sue_imu_velocity_z,int16_t sue_waypoint_goal_x,int16_t sue_waypoint_goal_y,int16_t sue_waypoint_goal_z,int16_t sue_memory_stack_free)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[70];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_uint32_t(buf, 4, sue_flags);
_mav_put_int16_t(buf, 8, sue_pwm_input_1);
_mav_put_int16_t(buf, 10, sue_pwm_input_2);
_mav_put_int16_t(buf, 12, sue_pwm_input_3);
_mav_put_int16_t(buf, 14, sue_pwm_input_4);
_mav_put_int16_t(buf, 16, sue_pwm_input_5);
_mav_put_int16_t(buf, 18, sue_pwm_input_6);
_mav_put_int16_t(buf, 20, sue_pwm_input_7);
_mav_put_int16_t(buf, 22, sue_pwm_input_8);
_mav_put_int16_t(buf, 24, sue_pwm_input_9);
_mav_put_int16_t(buf, 26, sue_pwm_input_10);
_mav_put_int16_t(buf, 28, sue_pwm_output_1);
_mav_put_int16_t(buf, 30, sue_pwm_output_2);
_mav_put_int16_t(buf, 32, sue_pwm_output_3);
_mav_put_int16_t(buf, 34, sue_pwm_output_4);
_mav_put_int16_t(buf, 36, sue_pwm_output_5);
_mav_put_int16_t(buf, 38, sue_pwm_output_6);
_mav_put_int16_t(buf, 40, sue_pwm_output_7);
_mav_put_int16_t(buf, 42, sue_pwm_output_8);
_mav_put_int16_t(buf, 44, sue_pwm_output_9);
_mav_put_int16_t(buf, 46, sue_pwm_output_10);
_mav_put_int16_t(buf, 48, sue_imu_location_x);
_mav_put_int16_t(buf, 50, sue_imu_location_y);
_mav_put_int16_t(buf, 52, sue_imu_location_z);
_mav_put_int16_t(buf, 54, sue_osc_fails);
_mav_put_int16_t(buf, 56, sue_imu_velocity_x);
_mav_put_int16_t(buf, 58, sue_imu_velocity_y);
_mav_put_int16_t(buf, 60, sue_imu_velocity_z);
_mav_put_int16_t(buf, 62, sue_waypoint_goal_x);
_mav_put_int16_t(buf, 64, sue_waypoint_goal_y);
_mav_put_int16_t(buf, 66, sue_waypoint_goal_z);
_mav_put_int16_t(buf, 68, sue_memory_stack_free);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 70);
#else
mavlink_serial_udb_extra_f2_b_t packet;
packet.sue_time = sue_time;
packet.sue_flags = sue_flags;
packet.sue_pwm_input_1 = sue_pwm_input_1;
packet.sue_pwm_input_2 = sue_pwm_input_2;
packet.sue_pwm_input_3 = sue_pwm_input_3;
packet.sue_pwm_input_4 = sue_pwm_input_4;
packet.sue_pwm_input_5 = sue_pwm_input_5;
packet.sue_pwm_input_6 = sue_pwm_input_6;
packet.sue_pwm_input_7 = sue_pwm_input_7;
packet.sue_pwm_input_8 = sue_pwm_input_8;
packet.sue_pwm_input_9 = sue_pwm_input_9;
packet.sue_pwm_input_10 = sue_pwm_input_10;
packet.sue_pwm_output_1 = sue_pwm_output_1;
packet.sue_pwm_output_2 = sue_pwm_output_2;
packet.sue_pwm_output_3 = sue_pwm_output_3;
packet.sue_pwm_output_4 = sue_pwm_output_4;
packet.sue_pwm_output_5 = sue_pwm_output_5;
packet.sue_pwm_output_6 = sue_pwm_output_6;
packet.sue_pwm_output_7 = sue_pwm_output_7;
packet.sue_pwm_output_8 = sue_pwm_output_8;
packet.sue_pwm_output_9 = sue_pwm_output_9;
packet.sue_pwm_output_10 = sue_pwm_output_10;
packet.sue_imu_location_x = sue_imu_location_x;
packet.sue_imu_location_y = sue_imu_location_y;
packet.sue_imu_location_z = sue_imu_location_z;
packet.sue_osc_fails = sue_osc_fails;
packet.sue_imu_velocity_x = sue_imu_velocity_x;
packet.sue_imu_velocity_y = sue_imu_velocity_y;
packet.sue_imu_velocity_z = sue_imu_velocity_z;
packet.sue_waypoint_goal_x = sue_waypoint_goal_x;
packet.sue_waypoint_goal_y = sue_waypoint_goal_y;
packet.sue_waypoint_goal_z = sue_waypoint_goal_z;
packet.sue_memory_stack_free = sue_memory_stack_free;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 70);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 70, 169);
}
/**
* @brief Encode a serial_udb_extra_f2_b 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 serial_udb_extra_f2_b C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b)
{
return mavlink_msg_serial_udb_extra_f2_b_pack(system_id, component_id, msg, serial_udb_extra_f2_b->sue_time, serial_udb_extra_f2_b->sue_pwm_input_1, serial_udb_extra_f2_b->sue_pwm_input_2, serial_udb_extra_f2_b->sue_pwm_input_3, serial_udb_extra_f2_b->sue_pwm_input_4, serial_udb_extra_f2_b->sue_pwm_input_5, serial_udb_extra_f2_b->sue_pwm_input_6, serial_udb_extra_f2_b->sue_pwm_input_7, serial_udb_extra_f2_b->sue_pwm_input_8, serial_udb_extra_f2_b->sue_pwm_input_9, serial_udb_extra_f2_b->sue_pwm_input_10, serial_udb_extra_f2_b->sue_pwm_output_1, serial_udb_extra_f2_b->sue_pwm_output_2, serial_udb_extra_f2_b->sue_pwm_output_3, serial_udb_extra_f2_b->sue_pwm_output_4, serial_udb_extra_f2_b->sue_pwm_output_5, serial_udb_extra_f2_b->sue_pwm_output_6, serial_udb_extra_f2_b->sue_pwm_output_7, serial_udb_extra_f2_b->sue_pwm_output_8, serial_udb_extra_f2_b->sue_pwm_output_9, serial_udb_extra_f2_b->sue_pwm_output_10, serial_udb_extra_f2_b->sue_imu_location_x, serial_udb_extra_f2_b->sue_imu_location_y, serial_udb_extra_f2_b->sue_imu_location_z, serial_udb_extra_f2_b->sue_flags, serial_udb_extra_f2_b->sue_osc_fails, serial_udb_extra_f2_b->sue_imu_velocity_x, serial_udb_extra_f2_b->sue_imu_velocity_y, serial_udb_extra_f2_b->sue_imu_velocity_z, serial_udb_extra_f2_b->sue_waypoint_goal_x, serial_udb_extra_f2_b->sue_waypoint_goal_y, serial_udb_extra_f2_b->sue_waypoint_goal_z, serial_udb_extra_f2_b->sue_memory_stack_free);
}
/**
* @brief Send a serial_udb_extra_f2_b message
* @param chan MAVLink channel to send the message
*
* @param sue_time Serial UDB Extra Time
* @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1
* @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2
* @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3
* @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4
* @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5
* @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6
* @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7
* @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8
* @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9
* @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10
* @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1
* @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2
* @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3
* @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4
* @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5
* @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6
* @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7
* @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8
* @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9
* @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10
* @param sue_imu_location_x Serial UDB Extra IMU Location X
* @param sue_imu_location_y Serial UDB Extra IMU Location Y
* @param sue_imu_location_z Serial UDB Extra IMU Location Z
* @param sue_flags Serial UDB Extra Status Flags
* @param sue_osc_fails Serial UDB Extra Oscillator Failure Count
* @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X
* @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y
* @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z
* @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X
* @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y
* @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z
* @param sue_memory_stack_free Serial UDB Extra Stack Memory Free
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[70];
_mav_put_uint32_t(buf, 0, sue_time);
_mav_put_uint32_t(buf, 4, sue_flags);
_mav_put_int16_t(buf, 8, sue_pwm_input_1);
_mav_put_int16_t(buf, 10, sue_pwm_input_2);
_mav_put_int16_t(buf, 12, sue_pwm_input_3);
_mav_put_int16_t(buf, 14, sue_pwm_input_4);
_mav_put_int16_t(buf, 16, sue_pwm_input_5);
_mav_put_int16_t(buf, 18, sue_pwm_input_6);
_mav_put_int16_t(buf, 20, sue_pwm_input_7);
_mav_put_int16_t(buf, 22, sue_pwm_input_8);
_mav_put_int16_t(buf, 24, sue_pwm_input_9);
_mav_put_int16_t(buf, 26, sue_pwm_input_10);
_mav_put_int16_t(buf, 28, sue_pwm_output_1);
_mav_put_int16_t(buf, 30, sue_pwm_output_2);
_mav_put_int16_t(buf, 32, sue_pwm_output_3);
_mav_put_int16_t(buf, 34, sue_pwm_output_4);
_mav_put_int16_t(buf, 36, sue_pwm_output_5);
_mav_put_int16_t(buf, 38, sue_pwm_output_6);
_mav_put_int16_t(buf, 40, sue_pwm_output_7);
_mav_put_int16_t(buf, 42, sue_pwm_output_8);
_mav_put_int16_t(buf, 44, sue_pwm_output_9);
_mav_put_int16_t(buf, 46, sue_pwm_output_10);
_mav_put_int16_t(buf, 48, sue_imu_location_x);
_mav_put_int16_t(buf, 50, sue_imu_location_y);
_mav_put_int16_t(buf, 52, sue_imu_location_z);
_mav_put_int16_t(buf, 54, sue_osc_fails);
_mav_put_int16_t(buf, 56, sue_imu_velocity_x);
_mav_put_int16_t(buf, 58, sue_imu_velocity_y);
_mav_put_int16_t(buf, 60, sue_imu_velocity_z);
_mav_put_int16_t(buf, 62, sue_waypoint_goal_x);
_mav_put_int16_t(buf, 64, sue_waypoint_goal_y);
_mav_put_int16_t(buf, 66, sue_waypoint_goal_z);
_mav_put_int16_t(buf, 68, sue_memory_stack_free);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, 70, 169);
#else
mavlink_serial_udb_extra_f2_b_t packet;
packet.sue_time = sue_time;
packet.sue_flags = sue_flags;
packet.sue_pwm_input_1 = sue_pwm_input_1;
packet.sue_pwm_input_2 = sue_pwm_input_2;
packet.sue_pwm_input_3 = sue_pwm_input_3;
packet.sue_pwm_input_4 = sue_pwm_input_4;
packet.sue_pwm_input_5 = sue_pwm_input_5;
packet.sue_pwm_input_6 = sue_pwm_input_6;
packet.sue_pwm_input_7 = sue_pwm_input_7;
packet.sue_pwm_input_8 = sue_pwm_input_8;
packet.sue_pwm_input_9 = sue_pwm_input_9;
packet.sue_pwm_input_10 = sue_pwm_input_10;
packet.sue_pwm_output_1 = sue_pwm_output_1;
packet.sue_pwm_output_2 = sue_pwm_output_2;
packet.sue_pwm_output_3 = sue_pwm_output_3;
packet.sue_pwm_output_4 = sue_pwm_output_4;
packet.sue_pwm_output_5 = sue_pwm_output_5;
packet.sue_pwm_output_6 = sue_pwm_output_6;
packet.sue_pwm_output_7 = sue_pwm_output_7;
packet.sue_pwm_output_8 = sue_pwm_output_8;
packet.sue_pwm_output_9 = sue_pwm_output_9;
packet.sue_pwm_output_10 = sue_pwm_output_10;
packet.sue_imu_location_x = sue_imu_location_x;
packet.sue_imu_location_y = sue_imu_location_y;
packet.sue_imu_location_z = sue_imu_location_z;
packet.sue_osc_fails = sue_osc_fails;
packet.sue_imu_velocity_x = sue_imu_velocity_x;
packet.sue_imu_velocity_y = sue_imu_velocity_y;
packet.sue_imu_velocity_z = sue_imu_velocity_z;
packet.sue_waypoint_goal_x = sue_waypoint_goal_x;
packet.sue_waypoint_goal_y = sue_waypoint_goal_y;
packet.sue_waypoint_goal_z = sue_waypoint_goal_z;
packet.sue_memory_stack_free = sue_memory_stack_free;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, 70, 169);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F2_B UNPACKING
/**
* @brief Get field sue_time from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Time
*/
static inline uint32_t mavlink_msg_serial_udb_extra_f2_b_get_sue_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field sue_pwm_input_1 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 1
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field sue_pwm_input_2 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 2
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
/**
* @brief Get field sue_pwm_input_3 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 3
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_3(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
/**
* @brief Get field sue_pwm_input_4 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 4
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_4(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
/**
* @brief Get field sue_pwm_input_5 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 5
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_5(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
/**
* @brief Get field sue_pwm_input_6 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 6
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_6(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
/**
* @brief Get field sue_pwm_input_7 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 7
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_7(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
/**
* @brief Get field sue_pwm_input_8 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 8
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_8(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
/**
* @brief Get field sue_pwm_input_9 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 9
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_9(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
/**
* @brief Get field sue_pwm_input_10 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Input Channel 10
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_10(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 26);
}
/**
* @brief Get field sue_pwm_output_1 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 1
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 28);
}
/**
* @brief Get field sue_pwm_output_2 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 2
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 30);
}
/**
* @brief Get field sue_pwm_output_3 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 3
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_3(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 32);
}
/**
* @brief Get field sue_pwm_output_4 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 4
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_4(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 34);
}
/**
* @brief Get field sue_pwm_output_5 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 5
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_5(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 36);
}
/**
* @brief Get field sue_pwm_output_6 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 6
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_6(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 38);
}
/**
* @brief Get field sue_pwm_output_7 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 7
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_7(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
/**
* @brief Get field sue_pwm_output_8 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 8
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_8(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 42);
}
/**
* @brief Get field sue_pwm_output_9 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 9
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_9(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 44);
}
/**
* @brief Get field sue_pwm_output_10 from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra PWM Output Channel 10
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_10(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 46);
}
/**
* @brief Get field sue_imu_location_x from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Location X
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 48);
}
/**
* @brief Get field sue_imu_location_y from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Location Y
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 50);
}
/**
* @brief Get field sue_imu_location_z from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Location Z
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 52);
}
/**
* @brief Get field sue_flags from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Status Flags
*/
static inline uint32_t mavlink_msg_serial_udb_extra_f2_b_get_sue_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field sue_osc_fails from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Oscillator Failure Count
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_osc_fails(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 54);
}
/**
* @brief Get field sue_imu_velocity_x from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Velocity X
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 56);
}
/**
* @brief Get field sue_imu_velocity_y from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Velocity Y
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 58);
}
/**
* @brief Get field sue_imu_velocity_z from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra IMU Velocity Z
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 60);
}
/**
* @brief Get field sue_waypoint_goal_x from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Current Waypoint Goal X
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 62);
}
/**
* @brief Get field sue_waypoint_goal_y from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Current Waypoint Goal Y
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 64);
}
/**
* @brief Get field sue_waypoint_goal_z from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Current Waypoint Goal Z
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 66);
}
/**
* @brief Get field sue_memory_stack_free from serial_udb_extra_f2_b message
*
* @return Serial UDB Extra Stack Memory Free
*/
static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_memory_stack_free(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 68);
}
/**
* @brief Decode a serial_udb_extra_f2_b message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f2_b C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f2_b_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f2_b->sue_time = mavlink_msg_serial_udb_extra_f2_b_get_sue_time(msg);
serial_udb_extra_f2_b->sue_flags = mavlink_msg_serial_udb_extra_f2_b_get_sue_flags(msg);
serial_udb_extra_f2_b->sue_pwm_input_1 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_1(msg);
serial_udb_extra_f2_b->sue_pwm_input_2 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_2(msg);
serial_udb_extra_f2_b->sue_pwm_input_3 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_3(msg);
serial_udb_extra_f2_b->sue_pwm_input_4 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_4(msg);
serial_udb_extra_f2_b->sue_pwm_input_5 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_5(msg);
serial_udb_extra_f2_b->sue_pwm_input_6 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_6(msg);
serial_udb_extra_f2_b->sue_pwm_input_7 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_7(msg);
serial_udb_extra_f2_b->sue_pwm_input_8 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_8(msg);
serial_udb_extra_f2_b->sue_pwm_input_9 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_9(msg);
serial_udb_extra_f2_b->sue_pwm_input_10 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_10(msg);
serial_udb_extra_f2_b->sue_pwm_output_1 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_1(msg);
serial_udb_extra_f2_b->sue_pwm_output_2 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_2(msg);
serial_udb_extra_f2_b->sue_pwm_output_3 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_3(msg);
serial_udb_extra_f2_b->sue_pwm_output_4 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_4(msg);
serial_udb_extra_f2_b->sue_pwm_output_5 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_5(msg);
serial_udb_extra_f2_b->sue_pwm_output_6 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_6(msg);
serial_udb_extra_f2_b->sue_pwm_output_7 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_7(msg);
serial_udb_extra_f2_b->sue_pwm_output_8 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_8(msg);
serial_udb_extra_f2_b->sue_pwm_output_9 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_9(msg);
serial_udb_extra_f2_b->sue_pwm_output_10 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_10(msg);
serial_udb_extra_f2_b->sue_imu_location_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_x(msg);
serial_udb_extra_f2_b->sue_imu_location_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_y(msg);
serial_udb_extra_f2_b->sue_imu_location_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_z(msg);
serial_udb_extra_f2_b->sue_osc_fails = mavlink_msg_serial_udb_extra_f2_b_get_sue_osc_fails(msg);
serial_udb_extra_f2_b->sue_imu_velocity_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_x(msg);
serial_udb_extra_f2_b->sue_imu_velocity_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_y(msg);
serial_udb_extra_f2_b->sue_imu_velocity_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_z(msg);
serial_udb_extra_f2_b->sue_waypoint_goal_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_x(msg);
serial_udb_extra_f2_b->sue_waypoint_goal_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_y(msg);
serial_udb_extra_f2_b->sue_waypoint_goal_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_z(msg);
serial_udb_extra_f2_b->sue_memory_stack_free = mavlink_msg_serial_udb_extra_f2_b_get_sue_memory_stack_free(msg);
#else
memcpy(serial_udb_extra_f2_b, _MAV_PAYLOAD(msg), 70);
#endif
}

View File

@@ -0,0 +1,342 @@
// MESSAGE SERIAL_UDB_EXTRA_F4 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4 172
typedef struct __mavlink_serial_udb_extra_f4_t
{
uint8_t sue_ROLL_STABILIZATION_AILERONS; ///< Serial UDB Extra Roll Stabilization with Ailerons Enabled
uint8_t sue_ROLL_STABILIZATION_RUDDER; ///< Serial UDB Extra Roll Stabilization with Rudder Enabled
uint8_t sue_PITCH_STABILIZATION; ///< Serial UDB Extra Pitch Stabilization Enabled
uint8_t sue_YAW_STABILIZATION_RUDDER; ///< Serial UDB Extra Yaw Stabilization using Rudder Enabled
uint8_t sue_YAW_STABILIZATION_AILERON; ///< Serial UDB Extra Yaw Stabilization using Ailerons Enabled
uint8_t sue_AILERON_NAVIGATION; ///< Serial UDB Extra Navigation with Ailerons Enabled
uint8_t sue_RUDDER_NAVIGATION; ///< Serial UDB Extra Navigation with Rudder Enabled
uint8_t sue_ALTITUDEHOLD_STABILIZED; ///< Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
uint8_t sue_ALTITUDEHOLD_WAYPOINT; ///< Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
uint8_t sue_RACING_MODE; ///< Serial UDB Extra Firmware racing mode enabled
} mavlink_serial_udb_extra_f4_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN 10
#define MAVLINK_MSG_ID_172_LEN 10
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F4 { \
"SERIAL_UDB_EXTRA_F4", \
10, \
{ { "sue_ROLL_STABILIZATION_AILERONS", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_serial_udb_extra_f4_t, sue_ROLL_STABILIZATION_AILERONS) }, \
{ "sue_ROLL_STABILIZATION_RUDDER", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_serial_udb_extra_f4_t, sue_ROLL_STABILIZATION_RUDDER) }, \
{ "sue_PITCH_STABILIZATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_serial_udb_extra_f4_t, sue_PITCH_STABILIZATION) }, \
{ "sue_YAW_STABILIZATION_RUDDER", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_serial_udb_extra_f4_t, sue_YAW_STABILIZATION_RUDDER) }, \
{ "sue_YAW_STABILIZATION_AILERON", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_serial_udb_extra_f4_t, sue_YAW_STABILIZATION_AILERON) }, \
{ "sue_AILERON_NAVIGATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_serial_udb_extra_f4_t, sue_AILERON_NAVIGATION) }, \
{ "sue_RUDDER_NAVIGATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_udb_extra_f4_t, sue_RUDDER_NAVIGATION) }, \
{ "sue_ALTITUDEHOLD_STABILIZED", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_udb_extra_f4_t, sue_ALTITUDEHOLD_STABILIZED) }, \
{ "sue_ALTITUDEHOLD_WAYPOINT", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_udb_extra_f4_t, sue_ALTITUDEHOLD_WAYPOINT) }, \
{ "sue_RACING_MODE", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_serial_udb_extra_f4_t, sue_RACING_MODE) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f4 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 sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled
* @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled
* @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled
* @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled
* @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled
* @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled
* @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled
* @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
* @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
* @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[10];
_mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS);
_mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION);
_mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON);
_mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION);
_mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION);
_mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED);
_mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT);
_mav_put_uint8_t(buf, 9, sue_RACING_MODE);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10);
#else
mavlink_serial_udb_extra_f4_t packet;
packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS;
packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER;
packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION;
packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION;
packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION;
packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED;
packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT;
packet.sue_RACING_MODE = sue_RACING_MODE;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4;
return mavlink_finalize_message(msg, system_id, component_id, 10, 191);
}
/**
* @brief Pack a serial_udb_extra_f4 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 sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled
* @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled
* @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled
* @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled
* @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled
* @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled
* @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled
* @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
* @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
* @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t sue_ROLL_STABILIZATION_AILERONS,uint8_t sue_ROLL_STABILIZATION_RUDDER,uint8_t sue_PITCH_STABILIZATION,uint8_t sue_YAW_STABILIZATION_RUDDER,uint8_t sue_YAW_STABILIZATION_AILERON,uint8_t sue_AILERON_NAVIGATION,uint8_t sue_RUDDER_NAVIGATION,uint8_t sue_ALTITUDEHOLD_STABILIZED,uint8_t sue_ALTITUDEHOLD_WAYPOINT,uint8_t sue_RACING_MODE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[10];
_mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS);
_mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION);
_mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON);
_mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION);
_mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION);
_mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED);
_mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT);
_mav_put_uint8_t(buf, 9, sue_RACING_MODE);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 10);
#else
mavlink_serial_udb_extra_f4_t packet;
packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS;
packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER;
packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION;
packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION;
packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION;
packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED;
packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT;
packet.sue_RACING_MODE = sue_RACING_MODE;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 10);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 10, 191);
}
/**
* @brief Encode a serial_udb_extra_f4 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 serial_udb_extra_f4 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4)
{
return mavlink_msg_serial_udb_extra_f4_pack(system_id, component_id, msg, serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS, serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_PITCH_STABILIZATION, serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f4->sue_AILERON_NAVIGATION, serial_udb_extra_f4->sue_RUDDER_NAVIGATION, serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED, serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT, serial_udb_extra_f4->sue_RACING_MODE);
}
/**
* @brief Send a serial_udb_extra_f4 message
* @param chan MAVLink channel to send the message
*
* @param sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled
* @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled
* @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled
* @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled
* @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled
* @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled
* @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled
* @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
* @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
* @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan, uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[10];
_mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS);
_mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION);
_mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER);
_mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON);
_mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION);
_mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION);
_mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED);
_mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT);
_mav_put_uint8_t(buf, 9, sue_RACING_MODE);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, 10, 191);
#else
mavlink_serial_udb_extra_f4_t packet;
packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS;
packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER;
packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION;
packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION;
packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION;
packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED;
packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT;
packet.sue_RACING_MODE = sue_RACING_MODE;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, 10, 191);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F4 UNPACKING
/**
* @brief Get field sue_ROLL_STABILIZATION_AILERONS from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Roll Stabilization with Ailerons Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_AILERONS(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field sue_ROLL_STABILIZATION_RUDDER from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Roll Stabilization with Rudder Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field sue_PITCH_STABILIZATION from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Pitch Stabilization Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_PITCH_STABILIZATION(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field sue_YAW_STABILIZATION_RUDDER from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Yaw Stabilization using Rudder Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field sue_YAW_STABILIZATION_AILERON from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Yaw Stabilization using Ailerons Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_AILERON(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field sue_AILERON_NAVIGATION from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Navigation with Ailerons Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_AILERON_NAVIGATION(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field sue_RUDDER_NAVIGATION from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Navigation with Rudder Enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_RUDDER_NAVIGATION(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field sue_ALTITUDEHOLD_STABILIZED from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Type of Alitude Hold when in Stabilized Mode
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_STABILIZED(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field sue_ALTITUDEHOLD_WAYPOINT from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Type of Alitude Hold when in Waypoint Mode
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_WAYPOINT(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field sue_RACING_MODE from serial_udb_extra_f4 message
*
* @return Serial UDB Extra Firmware racing mode enabled
*/
static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_RACING_MODE(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Decode a serial_udb_extra_f4 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f4 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f4_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS = mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_AILERONS(msg);
serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER = mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_RUDDER(msg);
serial_udb_extra_f4->sue_PITCH_STABILIZATION = mavlink_msg_serial_udb_extra_f4_get_sue_PITCH_STABILIZATION(msg);
serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER = mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_RUDDER(msg);
serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_AILERON(msg);
serial_udb_extra_f4->sue_AILERON_NAVIGATION = mavlink_msg_serial_udb_extra_f4_get_sue_AILERON_NAVIGATION(msg);
serial_udb_extra_f4->sue_RUDDER_NAVIGATION = mavlink_msg_serial_udb_extra_f4_get_sue_RUDDER_NAVIGATION(msg);
serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED = mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_STABILIZED(msg);
serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT = mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_WAYPOINT(msg);
serial_udb_extra_f4->sue_RACING_MODE = mavlink_msg_serial_udb_extra_f4_get_sue_RACING_MODE(msg);
#else
memcpy(serial_udb_extra_f4, _MAV_PAYLOAD(msg), 10);
#endif
}

View File

@@ -0,0 +1,254 @@
// MESSAGE SERIAL_UDB_EXTRA_F5 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5 173
typedef struct __mavlink_serial_udb_extra_f5_t
{
float sue_YAWKP_AILERON; ///< Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
float sue_YAWKD_AILERON; ///< Serial UDB YAWKD_AILERON Gain for Rate control of navigation
float sue_ROLLKP; ///< Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
float sue_ROLLKD; ///< Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
float sue_YAW_STABILIZATION_AILERON; ///< YAW_STABILIZATION_AILERON Proportional control
float sue_AILERON_BOOST; ///< Gain For Boosting Manual Aileron control When Plane Stabilized
} mavlink_serial_udb_extra_f5_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN 24
#define MAVLINK_MSG_ID_173_LEN 24
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F5 { \
"SERIAL_UDB_EXTRA_F5", \
6, \
{ { "sue_YAWKP_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKP_AILERON) }, \
{ "sue_YAWKD_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKD_AILERON) }, \
{ "sue_ROLLKP", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKP) }, \
{ "sue_ROLLKD", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKD) }, \
{ "sue_YAW_STABILIZATION_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAW_STABILIZATION_AILERON) }, \
{ "sue_AILERON_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f5_t, sue_AILERON_BOOST) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f5 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 sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
* @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation
* @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
* @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
* @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control
* @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_AILERON);
_mav_put_float(buf, 4, sue_YAWKD_AILERON);
_mav_put_float(buf, 8, sue_ROLLKP);
_mav_put_float(buf, 12, sue_ROLLKD);
_mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
_mav_put_float(buf, 20, sue_AILERON_BOOST);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_serial_udb_extra_f5_t packet;
packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
packet.sue_ROLLKP = sue_ROLLKP;
packet.sue_ROLLKD = sue_ROLLKD;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5;
return mavlink_finalize_message(msg, system_id, component_id, 24, 121);
}
/**
* @brief Pack a serial_udb_extra_f5 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 sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
* @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation
* @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
* @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
* @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control
* @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float sue_YAWKP_AILERON,float sue_YAWKD_AILERON,float sue_ROLLKP,float sue_ROLLKD,float sue_YAW_STABILIZATION_AILERON,float sue_AILERON_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_AILERON);
_mav_put_float(buf, 4, sue_YAWKD_AILERON);
_mav_put_float(buf, 8, sue_ROLLKP);
_mav_put_float(buf, 12, sue_ROLLKD);
_mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
_mav_put_float(buf, 20, sue_AILERON_BOOST);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_serial_udb_extra_f5_t packet;
packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
packet.sue_ROLLKP = sue_ROLLKP;
packet.sue_ROLLKD = sue_ROLLKD;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 121);
}
/**
* @brief Encode a serial_udb_extra_f5 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 serial_udb_extra_f5 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
{
return mavlink_msg_serial_udb_extra_f5_pack(system_id, component_id, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST);
}
/**
* @brief Send a serial_udb_extra_f5 message
* @param chan MAVLink channel to send the message
*
* @param sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
* @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation
* @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
* @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
* @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control
* @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_AILERON);
_mav_put_float(buf, 4, sue_YAWKD_AILERON);
_mav_put_float(buf, 8, sue_ROLLKP);
_mav_put_float(buf, 12, sue_ROLLKD);
_mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON);
_mav_put_float(buf, 20, sue_AILERON_BOOST);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, 24, 121);
#else
mavlink_serial_udb_extra_f5_t packet;
packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON;
packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON;
packet.sue_ROLLKP = sue_ROLLKP;
packet.sue_ROLLKD = sue_ROLLKD;
packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON;
packet.sue_AILERON_BOOST = sue_AILERON_BOOST;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, 24, 121);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F5 UNPACKING
/**
* @brief Get field sue_YAWKP_AILERON from serial_udb_extra_f5 message
*
* @return Serial UDB YAWKP_AILERON Gain for Proporional control of navigation
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field sue_YAWKD_AILERON from serial_udb_extra_f5 message
*
* @return Serial UDB YAWKD_AILERON Gain for Rate control of navigation
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field sue_ROLLKP from serial_udb_extra_f5 message
*
* @return Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field sue_ROLLKD from serial_udb_extra_f5 message
*
* @return Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field sue_YAW_STABILIZATION_AILERON from serial_udb_extra_f5 message
*
* @return YAW_STABILIZATION_AILERON Proportional control
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field sue_AILERON_BOOST from serial_udb_extra_f5 message
*
* @return Gain For Boosting Manual Aileron control When Plane Stabilized
*/
static inline float mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a serial_udb_extra_f5 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f5 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f5_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f5->sue_YAWKP_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(msg);
serial_udb_extra_f5->sue_YAWKD_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(msg);
serial_udb_extra_f5->sue_ROLLKP = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(msg);
serial_udb_extra_f5->sue_ROLLKD = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(msg);
serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(msg);
serial_udb_extra_f5->sue_AILERON_BOOST = mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(msg);
#else
memcpy(serial_udb_extra_f5, _MAV_PAYLOAD(msg), 24);
#endif
}

View File

@@ -0,0 +1,232 @@
// MESSAGE SERIAL_UDB_EXTRA_F6 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6 174
typedef struct __mavlink_serial_udb_extra_f6_t
{
float sue_PITCHGAIN; ///< Serial UDB Extra PITCHGAIN Proportional Control
float sue_PITCHKD; ///< Serial UDB Extra Pitch Rate Control
float sue_RUDDER_ELEV_MIX; ///< Serial UDB Extra Rudder to Elevator Mix
float sue_ROLL_ELEV_MIX; ///< Serial UDB Extra Roll to Elevator Mix
float sue_ELEVATOR_BOOST; ///< Gain For Boosting Manual Elevator control When Plane Stabilized
} mavlink_serial_udb_extra_f6_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN 20
#define MAVLINK_MSG_ID_174_LEN 20
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F6 { \
"SERIAL_UDB_EXTRA_F6", \
5, \
{ { "sue_PITCHGAIN", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f6_t, sue_PITCHGAIN) }, \
{ "sue_PITCHKD", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f6_t, sue_PITCHKD) }, \
{ "sue_RUDDER_ELEV_MIX", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f6_t, sue_RUDDER_ELEV_MIX) }, \
{ "sue_ROLL_ELEV_MIX", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f6_t, sue_ROLL_ELEV_MIX) }, \
{ "sue_ELEVATOR_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f6_t, sue_ELEVATOR_BOOST) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f6 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 sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control
* @param sue_PITCHKD Serial UDB Extra Pitch Rate Control
* @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix
* @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix
* @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, sue_PITCHGAIN);
_mav_put_float(buf, 4, sue_PITCHKD);
_mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX);
_mav_put_float(buf, 12, sue_ROLL_ELEV_MIX);
_mav_put_float(buf, 16, sue_ELEVATOR_BOOST);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_serial_udb_extra_f6_t packet;
packet.sue_PITCHGAIN = sue_PITCHGAIN;
packet.sue_PITCHKD = sue_PITCHKD;
packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX;
packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX;
packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6;
return mavlink_finalize_message(msg, system_id, component_id, 20, 54);
}
/**
* @brief Pack a serial_udb_extra_f6 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 sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control
* @param sue_PITCHKD Serial UDB Extra Pitch Rate Control
* @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix
* @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix
* @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float sue_PITCHGAIN,float sue_PITCHKD,float sue_RUDDER_ELEV_MIX,float sue_ROLL_ELEV_MIX,float sue_ELEVATOR_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, sue_PITCHGAIN);
_mav_put_float(buf, 4, sue_PITCHKD);
_mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX);
_mav_put_float(buf, 12, sue_ROLL_ELEV_MIX);
_mav_put_float(buf, 16, sue_ELEVATOR_BOOST);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_serial_udb_extra_f6_t packet;
packet.sue_PITCHGAIN = sue_PITCHGAIN;
packet.sue_PITCHKD = sue_PITCHKD;
packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX;
packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX;
packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 54);
}
/**
* @brief Encode a serial_udb_extra_f6 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 serial_udb_extra_f6 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6)
{
return mavlink_msg_serial_udb_extra_f6_pack(system_id, component_id, msg, serial_udb_extra_f6->sue_PITCHGAIN, serial_udb_extra_f6->sue_PITCHKD, serial_udb_extra_f6->sue_RUDDER_ELEV_MIX, serial_udb_extra_f6->sue_ROLL_ELEV_MIX, serial_udb_extra_f6->sue_ELEVATOR_BOOST);
}
/**
* @brief Send a serial_udb_extra_f6 message
* @param chan MAVLink channel to send the message
*
* @param sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control
* @param sue_PITCHKD Serial UDB Extra Pitch Rate Control
* @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix
* @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix
* @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f6_send(mavlink_channel_t chan, float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, sue_PITCHGAIN);
_mav_put_float(buf, 4, sue_PITCHKD);
_mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX);
_mav_put_float(buf, 12, sue_ROLL_ELEV_MIX);
_mav_put_float(buf, 16, sue_ELEVATOR_BOOST);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, 20, 54);
#else
mavlink_serial_udb_extra_f6_t packet;
packet.sue_PITCHGAIN = sue_PITCHGAIN;
packet.sue_PITCHKD = sue_PITCHKD;
packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX;
packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX;
packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, 20, 54);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F6 UNPACKING
/**
* @brief Get field sue_PITCHGAIN from serial_udb_extra_f6 message
*
* @return Serial UDB Extra PITCHGAIN Proportional Control
*/
static inline float mavlink_msg_serial_udb_extra_f6_get_sue_PITCHGAIN(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field sue_PITCHKD from serial_udb_extra_f6 message
*
* @return Serial UDB Extra Pitch Rate Control
*/
static inline float mavlink_msg_serial_udb_extra_f6_get_sue_PITCHKD(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field sue_RUDDER_ELEV_MIX from serial_udb_extra_f6 message
*
* @return Serial UDB Extra Rudder to Elevator Mix
*/
static inline float mavlink_msg_serial_udb_extra_f6_get_sue_RUDDER_ELEV_MIX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field sue_ROLL_ELEV_MIX from serial_udb_extra_f6 message
*
* @return Serial UDB Extra Roll to Elevator Mix
*/
static inline float mavlink_msg_serial_udb_extra_f6_get_sue_ROLL_ELEV_MIX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field sue_ELEVATOR_BOOST from serial_udb_extra_f6 message
*
* @return Gain For Boosting Manual Elevator control When Plane Stabilized
*/
static inline float mavlink_msg_serial_udb_extra_f6_get_sue_ELEVATOR_BOOST(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a serial_udb_extra_f6 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f6 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f6_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f6->sue_PITCHGAIN = mavlink_msg_serial_udb_extra_f6_get_sue_PITCHGAIN(msg);
serial_udb_extra_f6->sue_PITCHKD = mavlink_msg_serial_udb_extra_f6_get_sue_PITCHKD(msg);
serial_udb_extra_f6->sue_RUDDER_ELEV_MIX = mavlink_msg_serial_udb_extra_f6_get_sue_RUDDER_ELEV_MIX(msg);
serial_udb_extra_f6->sue_ROLL_ELEV_MIX = mavlink_msg_serial_udb_extra_f6_get_sue_ROLL_ELEV_MIX(msg);
serial_udb_extra_f6->sue_ELEVATOR_BOOST = mavlink_msg_serial_udb_extra_f6_get_sue_ELEVATOR_BOOST(msg);
#else
memcpy(serial_udb_extra_f6, _MAV_PAYLOAD(msg), 20);
#endif
}

View File

@@ -0,0 +1,254 @@
// MESSAGE SERIAL_UDB_EXTRA_F7 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7 175
typedef struct __mavlink_serial_udb_extra_f7_t
{
float sue_YAWKP_RUDDER; ///< Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
float sue_YAWKD_RUDDER; ///< Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
float sue_ROLLKP_RUDDER; ///< Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
float sue_ROLLKD_RUDDER; ///< Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
float sue_RUDDER_BOOST; ///< SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
float sue_RTL_PITCH_DOWN; ///< Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
} mavlink_serial_udb_extra_f7_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN 24
#define MAVLINK_MSG_ID_175_LEN 24
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F7 { \
"SERIAL_UDB_EXTRA_F7", \
6, \
{ { "sue_YAWKP_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f7_t, sue_YAWKP_RUDDER) }, \
{ "sue_YAWKD_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f7_t, sue_YAWKD_RUDDER) }, \
{ "sue_ROLLKP_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f7_t, sue_ROLLKP_RUDDER) }, \
{ "sue_ROLLKD_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f7_t, sue_ROLLKD_RUDDER) }, \
{ "sue_RUDDER_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f7_t, sue_RUDDER_BOOST) }, \
{ "sue_RTL_PITCH_DOWN", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f7_t, sue_RTL_PITCH_DOWN) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f7 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 sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
* @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
* @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
* @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
* @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
* @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_RUDDER);
_mav_put_float(buf, 4, sue_YAWKD_RUDDER);
_mav_put_float(buf, 8, sue_ROLLKP_RUDDER);
_mav_put_float(buf, 12, sue_ROLLKD_RUDDER);
_mav_put_float(buf, 16, sue_RUDDER_BOOST);
_mav_put_float(buf, 20, sue_RTL_PITCH_DOWN);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_serial_udb_extra_f7_t packet;
packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER;
packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER;
packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER;
packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER;
packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST;
packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7;
return mavlink_finalize_message(msg, system_id, component_id, 24, 171);
}
/**
* @brief Pack a serial_udb_extra_f7 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 sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
* @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
* @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
* @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
* @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
* @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float sue_YAWKP_RUDDER,float sue_YAWKD_RUDDER,float sue_ROLLKP_RUDDER,float sue_ROLLKD_RUDDER,float sue_RUDDER_BOOST,float sue_RTL_PITCH_DOWN)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_RUDDER);
_mav_put_float(buf, 4, sue_YAWKD_RUDDER);
_mav_put_float(buf, 8, sue_ROLLKP_RUDDER);
_mav_put_float(buf, 12, sue_ROLLKD_RUDDER);
_mav_put_float(buf, 16, sue_RUDDER_BOOST);
_mav_put_float(buf, 20, sue_RTL_PITCH_DOWN);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_serial_udb_extra_f7_t packet;
packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER;
packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER;
packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER;
packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER;
packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST;
packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 171);
}
/**
* @brief Encode a serial_udb_extra_f7 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 serial_udb_extra_f7 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7)
{
return mavlink_msg_serial_udb_extra_f7_pack(system_id, component_id, msg, serial_udb_extra_f7->sue_YAWKP_RUDDER, serial_udb_extra_f7->sue_YAWKD_RUDDER, serial_udb_extra_f7->sue_ROLLKP_RUDDER, serial_udb_extra_f7->sue_ROLLKD_RUDDER, serial_udb_extra_f7->sue_RUDDER_BOOST, serial_udb_extra_f7->sue_RTL_PITCH_DOWN);
}
/**
* @brief Send a serial_udb_extra_f7 message
* @param chan MAVLink channel to send the message
*
* @param sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
* @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
* @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
* @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
* @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
* @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan, float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_float(buf, 0, sue_YAWKP_RUDDER);
_mav_put_float(buf, 4, sue_YAWKD_RUDDER);
_mav_put_float(buf, 8, sue_ROLLKP_RUDDER);
_mav_put_float(buf, 12, sue_ROLLKD_RUDDER);
_mav_put_float(buf, 16, sue_RUDDER_BOOST);
_mav_put_float(buf, 20, sue_RTL_PITCH_DOWN);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, 24, 171);
#else
mavlink_serial_udb_extra_f7_t packet;
packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER;
packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER;
packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER;
packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER;
packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST;
packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, 24, 171);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F7 UNPACKING
/**
* @brief Get field sue_YAWKP_RUDDER from serial_udb_extra_f7 message
*
* @return Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_YAWKP_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field sue_YAWKD_RUDDER from serial_udb_extra_f7 message
*
* @return Serial UDB YAWKD_RUDDER Gain for Rate control of navigation
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_YAWKD_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field sue_ROLLKP_RUDDER from serial_udb_extra_f7 message
*
* @return Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKP_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field sue_ROLLKD_RUDDER from serial_udb_extra_f7 message
*
* @return Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKD_RUDDER(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field sue_RUDDER_BOOST from serial_udb_extra_f7 message
*
* @return SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_RUDDER_BOOST(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field sue_RTL_PITCH_DOWN from serial_udb_extra_f7 message
*
* @return Serial UDB Extra Return To Landing - Angle to Pitch Plane Down
*/
static inline float mavlink_msg_serial_udb_extra_f7_get_sue_RTL_PITCH_DOWN(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a serial_udb_extra_f7 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f7 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f7_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f7->sue_YAWKP_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_YAWKP_RUDDER(msg);
serial_udb_extra_f7->sue_YAWKD_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_YAWKD_RUDDER(msg);
serial_udb_extra_f7->sue_ROLLKP_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKP_RUDDER(msg);
serial_udb_extra_f7->sue_ROLLKD_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKD_RUDDER(msg);
serial_udb_extra_f7->sue_RUDDER_BOOST = mavlink_msg_serial_udb_extra_f7_get_sue_RUDDER_BOOST(msg);
serial_udb_extra_f7->sue_RTL_PITCH_DOWN = mavlink_msg_serial_udb_extra_f7_get_sue_RTL_PITCH_DOWN(msg);
#else
memcpy(serial_udb_extra_f7, _MAV_PAYLOAD(msg), 24);
#endif
}

View File

@@ -0,0 +1,276 @@
// MESSAGE SERIAL_UDB_EXTRA_F8 PACKING
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8 176
typedef struct __mavlink_serial_udb_extra_f8_t
{
float sue_HEIGHT_TARGET_MAX; ///< Serial UDB Extra HEIGHT_TARGET_MAX
float sue_HEIGHT_TARGET_MIN; ///< Serial UDB Extra HEIGHT_TARGET_MIN
float sue_ALT_HOLD_THROTTLE_MIN; ///< Serial UDB Extra ALT_HOLD_THROTTLE_MIN
float sue_ALT_HOLD_THROTTLE_MAX; ///< Serial UDB Extra ALT_HOLD_THROTTLE_MAX
float sue_ALT_HOLD_PITCH_MIN; ///< Serial UDB Extra ALT_HOLD_PITCH_MIN
float sue_ALT_HOLD_PITCH_MAX; ///< Serial UDB Extra ALT_HOLD_PITCH_MAX
float sue_ALT_HOLD_PITCH_HIGH; ///< Serial UDB Extra ALT_HOLD_PITCH_HIGH
} mavlink_serial_udb_extra_f8_t;
#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN 28
#define MAVLINK_MSG_ID_176_LEN 28
#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F8 { \
"SERIAL_UDB_EXTRA_F8", \
7, \
{ { "sue_HEIGHT_TARGET_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f8_t, sue_HEIGHT_TARGET_MAX) }, \
{ "sue_HEIGHT_TARGET_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f8_t, sue_HEIGHT_TARGET_MIN) }, \
{ "sue_ALT_HOLD_THROTTLE_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_THROTTLE_MIN) }, \
{ "sue_ALT_HOLD_THROTTLE_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_THROTTLE_MAX) }, \
{ "sue_ALT_HOLD_PITCH_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_MIN) }, \
{ "sue_ALT_HOLD_PITCH_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_MAX) }, \
{ "sue_ALT_HOLD_PITCH_HIGH", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_HIGH) }, \
} \
}
/**
* @brief Pack a serial_udb_extra_f8 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 sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX
* @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN
* @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN
* @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX
* @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN
* @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX
* @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX);
_mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN);
_mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN);
_mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX);
_mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN);
_mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX);
_mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_serial_udb_extra_f8_t packet;
packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX;
packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN;
packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN;
packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX;
packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN;
packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX;
packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8;
return mavlink_finalize_message(msg, system_id, component_id, 28, 142);
}
/**
* @brief Pack a serial_udb_extra_f8 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 sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX
* @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN
* @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN
* @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX
* @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN
* @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX
* @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float sue_HEIGHT_TARGET_MAX,float sue_HEIGHT_TARGET_MIN,float sue_ALT_HOLD_THROTTLE_MIN,float sue_ALT_HOLD_THROTTLE_MAX,float sue_ALT_HOLD_PITCH_MIN,float sue_ALT_HOLD_PITCH_MAX,float sue_ALT_HOLD_PITCH_HIGH)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX);
_mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN);
_mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN);
_mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX);
_mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN);
_mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX);
_mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_serial_udb_extra_f8_t packet;
packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX;
packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN;
packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN;
packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX;
packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN;
packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX;
packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 142);
}
/**
* @brief Encode a serial_udb_extra_f8 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 serial_udb_extra_f8 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8)
{
return mavlink_msg_serial_udb_extra_f8_pack(system_id, component_id, msg, serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX, serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH);
}
/**
* @brief Send a serial_udb_extra_f8 message
* @param chan MAVLink channel to send the message
*
* @param sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX
* @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN
* @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN
* @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX
* @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN
* @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX
* @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan, float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX);
_mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN);
_mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN);
_mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX);
_mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN);
_mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX);
_mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, 28, 142);
#else
mavlink_serial_udb_extra_f8_t packet;
packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX;
packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN;
packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN;
packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX;
packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN;
packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX;
packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, 28, 142);
#endif
}
#endif
// MESSAGE SERIAL_UDB_EXTRA_F8 UNPACKING
/**
* @brief Get field sue_HEIGHT_TARGET_MAX from serial_udb_extra_f8 message
*
* @return Serial UDB Extra HEIGHT_TARGET_MAX
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MAX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field sue_HEIGHT_TARGET_MIN from serial_udb_extra_f8 message
*
* @return Serial UDB Extra HEIGHT_TARGET_MIN
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MIN(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field sue_ALT_HOLD_THROTTLE_MIN from serial_udb_extra_f8 message
*
* @return Serial UDB Extra ALT_HOLD_THROTTLE_MIN
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MIN(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field sue_ALT_HOLD_THROTTLE_MAX from serial_udb_extra_f8 message
*
* @return Serial UDB Extra ALT_HOLD_THROTTLE_MAX
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MAX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field sue_ALT_HOLD_PITCH_MIN from serial_udb_extra_f8 message
*
* @return Serial UDB Extra ALT_HOLD_PITCH_MIN
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MIN(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field sue_ALT_HOLD_PITCH_MAX from serial_udb_extra_f8 message
*
* @return Serial UDB Extra ALT_HOLD_PITCH_MAX
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MAX(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field sue_ALT_HOLD_PITCH_HIGH from serial_udb_extra_f8 message
*
* @return Serial UDB Extra ALT_HOLD_PITCH_HIGH
*/
static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_HIGH(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a serial_udb_extra_f8 message into a struct
*
* @param msg The message to decode
* @param serial_udb_extra_f8 C-struct to decode the message contents into
*/
static inline void mavlink_msg_serial_udb_extra_f8_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8)
{
#if MAVLINK_NEED_BYTE_SWAP
serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MAX(msg);
serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MIN(msg);
serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MIN(msg);
serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MAX(msg);
serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MIN(msg);
serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MAX(msg);
serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_HIGH(msg);
#else
memcpy(serial_udb_extra_f8, _MAV_PAYLOAD(msg), 28);
#endif
}

File diff suppressed because it is too large Load Diff

View File

@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:23 2012"
#define MAVLINK_BUILD_DATE "Wed Jan 9 16:18:08 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254

View File

@@ -550,7 +550,7 @@ MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf,
#ifdef MAVLINK_SEND_UART_BYTES
/* this is the more efficient approach, if the platform
defines it */
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len);
#else
/* fallback to one byte at a time */
uint16_t i;

File diff suppressed because one or more lines are too long

View File

@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:06:36 2012"
#define MAVLINK_BUILD_DATE "Wed Jan 9 16:18:21 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255

View File

@@ -4,8 +4,12 @@
typedef struct __mavlink_cmd_airspeed_ack_t
{
float spCmd; ///< commanded airspeed
uint8_t ack; ///< 0:ack, 1:nack
float spCmd; ///<
uint8_t ack; ///<
} mavlink_cmd_airspeed_ack_t;
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN 5
@@ -28,8 +32,12 @@ typedef struct __mavlink_cmd_airspeed_ack_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @param spCmd
* @param ack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -59,8 +67,12 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint
* @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 spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @param spCmd
* @param ack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -102,8 +114,12 @@ static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, ui
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @param spCmd
* @param ack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -132,7 +148,9 @@ static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, flo
/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
* @return
*/
static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message_t* msg)
{
@@ -142,7 +160,9 @@ static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message
/**
* @brief Get field ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
* @return
*/
static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg)
{

View File

@@ -4,8 +4,12 @@
typedef struct __mavlink_cmd_airspeed_chng_t
{
float spCmd; ///< commanded airspeed
uint8_t target; ///< Target ID
float spCmd; ///<
uint8_t target; ///<
} mavlink_cmd_airspeed_chng_t;
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN 5
@@ -28,8 +32,12 @@ typedef struct __mavlink_cmd_airspeed_chng_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 Target ID
* @param spCmd commanded airspeed
* @param target
* @param spCmd
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -59,8 +67,12 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uin
* @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 Target ID
* @param spCmd commanded airspeed
* @param target
* @param spCmd
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -102,8 +114,12 @@ static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, u
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
* @param target
* @param spCmd
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -132,7 +148,9 @@ static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, ui
/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
* @return
*/
static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg)
{
@@ -142,7 +160,9 @@ static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_mes
/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
* @return
*/
static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_filt_rot_vel_t
{
float rotVel[3]; ///< rotational velocity
float rotVel[3]; ///<
} mavlink_filt_rot_vel_t;
#define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12
@@ -26,7 +28,9 @@ typedef struct __mavlink_filt_rot_vel_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rotVel rotational velocity
* @param rotVel
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_filt_rot_vel_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel rotational velocity
* @param rotVel
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
*
* @param rotVel rotational velocity
* @param rotVel
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const f
/**
* @brief Get field rotVel from filt_rot_vel message
*
* @return rotational velocity
* @return
*/
static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float *rotVel)
{

View File

@@ -4,8 +4,12 @@
typedef struct __mavlink_llc_out_t
{
int16_t servoOut[4]; ///< Servo signal
int16_t MotorOut[2]; ///< motor signal
int16_t servoOut[4]; ///<
int16_t MotorOut[2]; ///<
} mavlink_llc_out_t;
#define MAVLINK_MSG_ID_LLC_OUT_LEN 12
@@ -29,8 +33,12 @@ typedef struct __mavlink_llc_out_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param servoOut Servo signal
* @param MotorOut motor signal
* @param servoOut
* @param MotorOut
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -60,8 +68,12 @@ static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t compo
* @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 servoOut Servo signal
* @param MotorOut motor signal
* @param servoOut
* @param MotorOut
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -103,8 +115,12 @@ static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t com
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
*
* @param servoOut Servo signal
* @param MotorOut motor signal
* @param servoOut
* @param MotorOut
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -133,7 +149,9 @@ static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_
/**
* @brief Get field servoOut from llc_out message
*
* @return Servo signal
* @return
*/
static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t *servoOut)
{
@@ -143,7 +161,9 @@ static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t*
/**
* @brief Get field MotorOut from llc_out message
*
* @return motor signal
* @return
*/
static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t *MotorOut)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_obs_air_temp_t
{
float airT; ///< Air Temperatur
float airT; ///<
} mavlink_obs_air_temp_t;
#define MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN 4
@@ -26,7 +28,9 @@ typedef struct __mavlink_obs_air_temp_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airT Air Temperatur
* @param airT
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_obs_air_temp_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param airT Air Temperatur
* @param airT
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
*
* @param airT Air Temperatur
* @param airT
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float a
/**
* @brief Get field airT from obs_air_temp message
*
* @return Air Temperatur
* @return
*/
static inline float mavlink_msg_obs_air_temp_get_airT(const mavlink_message_t* msg)
{

View File

@@ -4,9 +4,15 @@
typedef struct __mavlink_obs_air_velocity_t
{
float magnitude; ///< Air speed
float aoa; ///< angle of attack
float slip; ///< slip angle
float magnitude; ///<
float aoa; ///<
float slip; ///<
} mavlink_obs_air_velocity_t;
#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN 12
@@ -30,9 +36,15 @@ typedef struct __mavlink_obs_air_velocity_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @param magnitude
* @param aoa
* @param slip
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -64,9 +76,15 @@ static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint
* @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 magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @param magnitude
* @param aoa
* @param slip
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -110,9 +128,15 @@ static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, ui
* @brief Send a obs_air_velocity message
* @param chan MAVLink channel to send the message
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @param magnitude
* @param aoa
* @param slip
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -143,7 +167,9 @@ static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, flo
/**
* @brief Get field magnitude from obs_air_velocity message
*
* @return Air speed
* @return
*/
static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_message_t* msg)
{
@@ -153,7 +179,9 @@ static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_mes
/**
* @brief Get field aoa from obs_air_velocity message
*
* @return angle of attack
* @return
*/
static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t* msg)
{
@@ -163,7 +191,9 @@ static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t
/**
* @brief Get field slip from obs_air_velocity message
*
* @return slip angle
* @return
*/
static inline float mavlink_msg_obs_air_velocity_get_slip(const mavlink_message_t* msg)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_obs_attitude_t
{
double quat[4]; ///< Quaternion re;im
double quat[4]; ///<
} mavlink_obs_attitude_t;
#define MAVLINK_MSG_ID_OBS_ATTITUDE_LEN 32
@@ -26,7 +28,9 @@ typedef struct __mavlink_obs_attitude_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param quat Quaternion re;im
* @param quat
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_obs_attitude_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param quat Quaternion re;im
* @param quat
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_
* @brief Send a obs_attitude message
* @param chan MAVLink channel to send the message
*
* @param quat Quaternion re;im
* @param quat
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const d
/**
* @brief Get field quat from obs_attitude message
*
* @return Quaternion re;im
* @return
*/
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double *quat)
{

View File

@@ -4,8 +4,12 @@
typedef struct __mavlink_obs_bias_t
{
float accBias[3]; ///< accelerometer bias
float gyroBias[3]; ///< gyroscope bias
float accBias[3]; ///<
float gyroBias[3]; ///<
} mavlink_obs_bias_t;
#define MAVLINK_MSG_ID_OBS_BIAS_LEN 24
@@ -29,8 +33,12 @@ typedef struct __mavlink_obs_bias_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @param accBias
* @param gyroBias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -60,8 +68,12 @@ static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t comp
* @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 accBias accelerometer bias
* @param gyroBias gyroscope bias
* @param accBias
* @param gyroBias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -103,8 +115,12 @@ static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t co
* @brief Send a obs_bias message
* @param chan MAVLink channel to send the message
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @param accBias
* @param gyroBias
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -133,7 +149,9 @@ static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float
/**
* @brief Get field accBias from obs_bias message
*
* @return accelerometer bias
* @return
*/
static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float *accBias)
{
@@ -143,7 +161,9 @@ static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t*
/**
* @brief Get field gyroBias from obs_bias message
*
* @return gyroscope bias
* @return
*/
static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float *gyroBias)
{

View File

@@ -4,9 +4,15 @@
typedef struct __mavlink_obs_position_t
{
int32_t lon; ///< Longitude expressed in 1E7
int32_t lat; ///< Latitude expressed in 1E7
int32_t alt; ///< Altitude expressed in milimeters
int32_t lon; ///<
int32_t lat; ///<
int32_t alt; ///<
} mavlink_obs_position_t;
#define MAVLINK_MSG_ID_OBS_POSITION_LEN 12
@@ -30,9 +36,15 @@ typedef struct __mavlink_obs_position_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @param lon
* @param lat
* @param alt
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -64,9 +76,15 @@ static inline uint16_t mavlink_msg_obs_position_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @param lon
* @param lat
* @param alt
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -110,9 +128,15 @@ static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_
* @brief Send a obs_position message
* @param chan MAVLink channel to send the message
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @param lon
* @param lat
* @param alt
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -143,7 +167,9 @@ static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t
/**
* @brief Get field lon from obs_position message
*
* @return Longitude expressed in 1E7
* @return
*/
static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t* msg)
{
@@ -153,7 +179,9 @@ static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t*
/**
* @brief Get field lat from obs_position message
*
* @return Latitude expressed in 1E7
* @return
*/
static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg)
{
@@ -163,7 +191,9 @@ static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t*
/**
* @brief Get field alt from obs_position message
*
* @return Altitude expressed in milimeters
* @return
*/
static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_obs_qff_t
{
float qff; ///< Wind
float qff; ///<
} mavlink_obs_qff_t;
#define MAVLINK_MSG_ID_OBS_QFF_LEN 4
@@ -26,7 +28,9 @@ typedef struct __mavlink_obs_qff_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param qff Wind
* @param qff
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t compo
* @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 qff Wind
* @param qff
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t com
* @brief Send a obs_qff message
* @param chan MAVLink channel to send the message
*
* @param qff Wind
* @param qff
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff)
/**
* @brief Get field qff from obs_qff message
*
* @return Wind
* @return
*/
static inline float mavlink_msg_obs_qff_get_qff(const mavlink_message_t* msg)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_obs_velocity_t
{
float vel[3]; ///< Velocity
float vel[3]; ///<
} mavlink_obs_velocity_t;
#define MAVLINK_MSG_ID_OBS_VELOCITY_LEN 12
@@ -26,7 +28,9 @@ typedef struct __mavlink_obs_velocity_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param vel Velocity
* @param vel
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_obs_velocity_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 was sent over
* @param msg The MAVLink message to compress the data into
* @param vel Velocity
* @param vel
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_
* @brief Send a obs_velocity message
* @param chan MAVLink channel to send the message
*
* @param vel Velocity
* @param vel
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const f
/**
* @brief Get field vel from obs_velocity message
*
* @return Velocity
* @return
*/
static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float *vel)
{

View File

@@ -4,7 +4,9 @@
typedef struct __mavlink_obs_wind_t
{
float wind[3]; ///< Wind
float wind[3]; ///<
} mavlink_obs_wind_t;
#define MAVLINK_MSG_ID_OBS_WIND_LEN 12
@@ -26,7 +28,9 @@ typedef struct __mavlink_obs_wind_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param wind Wind
* @param wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -54,7 +58,9 @@ static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t comp
* @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 wind Wind
* @param wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -94,7 +100,9 @@ static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t co
* @brief Send a obs_wind message
* @param chan MAVLink channel to send the message
*
* @param wind Wind
* @param wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -121,7 +129,9 @@ static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float
/**
* @brief Get field wind from obs_wind message
*
* @return Wind
* @return
*/
static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float *wind)
{

View File

@@ -4,9 +4,15 @@
typedef struct __mavlink_pm_elec_t
{
float PwCons; ///< current power consumption
float BatStat; ///< battery status
float PwGen[3]; ///< Power generation from each module
float PwCons; ///<
float BatStat; ///<
float PwGen[3]; ///<
} mavlink_pm_elec_t;
#define MAVLINK_MSG_ID_PM_ELEC_LEN 20
@@ -30,9 +36,15 @@ typedef struct __mavlink_pm_elec_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @param PwCons
* @param BatStat
* @param PwGen
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -62,9 +74,15 @@ static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t compo
* @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 PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @param PwCons
* @param BatStat
* @param PwGen
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -106,9 +124,15 @@ static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t com
* @brief Send a pm_elec message
* @param chan MAVLink channel to send the message
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @param PwCons
* @param BatStat
* @param PwGen
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -137,7 +161,9 @@ static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons
/**
* @brief Get field PwCons from pm_elec message
*
* @return current power consumption
* @return
*/
static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg)
{
@@ -147,7 +173,9 @@ static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg)
/**
* @brief Get field BatStat from pm_elec message
*
* @return battery status
* @return
*/
static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg)
{
@@ -157,7 +185,9 @@ static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg
/**
* @brief Get field PwGen from pm_elec message
*
* @return Power generation from each module
* @return
*/
static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float *PwGen)
{

View File

@@ -4,10 +4,18 @@
typedef struct __mavlink_sys_stat_t
{
uint8_t gps; ///< gps status
uint8_t act; ///< actuator status
uint8_t mod; ///< module status
uint8_t commRssi; ///< module status
uint8_t gps; ///<
uint8_t act; ///<
uint8_t mod; ///<
uint8_t commRssi; ///<
} mavlink_sys_stat_t;
#define MAVLINK_MSG_ID_SYS_Stat_LEN 4
@@ -32,10 +40,18 @@ typedef struct __mavlink_sys_stat_t
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @param gps
* @param act
* @param mod
* @param commRssi
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -69,10 +85,18 @@ static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t comp
* @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 gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @param gps
* @param act
* @param mod
* @param commRssi
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -118,10 +142,18 @@ static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t co
* @brief Send a sys_stat message
* @param chan MAVLink channel to send the message
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @param gps
* @param act
* @param mod
* @param commRssi
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -154,7 +186,9 @@ static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps
/**
* @brief Get field gps from sys_stat message
*
* @return gps status
* @return
*/
static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
{
@@ -164,7 +198,9 @@ static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
/**
* @brief Get field act from sys_stat message
*
* @return actuator status
* @return
*/
static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
{
@@ -174,7 +210,9 @@ static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
/**
* @brief Get field mod from sys_stat message
*
* @return module status
* @return
*/
static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
{
@@ -184,7 +222,9 @@ static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
/**
* @brief Get field commRssi from sys_stat message
*
* @return module status
* @return
*/
static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg)
{

File diff suppressed because one or more lines are too long

View File

@@ -5,7 +5,7 @@
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
#define MAVLINK_BUILD_DATE "Sat Dec 1 02:07:06 2012"
#define MAVLINK_BUILD_DATE "Wed Jan 9 16:19:38 2013"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 254