mavlink_msg_v2_extension.h
Go to the documentation of this file.
1 // MESSAGE V2_EXTENSION PACKING
2 
3 #define MAVLINK_MSG_ID_V2_EXTENSION 248
4 
6 {
7  uint16_t message_type; /*< A code that identifies the software component that understands this message (analogous to usb device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to https://github.com/mavlink/mavlink/extension-message-ids.xml. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase.*/
8  uint8_t target_network; /*< Network ID (0 for broadcast)*/
9  uint8_t target_system; /*< System ID (0 for broadcast)*/
10  uint8_t target_component; /*< Component ID (0 for broadcast)*/
11  uint8_t payload[249]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.*/
13 
14 #define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254
15 #define MAVLINK_MSG_ID_248_LEN 254
16 
17 #define MAVLINK_MSG_ID_V2_EXTENSION_CRC 8
18 #define MAVLINK_MSG_ID_248_CRC 8
19 
20 #define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249
21 
22 #define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \
23  "V2_EXTENSION", \
24  5, \
25  { { "message_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_v2_extension_t, message_type) }, \
26  { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_v2_extension_t, target_network) }, \
27  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_v2_extension_t, target_system) }, \
28  { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_v2_extension_t, target_component) }, \
29  { "payload", NULL, MAVLINK_TYPE_UINT8_T, 249, 5, offsetof(mavlink_v2_extension_t, payload) }, \
30  } \
31 }
32 
33 
47 static inline uint16_t mavlink_msg_v2_extension_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48  uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
49 {
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
52  _mav_put_uint16_t(buf, 0, message_type);
53  _mav_put_uint8_t(buf, 2, target_network);
54  _mav_put_uint8_t(buf, 3, target_system);
55  _mav_put_uint8_t(buf, 4, target_component);
56  _mav_put_uint8_t_array(buf, 5, payload, 249);
58 #else
60  packet.message_type = message_type;
64  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
66 #endif
67 
68  msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
69 #if MAVLINK_CRC_EXTRA
71 #else
72  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
73 #endif
74 }
75 
89 static inline uint16_t mavlink_msg_v2_extension_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
90  mavlink_message_t* msg,
91  uint8_t target_network,uint8_t target_system,uint8_t target_component,uint16_t message_type,const uint8_t *payload)
92 {
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95  _mav_put_uint16_t(buf, 0, message_type);
96  _mav_put_uint8_t(buf, 2, target_network);
97  _mav_put_uint8_t(buf, 3, target_system);
98  _mav_put_uint8_t(buf, 4, target_component);
99  _mav_put_uint8_t_array(buf, 5, payload, 249);
101 #else
102  mavlink_v2_extension_t packet;
103  packet.message_type = message_type;
105  packet.target_system = target_system;
107  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
109 #endif
110 
111  msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
112 #if MAVLINK_CRC_EXTRA
114 #else
115  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
116 #endif
117 }
118 
127 static inline uint16_t mavlink_msg_v2_extension_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
128 {
129  return mavlink_msg_v2_extension_pack(system_id, component_id, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
130 }
131 
141 static inline uint16_t mavlink_msg_v2_extension_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_v2_extension_t* v2_extension)
142 {
143  return mavlink_msg_v2_extension_pack_chan(system_id, component_id, chan, msg, v2_extension->target_network, v2_extension->target_system, v2_extension->target_component, v2_extension->message_type, v2_extension->payload);
144 }
145 
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
157 
158 static inline void mavlink_msg_v2_extension_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
159 {
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
166  _mav_put_uint8_t_array(buf, 5, payload, 249);
167 #if MAVLINK_CRC_EXTRA
169 #else
170  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
171 #endif
172 #else
173  mavlink_v2_extension_t packet;
174  packet.message_type = message_type;
176  packet.target_system = target_system;
178  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*249);
179 #if MAVLINK_CRC_EXTRA
180  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
181 #else
182  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
183 #endif
184 #endif
185 }
186 
187 #if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
188 /*
189  This varient of _send() can be used to save stack space by re-using
190  memory from the receive buffer. The caller provides a
191  mavlink_message_t which is the size of a full mavlink message. This
192  is usually the receive buffer for the channel, and allows a reply to an
193  incoming message with minimum stack space usage.
194  */
195 static inline void mavlink_msg_v2_extension_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, uint16_t message_type, const uint8_t *payload)
196 {
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198  char *buf = (char *)msgbuf;
203  _mav_put_uint8_t_array(buf, 5, payload, 249);
204 #if MAVLINK_CRC_EXTRA
206 #else
207  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
208 #endif
209 #else
211  packet->message_type = message_type;
212  packet->target_network = target_network;
213  packet->target_system = target_system;
215  mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*249);
216 #if MAVLINK_CRC_EXTRA
217  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
218 #else
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
220 #endif
221 #endif
222 }
223 #endif
224 
225 #endif
226 
227 // MESSAGE V2_EXTENSION UNPACKING
228 
229 
235 static inline uint8_t mavlink_msg_v2_extension_get_target_network(const mavlink_message_t* msg)
236 {
237  return _MAV_RETURN_uint8_t(msg, 2);
238 }
239 
245 static inline uint8_t mavlink_msg_v2_extension_get_target_system(const mavlink_message_t* msg)
246 {
247  return _MAV_RETURN_uint8_t(msg, 3);
248 }
249 
255 static inline uint8_t mavlink_msg_v2_extension_get_target_component(const mavlink_message_t* msg)
256 {
257  return _MAV_RETURN_uint8_t(msg, 4);
258 }
259 
265 static inline uint16_t mavlink_msg_v2_extension_get_message_type(const mavlink_message_t* msg)
266 {
267  return _MAV_RETURN_uint16_t(msg, 0);
268 }
269 
275 static inline uint16_t mavlink_msg_v2_extension_get_payload(const mavlink_message_t* msg, uint8_t *payload)
276 {
277  return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5);
278 }
279 
286 static inline void mavlink_msg_v2_extension_decode(const mavlink_message_t* msg, mavlink_v2_extension_t* v2_extension)
287 {
288 #if MAVLINK_NEED_BYTE_SWAP
293  mavlink_msg_v2_extension_get_payload(msg, v2_extension->payload);
294 #else
295  memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN);
296 #endif
297 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
Definition: protocol.h:197
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:295
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47