3 #define MAVLINK_MSG_ID_V2_EXTENSION 248
14 #define MAVLINK_MSG_ID_V2_EXTENSION_LEN 254
15 #define MAVLINK_MSG_ID_248_LEN 254
17 #define MAVLINK_MSG_ID_V2_EXTENSION_CRC 48
18 #define MAVLINK_MSG_ID_248_CRC 48
20 #define MAVLINK_MSG_V2_EXTENSION_FIELD_PAYLOAD_LEN 249
22 #define MAVLINK_MESSAGE_INFO_V2_EXTENSION { \
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) }, \
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)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
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);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
64 mav_array_memcpy(packet.
payload, payload,
sizeof(uint8_t)*249);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
68 msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
70 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
72 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
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)
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
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);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
107 mav_array_memcpy(packet.
payload, payload,
sizeof(uint8_t)*249);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
111 msg->msgid = MAVLINK_MSG_ID_V2_EXTENSION;
112 #if MAVLINK_CRC_EXTRA
113 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
115 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
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)
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)
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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)
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
161 char buf[MAVLINK_MSG_ID_V2_EXTENSION_LEN];
162 _mav_put_uint16_t(buf, 0, message_type);
163 _mav_put_uint8_t(buf, 2, target_network);
164 _mav_put_uint8_t(buf, 3, target_system);
165 _mav_put_uint8_t(buf, 4, target_component);
166 _mav_put_uint8_t_array(buf, 5, payload, 249);
167 #if MAVLINK_CRC_EXTRA
168 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
170 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
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);
182 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (
const char *)&packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
187 #if MAVLINK_MSG_ID_V2_EXTENSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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)
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198 char *buf = (
char *)msgbuf;
199 _mav_put_uint16_t(buf, 0, message_type);
200 _mav_put_uint8_t(buf, 2, target_network);
201 _mav_put_uint8_t(buf, 3, target_system);
202 _mav_put_uint8_t(buf, 4, target_component);
203 _mav_put_uint8_t_array(buf, 5, payload, 249);
204 #if MAVLINK_CRC_EXTRA
205 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN, MAVLINK_MSG_ID_V2_EXTENSION_CRC);
207 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, buf, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
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);
219 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_V2_EXTENSION, (
const char *)packet, MAVLINK_MSG_ID_V2_EXTENSION_LEN);
235 static inline uint8_t mavlink_msg_v2_extension_get_target_network(
const mavlink_message_t* msg)
237 return _MAV_RETURN_uint8_t(msg, 2);
245 static inline uint8_t mavlink_msg_v2_extension_get_target_system(
const mavlink_message_t* msg)
247 return _MAV_RETURN_uint8_t(msg, 3);
255 static inline uint8_t mavlink_msg_v2_extension_get_target_component(
const mavlink_message_t* msg)
257 return _MAV_RETURN_uint8_t(msg, 4);
265 static inline uint16_t mavlink_msg_v2_extension_get_message_type(
const mavlink_message_t* msg)
267 return _MAV_RETURN_uint16_t(msg, 0);
275 static inline uint16_t mavlink_msg_v2_extension_get_payload(
const mavlink_message_t* msg, uint8_t *payload)
277 return _MAV_RETURN_uint8_t_array(msg, payload, 249, 5);
286 static inline void mavlink_msg_v2_extension_decode(
const mavlink_message_t* msg,
mavlink_v2_extension_t* v2_extension)
288 #if MAVLINK_NEED_BYTE_SWAP
289 v2_extension->
message_type = mavlink_msg_v2_extension_get_message_type(msg);
290 v2_extension->
target_network = mavlink_msg_v2_extension_get_target_network(msg);
291 v2_extension->
target_system = mavlink_msg_v2_extension_get_target_system(msg);
292 v2_extension->
target_component = mavlink_msg_v2_extension_get_target_component(msg);
293 mavlink_msg_v2_extension_get_payload(msg, v2_extension->
payload);
295 memcpy(v2_extension, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_V2_EXTENSION_LEN);
uint8_t payload[249]
Variable length payload. The length is defined by the remaining message length when subtracting the h...
Definition: mavlink_msg_v2_extension.h:11
uint8_t target_component
Component ID (0 for broadcast)
Definition: mavlink_msg_v2_extension.h:10
uint8_t target_network
Network ID (0 for broadcast)
Definition: mavlink_msg_v2_extension.h:8
Definition: mavlink_msg_v2_extension.h:5
uint8_t target_system
System ID (0 for broadcast)
Definition: mavlink_msg_v2_extension.h:9
uint16_t message_type
A code that identifies the software component that understands this message (analogous to usb device ...
Definition: mavlink_msg_v2_extension.h:7