mavlink_msg_file_transfer_protocol.h
Go to the documentation of this file.
1 // MESSAGE FILE_TRANSFER_PROTOCOL PACKING
2 
3 #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110
4 
6 {
7  uint8_t target_network; /*< Network ID (0 for broadcast)*/
8  uint8_t target_system; /*< System ID (0 for broadcast)*/
9  uint8_t target_component; /*< Component ID (0 for broadcast)*/
10  uint8_t payload[251]; /*< 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.*/
12 
13 #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
14 #define MAVLINK_MSG_ID_110_LEN 254
15 
16 #define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84
17 #define MAVLINK_MSG_ID_110_CRC 84
18 
19 #define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251
20 
21 #define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \
22  "FILE_TRANSFER_PROTOCOL", \
23  4, \
24  { { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \
25  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \
26  { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \
27  { "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \
28  } \
29 }
30 
31 
44 static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
45  uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
46 {
47 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
49  _mav_put_uint8_t(buf, 0, target_network);
50  _mav_put_uint8_t(buf, 1, target_system);
51  _mav_put_uint8_t(buf, 2, target_component);
52  _mav_put_uint8_t_array(buf, 3, payload, 251);
54 #else
59  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
61 #endif
62 
64 #if MAVLINK_CRC_EXTRA
66 #else
67  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
68 #endif
69 }
70 
83 static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
84  mavlink_message_t* msg,
85  uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload)
86 {
87 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
89  _mav_put_uint8_t(buf, 0, target_network);
90  _mav_put_uint8_t(buf, 1, target_system);
91  _mav_put_uint8_t(buf, 2, target_component);
92  _mav_put_uint8_t_array(buf, 3, payload, 251);
94 #else
99  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
101 #endif
102 
104 #if MAVLINK_CRC_EXTRA
106 #else
107  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
108 #endif
109 }
110 
119 static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
120 {
121  return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
122 }
123 
133 static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
134 {
135  return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
136 }
137 
147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
148 
149 static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
150 {
151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
156  _mav_put_uint8_t_array(buf, 3, payload, 251);
157 #if MAVLINK_CRC_EXTRA
159 #else
160  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
161 #endif
162 #else
165  packet.target_system = target_system;
167  mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
168 #if MAVLINK_CRC_EXTRA
170 #else
171  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
172 #endif
173 #endif
174 }
175 
176 #if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
177 /*
178  This varient of _send() can be used to save stack space by re-using
179  memory from the receive buffer. The caller provides a
180  mavlink_message_t which is the size of a full mavlink message. This
181  is usually the receive buffer for the channel, and allows a reply to an
182  incoming message with minimum stack space usage.
183  */
184 static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
185 {
186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
187  char *buf = (char *)msgbuf;
191  _mav_put_uint8_t_array(buf, 3, payload, 251);
192 #if MAVLINK_CRC_EXTRA
194 #else
195  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
196 #endif
197 #else
199  packet->target_network = target_network;
200  packet->target_system = target_system;
202  mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251);
203 #if MAVLINK_CRC_EXTRA
205 #else
206  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
207 #endif
208 #endif
209 }
210 #endif
211 
212 #endif
213 
214 // MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING
215 
216 
222 static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg)
223 {
224  return _MAV_RETURN_uint8_t(msg, 0);
225 }
226 
232 static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg)
233 {
234  return _MAV_RETURN_uint8_t(msg, 1);
235 }
236 
242 static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg)
243 {
244  return _MAV_RETURN_uint8_t(msg, 2);
245 }
246 
252 static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload)
253 {
254  return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3);
255 }
256 
263 static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol)
264 {
265 #if MAVLINK_NEED_BYTE_SWAP
269  mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload);
270 #else
271  memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
272 #endif
273 }
#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


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