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

mavlink_msg_ping.h

00001 // MESSAGE PING PACKING
00002 
00003 #define MAVLINK_MSG_ID_PING 3
00004 
00005 typedef struct __mavlink_ping_t 
00006 {
00007     uint32_t seq; ///< PING sequence
00008     uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00009     uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00010     uint64_t time; ///< Unix timestamp in microseconds
00011 
00012 } mavlink_ping_t;
00013 
00014 
00015 
00016 /**
00017  * @brief Pack a ping message
00018  * @param system_id ID of this system
00019  * @param component_id ID of this component (e.g. 200 for IMU)
00020  * @param msg The MAVLink message to compress the data into
00021  *
00022  * @param seq PING sequence
00023  * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00024  * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00025  * @param time Unix timestamp in microseconds
00026  * @return length of the message in bytes (excluding serial stream start sign)
00027  */
00028 static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
00029 {
00030     uint16_t i = 0;
00031     msg->msgid = MAVLINK_MSG_ID_PING;
00032 
00033     i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
00034     i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00035     i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00036     i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
00037 
00038     return mavlink_finalize_message(msg, system_id, component_id, i);
00039 }
00040 
00041 /**
00042  * @brief Pack a ping message
00043  * @param system_id ID of this system
00044  * @param component_id ID of this component (e.g. 200 for IMU)
00045  * @param chan The MAVLink channel this message was sent over
00046  * @param msg The MAVLink message to compress the data into
00047  * @param seq PING sequence
00048  * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00049  * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00050  * @param time Unix timestamp in microseconds
00051  * @return length of the message in bytes (excluding serial stream start sign)
00052  */
00053 static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
00054 {
00055     uint16_t i = 0;
00056     msg->msgid = MAVLINK_MSG_ID_PING;
00057 
00058     i += put_uint32_t_by_index(seq, i, msg->payload); // PING sequence
00059     i += put_uint8_t_by_index(target_system, i, msg->payload); // 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00060     i += put_uint8_t_by_index(target_component, i, msg->payload); // 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00061     i += put_uint64_t_by_index(time, i, msg->payload); // Unix timestamp in microseconds
00062 
00063     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00064 }
00065 
00066 /**
00067  * @brief Encode a ping struct into a message
00068  *
00069  * @param system_id ID of this system
00070  * @param component_id ID of this component (e.g. 200 for IMU)
00071  * @param msg The MAVLink message to compress the data into
00072  * @param ping C-struct to read the message contents from
00073  */
00074 static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
00075 {
00076     return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
00077 }
00078 
00079 /**
00080  * @brief Send a ping message
00081  * @param chan MAVLink channel to send the message
00082  *
00083  * @param seq PING sequence
00084  * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00085  * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00086  * @param time Unix timestamp in microseconds
00087  */
00088 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00089 
00090 static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
00091 {
00092     mavlink_message_t msg;
00093     mavlink_msg_ping_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, seq, target_system, target_component, time);
00094     mavlink_send_uart(chan, &msg);
00095 }
00096 
00097 #endif
00098 // MESSAGE PING UNPACKING
00099 
00100 /**
00101  * @brief Get field seq from ping message
00102  *
00103  * @return PING sequence
00104  */
00105 static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
00106 {
00107     generic_32bit r;
00108     r.b[3] = (msg->payload)[0];
00109     r.b[2] = (msg->payload)[1];
00110     r.b[1] = (msg->payload)[2];
00111     r.b[0] = (msg->payload)[3];
00112     return (uint32_t)r.i;
00113 }
00114 
00115 /**
00116  * @brief Get field target_system from ping message
00117  *
00118  * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
00119  */
00120 static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
00121 {
00122     return (uint8_t)(msg->payload+sizeof(uint32_t))[0];
00123 }
00124 
00125 /**
00126  * @brief Get field target_component from ping message
00127  *
00128  * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
00129  */
00130 static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
00131 {
00132     return (uint8_t)(msg->payload+sizeof(uint32_t)+sizeof(uint8_t))[0];
00133 }
00134 
00135 /**
00136  * @brief Get field time from ping message
00137  *
00138  * @return Unix timestamp in microseconds
00139  */
00140 static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
00141 {
00142     generic_64bit r;
00143     r.b[7] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[0];
00144     r.b[6] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[1];
00145     r.b[5] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[2];
00146     r.b[4] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[3];
00147     r.b[3] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[4];
00148     r.b[2] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[5];
00149     r.b[1] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[6];
00150     r.b[0] = (msg->payload+sizeof(uint32_t)+sizeof(uint8_t)+sizeof(uint8_t))[7];
00151     return (uint64_t)r.ll;
00152 }
00153 
00154 /**
00155  * @brief Decode a ping message into a struct
00156  *
00157  * @param msg The message to decode
00158  * @param ping C-struct to decode the message contents into
00159  */
00160 static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
00161 {
00162     ping->seq = mavlink_msg_ping_get_seq(msg);
00163     ping->target_system = mavlink_msg_ping_get_target_system(msg);
00164     ping->target_component = mavlink_msg_ping_get_target_component(msg);
00165     ping->time = mavlink_msg_ping_get_time(msg);
00166 }