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

mavlink_msg_debug.h

00001 // MESSAGE DEBUG PACKING
00002 
00003 #define MAVLINK_MSG_ID_DEBUG 255
00004 
00005 typedef struct __mavlink_debug_t 
00006 {
00007     uint8_t ind; ///< index of debug variable
00008     float value; ///< DEBUG value
00009 
00010 } mavlink_debug_t;
00011 
00012 
00013 
00014 /**
00015  * @brief Pack a debug message
00016  * @param system_id ID of this system
00017  * @param component_id ID of this component (e.g. 200 for IMU)
00018  * @param msg The MAVLink message to compress the data into
00019  *
00020  * @param ind index of debug variable
00021  * @param value DEBUG value
00022  * @return length of the message in bytes (excluding serial stream start sign)
00023  */
00024 static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t ind, float value)
00025 {
00026     uint16_t i = 0;
00027     msg->msgid = MAVLINK_MSG_ID_DEBUG;
00028 
00029     i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
00030     i += put_float_by_index(value, i, msg->payload); // DEBUG value
00031 
00032     return mavlink_finalize_message(msg, system_id, component_id, i);
00033 }
00034 
00035 /**
00036  * @brief Pack a debug message
00037  * @param system_id ID of this system
00038  * @param component_id ID of this component (e.g. 200 for IMU)
00039  * @param chan The MAVLink channel this message was sent over
00040  * @param msg The MAVLink message to compress the data into
00041  * @param ind index of debug variable
00042  * @param value DEBUG value
00043  * @return length of the message in bytes (excluding serial stream start sign)
00044  */
00045 static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint8_t ind, float value)
00046 {
00047     uint16_t i = 0;
00048     msg->msgid = MAVLINK_MSG_ID_DEBUG;
00049 
00050     i += put_uint8_t_by_index(ind, i, msg->payload); // index of debug variable
00051     i += put_float_by_index(value, i, msg->payload); // DEBUG value
00052 
00053     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00054 }
00055 
00056 /**
00057  * @brief Encode a debug struct into a message
00058  *
00059  * @param system_id ID of this system
00060  * @param component_id ID of this component (e.g. 200 for IMU)
00061  * @param msg The MAVLink message to compress the data into
00062  * @param debug C-struct to read the message contents from
00063  */
00064 static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
00065 {
00066     return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
00067 }
00068 
00069 /**
00070  * @brief Send a debug message
00071  * @param chan MAVLink channel to send the message
00072  *
00073  * @param ind index of debug variable
00074  * @param value DEBUG value
00075  */
00076 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00077 
00078 static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
00079 {
00080     mavlink_message_t msg;
00081     mavlink_msg_debug_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, ind, value);
00082     mavlink_send_uart(chan, &msg);
00083 }
00084 
00085 #endif
00086 // MESSAGE DEBUG UNPACKING
00087 
00088 /**
00089  * @brief Get field ind from debug message
00090  *
00091  * @return index of debug variable
00092  */
00093 static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
00094 {
00095     return (uint8_t)(msg->payload)[0];
00096 }
00097 
00098 /**
00099  * @brief Get field value from debug message
00100  *
00101  * @return DEBUG value
00102  */
00103 static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
00104 {
00105     generic_32bit r;
00106     r.b[3] = (msg->payload+sizeof(uint8_t))[0];
00107     r.b[2] = (msg->payload+sizeof(uint8_t))[1];
00108     r.b[1] = (msg->payload+sizeof(uint8_t))[2];
00109     r.b[0] = (msg->payload+sizeof(uint8_t))[3];
00110     return (float)r.f;
00111 }
00112 
00113 /**
00114  * @brief Decode a debug message into a struct
00115  *
00116  * @param msg The message to decode
00117  * @param debug C-struct to decode the message contents into
00118  */
00119 static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
00120 {
00121     debug->ind = mavlink_msg_debug_get_ind(msg);
00122     debug->value = mavlink_msg_debug_get_value(msg);
00123 }