mavlink_msg_data_transmission_handshake.h
Go to the documentation of this file.
00001 // MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
00002 
00003 #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
00004 
00005 typedef struct __mavlink_data_transmission_handshake_t
00006 {
00007  uint32_t size; /*< total data size in bytes (set on ACK only)*/
00008  uint16_t width; /*< Width of a matrix or image*/
00009  uint16_t height; /*< Height of a matrix or image*/
00010  uint16_t packets; /*< number of packets beeing sent (set on ACK only)*/
00011  uint8_t type; /*< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)*/
00012  uint8_t payload; /*< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)*/
00013  uint8_t jpg_quality; /*< JPEG quality out of [1,100]*/
00014 } mavlink_data_transmission_handshake_t;
00015 
00016 #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
00017 #define MAVLINK_MSG_ID_130_LEN 13
00018 
00019 #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29
00020 #define MAVLINK_MSG_ID_130_CRC 29
00021 
00022 
00023 
00024 #define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \
00025         "DATA_TRANSMISSION_HANDSHAKE", \
00026         7, \
00027         {  { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
00028          { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
00029          { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
00030          { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
00031          { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
00032          { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
00033          { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
00034          } \
00035 }
00036 
00037 
00053 static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00054                                                        uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
00055 {
00056 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00057         char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
00058         _mav_put_uint32_t(buf, 0, size);
00059         _mav_put_uint16_t(buf, 4, width);
00060         _mav_put_uint16_t(buf, 6, height);
00061         _mav_put_uint16_t(buf, 8, packets);
00062         _mav_put_uint8_t(buf, 10, type);
00063         _mav_put_uint8_t(buf, 11, payload);
00064         _mav_put_uint8_t(buf, 12, jpg_quality);
00065 
00066         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00067 #else
00068         mavlink_data_transmission_handshake_t packet;
00069         packet.size = size;
00070         packet.width = width;
00071         packet.height = height;
00072         packet.packets = packets;
00073         packet.type = type;
00074         packet.payload = payload;
00075         packet.jpg_quality = jpg_quality;
00076 
00077         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00078 #endif
00079 
00080         msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
00081 #if MAVLINK_CRC_EXTRA
00082     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00083 #else
00084     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00085 #endif
00086 }
00087 
00103 static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00104                                                            mavlink_message_t* msg,
00105                                                            uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality)
00106 {
00107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00108         char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
00109         _mav_put_uint32_t(buf, 0, size);
00110         _mav_put_uint16_t(buf, 4, width);
00111         _mav_put_uint16_t(buf, 6, height);
00112         _mav_put_uint16_t(buf, 8, packets);
00113         _mav_put_uint8_t(buf, 10, type);
00114         _mav_put_uint8_t(buf, 11, payload);
00115         _mav_put_uint8_t(buf, 12, jpg_quality);
00116 
00117         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00118 #else
00119         mavlink_data_transmission_handshake_t packet;
00120         packet.size = size;
00121         packet.width = width;
00122         packet.height = height;
00123         packet.packets = packets;
00124         packet.type = type;
00125         packet.payload = payload;
00126         packet.jpg_quality = jpg_quality;
00127 
00128         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00129 #endif
00130 
00131         msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
00132 #if MAVLINK_CRC_EXTRA
00133     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00134 #else
00135     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00136 #endif
00137 }
00138 
00147 static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
00148 {
00149         return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
00150 }
00151 
00161 static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
00162 {
00163         return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
00164 }
00165 
00178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00179 
00180 static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
00181 {
00182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00183         char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
00184         _mav_put_uint32_t(buf, 0, size);
00185         _mav_put_uint16_t(buf, 4, width);
00186         _mav_put_uint16_t(buf, 6, height);
00187         _mav_put_uint16_t(buf, 8, packets);
00188         _mav_put_uint8_t(buf, 10, type);
00189         _mav_put_uint8_t(buf, 11, payload);
00190         _mav_put_uint8_t(buf, 12, jpg_quality);
00191 
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00196 #endif
00197 #else
00198         mavlink_data_transmission_handshake_t packet;
00199         packet.size = size;
00200         packet.width = width;
00201         packet.height = height;
00202         packet.packets = packets;
00203         packet.type = type;
00204         packet.payload = payload;
00205         packet.jpg_quality = jpg_quality;
00206 
00207 #if MAVLINK_CRC_EXTRA
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00209 #else
00210     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00211 #endif
00212 #endif
00213 }
00214 
00215 #if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00216 /*
00217   This varient of _send() can be used to save stack space by re-using
00218   memory from the receive buffer.  The caller provides a
00219   mavlink_message_t which is the size of a full mavlink message. This
00220   is usually the receive buffer for the channel, and allows a reply to an
00221   incoming message with minimum stack space usage.
00222  */
00223 static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
00224 {
00225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00226         char *buf = (char *)msgbuf;
00227         _mav_put_uint32_t(buf, 0, size);
00228         _mav_put_uint16_t(buf, 4, width);
00229         _mav_put_uint16_t(buf, 6, height);
00230         _mav_put_uint16_t(buf, 8, packets);
00231         _mav_put_uint8_t(buf, 10, type);
00232         _mav_put_uint8_t(buf, 11, payload);
00233         _mav_put_uint8_t(buf, 12, jpg_quality);
00234 
00235 #if MAVLINK_CRC_EXTRA
00236     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00237 #else
00238     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00239 #endif
00240 #else
00241         mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf;
00242         packet->size = size;
00243         packet->width = width;
00244         packet->height = height;
00245         packet->packets = packets;
00246         packet->type = type;
00247         packet->payload = payload;
00248         packet->jpg_quality = jpg_quality;
00249 
00250 #if MAVLINK_CRC_EXTRA
00251     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
00252 #else
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00254 #endif
00255 #endif
00256 }
00257 #endif
00258 
00259 #endif
00260 
00261 // MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
00262 
00263 
00269 static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
00270 {
00271         return _MAV_RETURN_uint8_t(msg,  10);
00272 }
00273 
00279 static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
00280 {
00281         return _MAV_RETURN_uint32_t(msg,  0);
00282 }
00283 
00289 static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg)
00290 {
00291         return _MAV_RETURN_uint16_t(msg,  4);
00292 }
00293 
00299 static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg)
00300 {
00301         return _MAV_RETURN_uint16_t(msg,  6);
00302 }
00303 
00309 static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
00310 {
00311         return _MAV_RETURN_uint16_t(msg,  8);
00312 }
00313 
00319 static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
00320 {
00321         return _MAV_RETURN_uint8_t(msg,  11);
00322 }
00323 
00329 static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
00330 {
00331         return _MAV_RETURN_uint8_t(msg,  12);
00332 }
00333 
00340 static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
00341 {
00342 #if MAVLINK_NEED_BYTE_SWAP
00343         data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
00344         data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg);
00345         data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg);
00346         data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
00347         data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
00348         data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
00349         data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
00350 #else
00351         memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
00352 #endif
00353 }


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