mavlink_msg_resource_request.h
Go to the documentation of this file.
00001 // MESSAGE RESOURCE_REQUEST PACKING
00002 
00003 #define MAVLINK_MSG_ID_RESOURCE_REQUEST 142
00004 
00005 typedef struct __mavlink_resource_request_t
00006 {
00007  uint8_t request_id; /*< Request ID. This ID should be re-used when sending back URI contents*/
00008  uint8_t uri_type; /*< The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary*/
00009  uint8_t uri[120]; /*< The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)*/
00010  uint8_t transfer_type; /*< The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream.*/
00011  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).*/
00012 } mavlink_resource_request_t;
00013 
00014 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN 243
00015 #define MAVLINK_MSG_ID_142_LEN 243
00016 
00017 #define MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC 72
00018 #define MAVLINK_MSG_ID_142_CRC 72
00019 
00020 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_URI_LEN 120
00021 #define MAVLINK_MSG_RESOURCE_REQUEST_FIELD_STORAGE_LEN 120
00022 
00023 #define MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST { \
00024         "RESOURCE_REQUEST", \
00025         5, \
00026         {  { "request_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_resource_request_t, request_id) }, \
00027          { "uri_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_resource_request_t, uri_type) }, \
00028          { "uri", NULL, MAVLINK_TYPE_UINT8_T, 120, 2, offsetof(mavlink_resource_request_t, uri) }, \
00029          { "transfer_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 122, offsetof(mavlink_resource_request_t, transfer_type) }, \
00030          { "storage", NULL, MAVLINK_TYPE_UINT8_T, 120, 123, offsetof(mavlink_resource_request_t, storage) }, \
00031          } \
00032 }
00033 
00034 
00048 static inline uint16_t mavlink_msg_resource_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00049                                                        uint8_t request_id, uint8_t uri_type, const uint8_t *uri, uint8_t transfer_type, const uint8_t *storage)
00050 {
00051 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00052         char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN];
00053         _mav_put_uint8_t(buf, 0, request_id);
00054         _mav_put_uint8_t(buf, 1, uri_type);
00055         _mav_put_uint8_t(buf, 122, transfer_type);
00056         _mav_put_uint8_t_array(buf, 2, uri, 120);
00057         _mav_put_uint8_t_array(buf, 123, storage, 120);
00058         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00059 #else
00060         mavlink_resource_request_t packet;
00061         packet.request_id = request_id;
00062         packet.uri_type = uri_type;
00063         packet.transfer_type = transfer_type;
00064         mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
00065         mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
00066         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00067 #endif
00068 
00069         msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST;
00070 #if MAVLINK_CRC_EXTRA
00071     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
00072 #else
00073     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00074 #endif
00075 }
00076 
00090 static inline uint16_t mavlink_msg_resource_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00091                                                            mavlink_message_t* msg,
00092                                                            uint8_t request_id,uint8_t uri_type,const uint8_t *uri,uint8_t transfer_type,const uint8_t *storage)
00093 {
00094 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00095         char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN];
00096         _mav_put_uint8_t(buf, 0, request_id);
00097         _mav_put_uint8_t(buf, 1, uri_type);
00098         _mav_put_uint8_t(buf, 122, transfer_type);
00099         _mav_put_uint8_t_array(buf, 2, uri, 120);
00100         _mav_put_uint8_t_array(buf, 123, storage, 120);
00101         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00102 #else
00103         mavlink_resource_request_t packet;
00104         packet.request_id = request_id;
00105         packet.uri_type = uri_type;
00106         packet.transfer_type = transfer_type;
00107         mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
00108         mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
00109         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00110 #endif
00111 
00112         msg->msgid = MAVLINK_MSG_ID_RESOURCE_REQUEST;
00113 #if MAVLINK_CRC_EXTRA
00114     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
00115 #else
00116     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00117 #endif
00118 }
00119 
00128 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)
00129 {
00130         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);
00131 }
00132 
00142 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)
00143 {
00144         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);
00145 }
00146 
00157 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00158 
00159 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)
00160 {
00161 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00162         char buf[MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN];
00163         _mav_put_uint8_t(buf, 0, request_id);
00164         _mav_put_uint8_t(buf, 1, uri_type);
00165         _mav_put_uint8_t(buf, 122, transfer_type);
00166         _mav_put_uint8_t_array(buf, 2, uri, 120);
00167         _mav_put_uint8_t_array(buf, 123, storage, 120);
00168 #if MAVLINK_CRC_EXTRA
00169     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
00170 #else
00171     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00172 #endif
00173 #else
00174         mavlink_resource_request_t packet;
00175         packet.request_id = request_id;
00176         packet.uri_type = uri_type;
00177         packet.transfer_type = transfer_type;
00178         mav_array_memcpy(packet.uri, uri, sizeof(uint8_t)*120);
00179         mav_array_memcpy(packet.storage, storage, sizeof(uint8_t)*120);
00180 #if MAVLINK_CRC_EXTRA
00181     _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);
00182 #else
00183     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00184 #endif
00185 #endif
00186 }
00187 
00188 #if MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00189 /*
00190   This varient of _send() can be used to save stack space by re-using
00191   memory from the receive buffer.  The caller provides a
00192   mavlink_message_t which is the size of a full mavlink message. This
00193   is usually the receive buffer for the channel, and allows a reply to an
00194   incoming message with minimum stack space usage.
00195  */
00196 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)
00197 {
00198 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00199         char *buf = (char *)msgbuf;
00200         _mav_put_uint8_t(buf, 0, request_id);
00201         _mav_put_uint8_t(buf, 1, uri_type);
00202         _mav_put_uint8_t(buf, 122, transfer_type);
00203         _mav_put_uint8_t_array(buf, 2, uri, 120);
00204         _mav_put_uint8_t_array(buf, 123, storage, 120);
00205 #if MAVLINK_CRC_EXTRA
00206     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN, MAVLINK_MSG_ID_RESOURCE_REQUEST_CRC);
00207 #else
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, buf, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00209 #endif
00210 #else
00211         mavlink_resource_request_t *packet = (mavlink_resource_request_t *)msgbuf;
00212         packet->request_id = request_id;
00213         packet->uri_type = uri_type;
00214         packet->transfer_type = transfer_type;
00215         mav_array_memcpy(packet->uri, uri, sizeof(uint8_t)*120);
00216         mav_array_memcpy(packet->storage, storage, sizeof(uint8_t)*120);
00217 #if MAVLINK_CRC_EXTRA
00218     _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);
00219 #else
00220     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RESOURCE_REQUEST, (const char *)packet, MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00221 #endif
00222 #endif
00223 }
00224 #endif
00225 
00226 #endif
00227 
00228 // MESSAGE RESOURCE_REQUEST UNPACKING
00229 
00230 
00236 static inline uint8_t mavlink_msg_resource_request_get_request_id(const mavlink_message_t* msg)
00237 {
00238         return _MAV_RETURN_uint8_t(msg,  0);
00239 }
00240 
00246 static inline uint8_t mavlink_msg_resource_request_get_uri_type(const mavlink_message_t* msg)
00247 {
00248         return _MAV_RETURN_uint8_t(msg,  1);
00249 }
00250 
00256 static inline uint16_t mavlink_msg_resource_request_get_uri(const mavlink_message_t* msg, uint8_t *uri)
00257 {
00258         return _MAV_RETURN_uint8_t_array(msg, uri, 120,  2);
00259 }
00260 
00266 static inline uint8_t mavlink_msg_resource_request_get_transfer_type(const mavlink_message_t* msg)
00267 {
00268         return _MAV_RETURN_uint8_t(msg,  122);
00269 }
00270 
00276 static inline uint16_t mavlink_msg_resource_request_get_storage(const mavlink_message_t* msg, uint8_t *storage)
00277 {
00278         return _MAV_RETURN_uint8_t_array(msg, storage, 120,  123);
00279 }
00280 
00287 static inline void mavlink_msg_resource_request_decode(const mavlink_message_t* msg, mavlink_resource_request_t* resource_request)
00288 {
00289 #if MAVLINK_NEED_BYTE_SWAP
00290         resource_request->request_id = mavlink_msg_resource_request_get_request_id(msg);
00291         resource_request->uri_type = mavlink_msg_resource_request_get_uri_type(msg);
00292         mavlink_msg_resource_request_get_uri(msg, resource_request->uri);
00293         resource_request->transfer_type = mavlink_msg_resource_request_get_transfer_type(msg);
00294         mavlink_msg_resource_request_get_storage(msg, resource_request->storage);
00295 #else
00296         memcpy(resource_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RESOURCE_REQUEST_LEN);
00297 #endif
00298 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35