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_encapsulated_data.h Source File

mavlink_msg_encapsulated_data.h

00001 // MESSAGE ENCAPSULATED_DATA PACKING
00002 
00003 #define MAVLINK_MSG_ID_ENCAPSULATED_DATA 171
00004 
00005 typedef struct __mavlink_encapsulated_data_t 
00006 {
00007     uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
00008     uint8_t data[253]; ///< image data bytes
00009 
00010 } mavlink_encapsulated_data_t;
00011 
00012 #define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
00013 
00014 
00015 /**
00016  * @brief Pack a encapsulated_data message
00017  * @param system_id ID of this system
00018  * @param component_id ID of this component (e.g. 200 for IMU)
00019  * @param msg The MAVLink message to compress the data into
00020  *
00021  * @param seqnr sequence number (starting with 0 on every transmission)
00022  * @param data image data bytes
00023  * @return length of the message in bytes (excluding serial stream start sign)
00024  */
00025 static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
00026 {
00027     uint16_t i = 0;
00028     msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
00029 
00030     i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
00031     i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
00032 
00033     return mavlink_finalize_message(msg, system_id, component_id, i);
00034 }
00035 
00036 /**
00037  * @brief Pack a encapsulated_data message
00038  * @param system_id ID of this system
00039  * @param component_id ID of this component (e.g. 200 for IMU)
00040  * @param chan The MAVLink channel this message was sent over
00041  * @param msg The MAVLink message to compress the data into
00042  * @param seqnr sequence number (starting with 0 on every transmission)
00043  * @param data image data bytes
00044  * @return length of the message in bytes (excluding serial stream start sign)
00045  */
00046 static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t seqnr, const uint8_t* data)
00047 {
00048     uint16_t i = 0;
00049     msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
00050 
00051     i += put_uint16_t_by_index(seqnr, i, msg->payload); // sequence number (starting with 0 on every transmission)
00052     i += put_array_by_index((const int8_t*)data, sizeof(uint8_t)*253, i, msg->payload); // image data bytes
00053 
00054     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00055 }
00056 
00057 /**
00058  * @brief Encode a encapsulated_data struct into a message
00059  *
00060  * @param system_id ID of this system
00061  * @param component_id ID of this component (e.g. 200 for IMU)
00062  * @param msg The MAVLink message to compress the data into
00063  * @param encapsulated_data C-struct to read the message contents from
00064  */
00065 static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
00066 {
00067     return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
00068 }
00069 
00070 /**
00071  * @brief Send a encapsulated_data message
00072  * @param chan MAVLink channel to send the message
00073  *
00074  * @param seqnr sequence number (starting with 0 on every transmission)
00075  * @param data image data bytes
00076  */
00077 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00078 
00079 static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t* data)
00080 {
00081     mavlink_message_t msg;
00082     mavlink_msg_encapsulated_data_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seqnr, data);
00083     mavlink_send_uart(chan, &msg);
00084 }
00085 
00086 #endif
00087 // MESSAGE ENCAPSULATED_DATA UNPACKING
00088 
00089 /**
00090  * @brief Get field seqnr from encapsulated_data message
00091  *
00092  * @return sequence number (starting with 0 on every transmission)
00093  */
00094 static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
00095 {
00096     generic_16bit r;
00097     r.b[1] = (msg->payload)[0];
00098     r.b[0] = (msg->payload)[1];
00099     return (uint16_t)r.s;
00100 }
00101 
00102 /**
00103  * @brief Get field data from encapsulated_data message
00104  *
00105  * @return image data bytes
00106  */
00107 static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t* r_data)
00108 {
00109 
00110     memcpy(r_data, msg->payload+sizeof(uint16_t), sizeof(uint8_t)*253);
00111     return sizeof(uint8_t)*253;
00112 }
00113 
00114 /**
00115  * @brief Decode a encapsulated_data message into a struct
00116  *
00117  * @param msg The message to decode
00118  * @param encapsulated_data C-struct to decode the message contents into
00119  */
00120 static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
00121 {
00122     encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
00123     mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
00124 }