mavlink_msg_resource_request.h
Go to the documentation of this file.
1 // MESSAGE RESOURCE_REQUEST PACKING
2 
3 #define MAVLINK_MSG_ID_RESOURCE_REQUEST 142
4 
6 {
7  uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/
8  uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/
9  uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/
10  uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/
11  uint8_t storage[120]; /*< The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP).*/
13 
14 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243
15 #define MAVLINK_MSG_ID_142_LEN 243
16 
17 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72
18 #define MAVLINK_MSG_ID_142_CRC 72
19 
20 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120
21 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120
22 
23 #define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \
24  "RESOURCE_REQUEST", \
25  5, \
26  { { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \
27  { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \
28  { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \
29  { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \
30  { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \
31  } \
32 }
33 
34 
48 static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
49  uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
50 {
51 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
53  _mav_put_uint8_t(buf, 0, request_id);
54  _mav_put_uint8_t(buf, 1, uri_type);
55  _mav_put_uint8_t(buf, 122, transfer_type);
56  _mav_put_uint8_t_array(buf, 2, uri, 120);
57  _mav_put_uint8_t_array(buf, 123, storage, 120);
59 #else
61  packet.request_id = request_id;
62  packet.uri_type = uri_type;
64  mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
65  mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
67 #endif
68 
70 #if MAVLINK_CRC_EXTRA
72 #else
73  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
74 #endif
75 }
76 
90 static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91  mavlink_message_t* msg,
92  uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage)
93 {
94 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
96  _mav_put_uint8_t(buf, 0, request_id);
97  _mav_put_uint8_t(buf, 1, uri_type);
98  _mav_put_uint8_t(buf, 122, transfer_type);
99  _mav_put_uint8_t_array(buf, 2, uri, 120);
100  _mav_put_uint8_t_array(buf, 123, storage, 120);
102 #else
104  packet.request_id = request_id;
105  packet.uri_type = uri_type;
106  packet.transfer_type = transfer_type;
107  mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
108  mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
110 #endif
111 
112  msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST;
113 #if MAVLINK_CRC_EXTRA
115 #else
116  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
117 #endif
118 }
119 
128 static inline uint16_t mavlink_msg_resource_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request)
129 {
130  return mavlink_msg_resource_request_pack(system_id, component_id, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage);
131 }
132 
142 static inline uint16_t mavlink_msg_resource_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_resource_request_t* resource_request)
143 {
144  return mavlink_msg_resource_request_pack_chan(system_id, component_id, chan, msg, resource_request->request_id, resource_request->uri_type, resource_request->uri, resource_request->transfer_type, resource_request->storage);
145 }
146 
157 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
158 
159 static inline void mavlink_msg_resource_request_send(mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
160 {
161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
163  _mav_put_uint8_t(buf, 0, request_id);
164  _mav_put_uint8_t(buf, 1, uri_type);
165  _mav_put_uint8_t(buf, 122, transfer_type);
166  _mav_put_uint8_t_array(buf, 2, uri, 120);
167  _mav_put_uint8_t_array(buf, 123, storage, 120);
168 #if MAVLINK_CRC_EXTRA
170 #else
171  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
172 #endif
173 #else
175  packet.request_id = request_id;
176  packet.uri_type = uri_type;
177  packet.transfer_type = transfer_type;
178  mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
179  mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
180 #if MAVLINK_CRC_EXTRA
181  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
182 #else
183  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
184 #endif
185 #endif
186 }
187 
188 #if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
189 /*
190  This varient of _send() can be used to save stack space by re-using
191  memory from the receive buffer. The caller provides a
192  mavlink_message_t which is the size of a full mavlink message. This
193  is usually the receive buffer for the channel, and allows a reply to an
194  incoming message with minimum stack space usage.
195  */
196 static inline void mavlink_msg_resource_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
197 {
198 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
199  char *buf = (char *)msgbuf;
200  _mav_put_uint8_t(buf, 0, request_id);
201  _mav_put_uint8_t(buf, 1, uri_type);
202  _mav_put_uint8_t(buf, 122, transfer_type);
203  _mav_put_uint8_t_array(buf, 2, uri, 120);
204  _mav_put_uint8_t_array(buf, 123, storage, 120);
205 #if MAVLINK_CRC_EXTRA
207 #else
208  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
209 #endif
210 #else
212  packet->request_id = request_id;
213  packet->uri_type = uri_type;
214  packet->transfer_type = transfer_type;
215  mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120);
216  mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120);
217 #if MAVLINK_CRC_EXTRA
218  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
219 #else
220  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
221 #endif
222 #endif
223 }
224 #endif
225 
226 #endif
227 
228 // MESSAGE RESOURCE_REQUEST UNPACKING
229 
230 
236 static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg)
237 {
238  return _MAV_RETURN_uint8_t(msg, 0);
239 }
240 
246 static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg)
247 {
248  return _MAV_RETURN_uint8_t(msg, 1);
249 }
250 
256 static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri)
257 {
258  return _MAV_RETURN_uint8_t_array(msg, uri, 120, 2);
259 }
260 
266 static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg)
267 {
268  return _MAV_RETURN_uint8_t(msg, 122);
269 }
270 
276 static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage)
277 {
278  return _MAV_RETURN_uint8_t_array(msg, storage, 120, 123);
279 }
280 
287 static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request)
288 {
289 #if MAVLINK_NEED_BYTE_SWAP
291  resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg);
292  mavlink_msg_resource_request_get_uri(msg, resource_request->uri);
294  mavlink_msg_resource_request_get_storage(msg, resource_request->storage);
295 #else
296  memcpy(resource_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
297 #endif
298 }
#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:47