Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_data_transmission_handshake.h Source File

mavlink_msg_data_transmission_handshake.h

00001 // MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
00002 
00003 #define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 170
00004 
00005 typedef struct __mavlink_data_transmission_handshake_t 
00006 {
00007     uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00008     uint32_t size; ///< total data size in bytes (set on ACK only)
00009     uint8_t packets; ///< number of packets beeing sent (set on ACK only)
00010     uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00011     uint8_t jpg_quality; ///< JPEG quality out of [1,100]
00012 
00013 } mavlink_data_transmission_handshake_t;
00014 
00015 
00016 
00017 /**
00018  * @brief Pack a data_transmission_handshake message
00019  * @param system_id ID of this system
00020  * @param component_id ID of this component (e.g. 200 for IMU)
00021  * @param msg The MAVLink message to compress the data into
00022  *
00023  * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00024  * @param size total data size in bytes (set on ACK only)
00025  * @param packets number of packets beeing sent (set on ACK only)
00026  * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00027  * @param jpg_quality JPEG quality out of [1,100]
00028  * @return length of the message in bytes (excluding serial stream start sign)
00029  */
00030 static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
00031 {
00032     uint16_t i = 0;
00033     msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
00034 
00035     i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00036     i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
00037     i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
00038     i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00039     i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
00040 
00041     return mavlink_finalize_message(msg, system_id, component_id, i);
00042 }
00043 
00044 /**
00045  * @brief Pack a data_transmission_handshake message
00046  * @param system_id ID of this system
00047  * @param component_id ID of this component (e.g. 200 for IMU)
00048  * @param chan The MAVLink channel this message was sent over
00049  * @param msg The MAVLink message to compress the data into
00050  * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00051  * @param size total data size in bytes (set on ACK only)
00052  * @param packets number of packets beeing sent (set on ACK only)
00053  * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00054  * @param jpg_quality JPEG quality out of [1,100]
00055  * @return length of the message in bytes (excluding serial stream start sign)
00056  */
00057 static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
00058 {
00059     uint16_t i = 0;
00060     msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
00061 
00062     i += put_uint8_t_by_index(type, i, msg->payload); // type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00063     i += put_uint32_t_by_index(size, i, msg->payload); // total data size in bytes (set on ACK only)
00064     i += put_uint8_t_by_index(packets, i, msg->payload); // number of packets beeing sent (set on ACK only)
00065     i += put_uint8_t_by_index(payload, i, msg->payload); // payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00066     i += put_uint8_t_by_index(jpg_quality, i, msg->payload); // JPEG quality out of [1,100]
00067 
00068     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00069 }
00070 
00071 /**
00072  * @brief Encode a data_transmission_handshake struct into a message
00073  *
00074  * @param system_id ID of this system
00075  * @param component_id ID of this component (e.g. 200 for IMU)
00076  * @param msg The MAVLink message to compress the data into
00077  * @param data_transmission_handshake C-struct to read the message contents from
00078  */
00079 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)
00080 {
00081     return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
00082 }
00083 
00084 /**
00085  * @brief Send a data_transmission_handshake message
00086  * @param chan MAVLink channel to send the message
00087  *
00088  * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00089  * @param size total data size in bytes (set on ACK only)
00090  * @param packets number of packets beeing sent (set on ACK only)
00091  * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00092  * @param jpg_quality JPEG quality out of [1,100]
00093  */
00094 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00095 
00096 static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint8_t packets, uint8_t payload, uint8_t jpg_quality)
00097 {
00098     mavlink_message_t msg;
00099     mavlink_msg_data_transmission_handshake_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, type, size, packets, payload, jpg_quality);
00100     mavlink_send_uart(chan, &msg);
00101 }
00102 
00103 #endif
00104 // MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
00105 
00106 /**
00107  * @brief Get field type from data_transmission_handshake message
00108  *
00109  * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
00110  */
00111 static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
00112 {
00113     return (uint8_t)(msg->payload)[0];
00114 }
00115 
00116 /**
00117  * @brief Get field size from data_transmission_handshake message
00118  *
00119  * @return total data size in bytes (set on ACK only)
00120  */
00121 static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
00122 {
00123     generic_32bit r;
00124     r.b[3] = (msg->payload+sizeof(uint8_t))[0];
00125     r.b[2] = (msg->payload+sizeof(uint8_t))[1];
00126     r.b[1] = (msg->payload+sizeof(uint8_t))[2];
00127     r.b[0] = (msg->payload+sizeof(uint8_t))[3];
00128     return (uint32_t)r.i;
00129 }
00130 
00131 /**
00132  * @brief Get field packets from data_transmission_handshake message
00133  *
00134  * @return number of packets beeing sent (set on ACK only)
00135  */
00136 static inline uint8_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
00137 {
00138     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t))[0];
00139 }
00140 
00141 /**
00142  * @brief Get field payload from data_transmission_handshake message
00143  *
00144  * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
00145  */
00146 static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
00147 {
00148     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t))[0];
00149 }
00150 
00151 /**
00152  * @brief Get field jpg_quality from data_transmission_handshake message
00153  *
00154  * @return JPEG quality out of [1,100]
00155  */
00156 static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
00157 {
00158     return (uint8_t)(msg->payload+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00159 }
00160 
00161 /**
00162  * @brief Decode a data_transmission_handshake message into a struct
00163  *
00164  * @param msg The message to decode
00165  * @param data_transmission_handshake C-struct to decode the message contents into
00166  */
00167 static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
00168 {
00169     data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
00170     data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
00171     data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
00172     data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
00173     data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
00174 }