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

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Committer:
shimniok
Date:
Wed Jun 20 14:57:48 2012 +0000
Revision:
0:826c6171fc1b
Updated documentation

Who changed what in which revision?

UserRevisionLine numberNew contents of line
shimniok 0:826c6171fc1b 1 // MESSAGE DEBUG_VECT PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_DEBUG_VECT 251
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_debug_vect_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 char name[10]; ///< Name
shimniok 0:826c6171fc1b 8 uint64_t usec; ///< Timestamp
shimniok 0:826c6171fc1b 9 float x; ///< x
shimniok 0:826c6171fc1b 10 float y; ///< y
shimniok 0:826c6171fc1b 11 float z; ///< z
shimniok 0:826c6171fc1b 12
shimniok 0:826c6171fc1b 13 } mavlink_debug_vect_t;
shimniok 0:826c6171fc1b 14
shimniok 0:826c6171fc1b 15 #define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18 /**
shimniok 0:826c6171fc1b 19 * @brief Pack a debug_vect message
shimniok 0:826c6171fc1b 20 * @param system_id ID of this system
shimniok 0:826c6171fc1b 21 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 22 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 23 *
shimniok 0:826c6171fc1b 24 * @param name Name
shimniok 0:826c6171fc1b 25 * @param usec Timestamp
shimniok 0:826c6171fc1b 26 * @param x x
shimniok 0:826c6171fc1b 27 * @param y y
shimniok 0:826c6171fc1b 28 * @param z z
shimniok 0:826c6171fc1b 29 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 30 */
shimniok 0:826c6171fc1b 31 static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
shimniok 0:826c6171fc1b 32 {
shimniok 0:826c6171fc1b 33 uint16_t i = 0;
shimniok 0:826c6171fc1b 34 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
shimniok 0:826c6171fc1b 35
shimniok 0:826c6171fc1b 36 i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name
shimniok 0:826c6171fc1b 37 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
shimniok 0:826c6171fc1b 38 i += put_float_by_index(x, i, msg->payload); // x
shimniok 0:826c6171fc1b 39 i += put_float_by_index(y, i, msg->payload); // y
shimniok 0:826c6171fc1b 40 i += put_float_by_index(z, i, msg->payload); // z
shimniok 0:826c6171fc1b 41
shimniok 0:826c6171fc1b 42 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 43 }
shimniok 0:826c6171fc1b 44
shimniok 0:826c6171fc1b 45 /**
shimniok 0:826c6171fc1b 46 * @brief Pack a debug_vect message
shimniok 0:826c6171fc1b 47 * @param system_id ID of this system
shimniok 0:826c6171fc1b 48 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 49 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 50 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 51 * @param name Name
shimniok 0:826c6171fc1b 52 * @param usec Timestamp
shimniok 0:826c6171fc1b 53 * @param x x
shimniok 0:826c6171fc1b 54 * @param y y
shimniok 0:826c6171fc1b 55 * @param z z
shimniok 0:826c6171fc1b 56 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 57 */
shimniok 0:826c6171fc1b 58 static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const char* name, uint64_t usec, float x, float y, float z)
shimniok 0:826c6171fc1b 59 {
shimniok 0:826c6171fc1b 60 uint16_t i = 0;
shimniok 0:826c6171fc1b 61 msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
shimniok 0:826c6171fc1b 62
shimniok 0:826c6171fc1b 63 i += put_array_by_index((const int8_t*)name, sizeof(char)*10, i, msg->payload); // Name
shimniok 0:826c6171fc1b 64 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp
shimniok 0:826c6171fc1b 65 i += put_float_by_index(x, i, msg->payload); // x
shimniok 0:826c6171fc1b 66 i += put_float_by_index(y, i, msg->payload); // y
shimniok 0:826c6171fc1b 67 i += put_float_by_index(z, i, msg->payload); // z
shimniok 0:826c6171fc1b 68
shimniok 0:826c6171fc1b 69 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 70 }
shimniok 0:826c6171fc1b 71
shimniok 0:826c6171fc1b 72 /**
shimniok 0:826c6171fc1b 73 * @brief Encode a debug_vect struct into a message
shimniok 0:826c6171fc1b 74 *
shimniok 0:826c6171fc1b 75 * @param system_id ID of this system
shimniok 0:826c6171fc1b 76 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 77 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 78 * @param debug_vect C-struct to read the message contents from
shimniok 0:826c6171fc1b 79 */
shimniok 0:826c6171fc1b 80 static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
shimniok 0:826c6171fc1b 81 {
shimniok 0:826c6171fc1b 82 return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
shimniok 0:826c6171fc1b 83 }
shimniok 0:826c6171fc1b 84
shimniok 0:826c6171fc1b 85 /**
shimniok 0:826c6171fc1b 86 * @brief Send a debug_vect message
shimniok 0:826c6171fc1b 87 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 88 *
shimniok 0:826c6171fc1b 89 * @param name Name
shimniok 0:826c6171fc1b 90 * @param usec Timestamp
shimniok 0:826c6171fc1b 91 * @param x x
shimniok 0:826c6171fc1b 92 * @param y y
shimniok 0:826c6171fc1b 93 * @param z z
shimniok 0:826c6171fc1b 94 */
shimniok 0:826c6171fc1b 95 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 96
shimniok 0:826c6171fc1b 97 static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char* name, uint64_t usec, float x, float y, float z)
shimniok 0:826c6171fc1b 98 {
shimniok 0:826c6171fc1b 99 mavlink_message_t msg;
shimniok 0:826c6171fc1b 100 mavlink_msg_debug_vect_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, name, usec, x, y, z);
shimniok 0:826c6171fc1b 101 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 102 }
shimniok 0:826c6171fc1b 103
shimniok 0:826c6171fc1b 104 #endif
shimniok 0:826c6171fc1b 105 // MESSAGE DEBUG_VECT UNPACKING
shimniok 0:826c6171fc1b 106
shimniok 0:826c6171fc1b 107 /**
shimniok 0:826c6171fc1b 108 * @brief Get field name from debug_vect message
shimniok 0:826c6171fc1b 109 *
shimniok 0:826c6171fc1b 110 * @return Name
shimniok 0:826c6171fc1b 111 */
shimniok 0:826c6171fc1b 112 static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char* r_data)
shimniok 0:826c6171fc1b 113 {
shimniok 0:826c6171fc1b 114
shimniok 0:826c6171fc1b 115 memcpy(r_data, msg->payload, sizeof(char)*10);
shimniok 0:826c6171fc1b 116 return sizeof(char)*10;
shimniok 0:826c6171fc1b 117 }
shimniok 0:826c6171fc1b 118
shimniok 0:826c6171fc1b 119 /**
shimniok 0:826c6171fc1b 120 * @brief Get field usec from debug_vect message
shimniok 0:826c6171fc1b 121 *
shimniok 0:826c6171fc1b 122 * @return Timestamp
shimniok 0:826c6171fc1b 123 */
shimniok 0:826c6171fc1b 124 static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 125 {
shimniok 0:826c6171fc1b 126 generic_64bit r;
shimniok 0:826c6171fc1b 127 r.b[7] = (msg->payload+sizeof(char)*10)[0];
shimniok 0:826c6171fc1b 128 r.b[6] = (msg->payload+sizeof(char)*10)[1];
shimniok 0:826c6171fc1b 129 r.b[5] = (msg->payload+sizeof(char)*10)[2];
shimniok 0:826c6171fc1b 130 r.b[4] = (msg->payload+sizeof(char)*10)[3];
shimniok 0:826c6171fc1b 131 r.b[3] = (msg->payload+sizeof(char)*10)[4];
shimniok 0:826c6171fc1b 132 r.b[2] = (msg->payload+sizeof(char)*10)[5];
shimniok 0:826c6171fc1b 133 r.b[1] = (msg->payload+sizeof(char)*10)[6];
shimniok 0:826c6171fc1b 134 r.b[0] = (msg->payload+sizeof(char)*10)[7];
shimniok 0:826c6171fc1b 135 return (uint64_t)r.ll;
shimniok 0:826c6171fc1b 136 }
shimniok 0:826c6171fc1b 137
shimniok 0:826c6171fc1b 138 /**
shimniok 0:826c6171fc1b 139 * @brief Get field x from debug_vect message
shimniok 0:826c6171fc1b 140 *
shimniok 0:826c6171fc1b 141 * @return x
shimniok 0:826c6171fc1b 142 */
shimniok 0:826c6171fc1b 143 static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 144 {
shimniok 0:826c6171fc1b 145 generic_32bit r;
shimniok 0:826c6171fc1b 146 r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[0];
shimniok 0:826c6171fc1b 147 r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[1];
shimniok 0:826c6171fc1b 148 r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[2];
shimniok 0:826c6171fc1b 149 r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t))[3];
shimniok 0:826c6171fc1b 150 return (float)r.f;
shimniok 0:826c6171fc1b 151 }
shimniok 0:826c6171fc1b 152
shimniok 0:826c6171fc1b 153 /**
shimniok 0:826c6171fc1b 154 * @brief Get field y from debug_vect message
shimniok 0:826c6171fc1b 155 *
shimniok 0:826c6171fc1b 156 * @return y
shimniok 0:826c6171fc1b 157 */
shimniok 0:826c6171fc1b 158 static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 159 {
shimniok 0:826c6171fc1b 160 generic_32bit r;
shimniok 0:826c6171fc1b 161 r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 162 r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 163 r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 164 r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 165 return (float)r.f;
shimniok 0:826c6171fc1b 166 }
shimniok 0:826c6171fc1b 167
shimniok 0:826c6171fc1b 168 /**
shimniok 0:826c6171fc1b 169 * @brief Get field z from debug_vect message
shimniok 0:826c6171fc1b 170 *
shimniok 0:826c6171fc1b 171 * @return z
shimniok 0:826c6171fc1b 172 */
shimniok 0:826c6171fc1b 173 static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 174 {
shimniok 0:826c6171fc1b 175 generic_32bit r;
shimniok 0:826c6171fc1b 176 r.b[3] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 177 r.b[2] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 178 r.b[1] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 179 r.b[0] = (msg->payload+sizeof(char)*10+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 180 return (float)r.f;
shimniok 0:826c6171fc1b 181 }
shimniok 0:826c6171fc1b 182
shimniok 0:826c6171fc1b 183 /**
shimniok 0:826c6171fc1b 184 * @brief Decode a debug_vect message into a struct
shimniok 0:826c6171fc1b 185 *
shimniok 0:826c6171fc1b 186 * @param msg The message to decode
shimniok 0:826c6171fc1b 187 * @param debug_vect C-struct to decode the message contents into
shimniok 0:826c6171fc1b 188 */
shimniok 0:826c6171fc1b 189 static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
shimniok 0:826c6171fc1b 190 {
shimniok 0:826c6171fc1b 191 mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
shimniok 0:826c6171fc1b 192 debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
shimniok 0:826c6171fc1b 193 debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
shimniok 0:826c6171fc1b 194 debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
shimniok 0:826c6171fc1b 195 debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
shimniok 0:826c6171fc1b 196 }