mavlink_msg_extended_message.h 6.74 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19
// MESSAGE EXTENDED_MESSAGE PACKING

#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255

typedef struct __mavlink_extended_message_t
{
 uint8_t target_system; ///< System which should execute the command
 uint8_t target_component; ///< Component which should execute the command, 0 for all components
 uint8_t protocol_flags; ///< Retransmission / ACK flags
} mavlink_extended_message_t;

#define MAVLINK_MSG_ID_EXTENDED_MESSAGE_LEN 3
#define MAVLINK_MSG_ID_255_LEN 3



#define MAVLINK_MESSAGE_INFO_EXTENDED_MESSAGE { \
	"EXTENDED_MESSAGE", \
	3, \
lm's avatar
lm committed
20 21 22
	{  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_extended_message_t, target_system) }, \
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_extended_message_t, target_component) }, \
         { "protocol_flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_extended_message_t, protocol_flags) }, \
23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40
         } \
}


/**
 * @brief Pack a extended_message 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 which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param protocol_flags Retransmission / ACK flags
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_extended_message_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{
LM's avatar
LM committed
41 42 43 44 45 46 47 48 49 50 51 52
#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, protocol_flags);

        memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
	mavlink_extended_message_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.protocol_flags = protocol_flags;
53

LM's avatar
LM committed
54 55
        memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif
56

LM's avatar
LM committed
57
	msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75
	return mavlink_finalize_message(msg, system_id, component_id, 3, 247);
}

/**
 * @brief Pack a extended_message 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 which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param protocol_flags Retransmission / ACK flags
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_extended_message_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 protocol_flags)
{
LM's avatar
LM committed
76 77 78 79 80
#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, protocol_flags);
81

LM's avatar
LM committed
82 83 84 85 86 87
        memcpy(_MAV_PAYLOAD(msg), buf, 3);
#else
	mavlink_extended_message_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.protocol_flags = protocol_flags;
88

LM's avatar
LM committed
89 90 91 92
        memcpy(_MAV_PAYLOAD(msg), &packet, 3);
#endif

	msg->msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 247);
}

/**
 * @brief Encode a extended_message 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 extended_message C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_extended_message_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_extended_message_t* extended_message)
{
	return mavlink_msg_extended_message_pack(system_id, component_id, msg, extended_message->target_system, extended_message->target_component, extended_message->protocol_flags);
}

/**
 * @brief Send a extended_message message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system System which should execute the command
 * @param target_component Component which should execute the command, 0 for all components
 * @param protocol_flags Retransmission / ACK flags
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

static inline void mavlink_msg_extended_message_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t protocol_flags)
{
LM's avatar
LM committed
121 122 123 124 125
#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, protocol_flags);
126

LM's avatar
LM committed
127 128 129 130 131 132
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, buf, 3, 247);
#else
	mavlink_extended_message_t packet;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.protocol_flags = protocol_flags;
133

LM's avatar
LM committed
134 135
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EXTENDED_MESSAGE, (const char *)&packet, 3, 247);
#endif
136 137 138 139 140 141 142 143 144 145 146 147 148 149
}

#endif

// MESSAGE EXTENDED_MESSAGE UNPACKING


/**
 * @brief Get field target_system from extended_message message
 *
 * @return System which should execute the command
 */
static inline uint8_t mavlink_msg_extended_message_get_target_system(const mavlink_message_t* msg)
{
LM's avatar
LM committed
150
	return _MAV_RETURN_uint8_t(msg,  0);
151 152 153 154 155 156 157 158 159
}

/**
 * @brief Get field target_component from extended_message message
 *
 * @return Component which should execute the command, 0 for all components
 */
static inline uint8_t mavlink_msg_extended_message_get_target_component(const mavlink_message_t* msg)
{
LM's avatar
LM committed
160
	return _MAV_RETURN_uint8_t(msg,  1);
161 162 163 164 165 166 167 168 169
}

/**
 * @brief Get field protocol_flags from extended_message message
 *
 * @return Retransmission / ACK flags
 */
static inline uint8_t mavlink_msg_extended_message_get_protocol_flags(const mavlink_message_t* msg)
{
LM's avatar
LM committed
170
	return _MAV_RETURN_uint8_t(msg,  2);
171 172 173 174 175 176 177 178 179 180 181 182 183 184 185
}

/**
 * @brief Decode a extended_message message into a struct
 *
 * @param msg The message to decode
 * @param extended_message C-struct to decode the message contents into
 */
static inline void mavlink_msg_extended_message_decode(const mavlink_message_t* msg, mavlink_extended_message_t* extended_message)
{
#if MAVLINK_NEED_BYTE_SWAP
	extended_message->target_system = mavlink_msg_extended_message_get_target_system(msg);
	extended_message->target_component = mavlink_msg_extended_message_get_target_component(msg);
	extended_message->protocol_flags = mavlink_msg_extended_message_get_protocol_flags(msg);
#else
LM's avatar
LM committed
186
	memcpy(extended_message, _MAV_PAYLOAD(msg), 3);
187 188
#endif
}