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 MARKER PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_MARKER 130
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_marker_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint16_t id; ///< ID
shimniok 0:826c6171fc1b 8 float x; ///< x position
shimniok 0:826c6171fc1b 9 float y; ///< y position
shimniok 0:826c6171fc1b 10 float z; ///< z position
shimniok 0:826c6171fc1b 11 float roll; ///< roll orientation
shimniok 0:826c6171fc1b 12 float pitch; ///< pitch orientation
shimniok 0:826c6171fc1b 13 float yaw; ///< yaw orientation
shimniok 0:826c6171fc1b 14
shimniok 0:826c6171fc1b 15 } mavlink_marker_t;
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19 /**
shimniok 0:826c6171fc1b 20 * @brief Pack a marker message
shimniok 0:826c6171fc1b 21 * @param system_id ID of this system
shimniok 0:826c6171fc1b 22 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 23 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 24 *
shimniok 0:826c6171fc1b 25 * @param id ID
shimniok 0:826c6171fc1b 26 * @param x x position
shimniok 0:826c6171fc1b 27 * @param y y position
shimniok 0:826c6171fc1b 28 * @param z z position
shimniok 0:826c6171fc1b 29 * @param roll roll orientation
shimniok 0:826c6171fc1b 30 * @param pitch pitch orientation
shimniok 0:826c6171fc1b 31 * @param yaw yaw orientation
shimniok 0:826c6171fc1b 32 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 33 */
shimniok 0:826c6171fc1b 34 static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
shimniok 0:826c6171fc1b 35 {
shimniok 0:826c6171fc1b 36 uint16_t i = 0;
shimniok 0:826c6171fc1b 37 msg->msgid = MAVLINK_MSG_ID_MARKER;
shimniok 0:826c6171fc1b 38
shimniok 0:826c6171fc1b 39 i += put_uint16_t_by_index(id, i, msg->payload); // ID
shimniok 0:826c6171fc1b 40 i += put_float_by_index(x, i, msg->payload); // x position
shimniok 0:826c6171fc1b 41 i += put_float_by_index(y, i, msg->payload); // y position
shimniok 0:826c6171fc1b 42 i += put_float_by_index(z, i, msg->payload); // z position
shimniok 0:826c6171fc1b 43 i += put_float_by_index(roll, i, msg->payload); // roll orientation
shimniok 0:826c6171fc1b 44 i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
shimniok 0:826c6171fc1b 45 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
shimniok 0:826c6171fc1b 46
shimniok 0:826c6171fc1b 47 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 48 }
shimniok 0:826c6171fc1b 49
shimniok 0:826c6171fc1b 50 /**
shimniok 0:826c6171fc1b 51 * @brief Pack a marker message
shimniok 0:826c6171fc1b 52 * @param system_id ID of this system
shimniok 0:826c6171fc1b 53 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 54 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 55 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 56 * @param id ID
shimniok 0:826c6171fc1b 57 * @param x x position
shimniok 0:826c6171fc1b 58 * @param y y position
shimniok 0:826c6171fc1b 59 * @param z z position
shimniok 0:826c6171fc1b 60 * @param roll roll orientation
shimniok 0:826c6171fc1b 61 * @param pitch pitch orientation
shimniok 0:826c6171fc1b 62 * @param yaw yaw orientation
shimniok 0:826c6171fc1b 63 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 64 */
shimniok 0:826c6171fc1b 65 static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
shimniok 0:826c6171fc1b 66 {
shimniok 0:826c6171fc1b 67 uint16_t i = 0;
shimniok 0:826c6171fc1b 68 msg->msgid = MAVLINK_MSG_ID_MARKER;
shimniok 0:826c6171fc1b 69
shimniok 0:826c6171fc1b 70 i += put_uint16_t_by_index(id, i, msg->payload); // ID
shimniok 0:826c6171fc1b 71 i += put_float_by_index(x, i, msg->payload); // x position
shimniok 0:826c6171fc1b 72 i += put_float_by_index(y, i, msg->payload); // y position
shimniok 0:826c6171fc1b 73 i += put_float_by_index(z, i, msg->payload); // z position
shimniok 0:826c6171fc1b 74 i += put_float_by_index(roll, i, msg->payload); // roll orientation
shimniok 0:826c6171fc1b 75 i += put_float_by_index(pitch, i, msg->payload); // pitch orientation
shimniok 0:826c6171fc1b 76 i += put_float_by_index(yaw, i, msg->payload); // yaw orientation
shimniok 0:826c6171fc1b 77
shimniok 0:826c6171fc1b 78 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 79 }
shimniok 0:826c6171fc1b 80
shimniok 0:826c6171fc1b 81 /**
shimniok 0:826c6171fc1b 82 * @brief Encode a marker struct into a message
shimniok 0:826c6171fc1b 83 *
shimniok 0:826c6171fc1b 84 * @param system_id ID of this system
shimniok 0:826c6171fc1b 85 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 86 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 87 * @param marker C-struct to read the message contents from
shimniok 0:826c6171fc1b 88 */
shimniok 0:826c6171fc1b 89 static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker)
shimniok 0:826c6171fc1b 90 {
shimniok 0:826c6171fc1b 91 return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw);
shimniok 0:826c6171fc1b 92 }
shimniok 0:826c6171fc1b 93
shimniok 0:826c6171fc1b 94 /**
shimniok 0:826c6171fc1b 95 * @brief Send a marker message
shimniok 0:826c6171fc1b 96 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 97 *
shimniok 0:826c6171fc1b 98 * @param id ID
shimniok 0:826c6171fc1b 99 * @param x x position
shimniok 0:826c6171fc1b 100 * @param y y position
shimniok 0:826c6171fc1b 101 * @param z z position
shimniok 0:826c6171fc1b 102 * @param roll roll orientation
shimniok 0:826c6171fc1b 103 * @param pitch pitch orientation
shimniok 0:826c6171fc1b 104 * @param yaw yaw orientation
shimniok 0:826c6171fc1b 105 */
shimniok 0:826c6171fc1b 106 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 107
shimniok 0:826c6171fc1b 108 static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw)
shimniok 0:826c6171fc1b 109 {
shimniok 0:826c6171fc1b 110 mavlink_message_t msg;
shimniok 0:826c6171fc1b 111 mavlink_msg_marker_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, id, x, y, z, roll, pitch, yaw);
shimniok 0:826c6171fc1b 112 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 113 }
shimniok 0:826c6171fc1b 114
shimniok 0:826c6171fc1b 115 #endif
shimniok 0:826c6171fc1b 116 // MESSAGE MARKER UNPACKING
shimniok 0:826c6171fc1b 117
shimniok 0:826c6171fc1b 118 /**
shimniok 0:826c6171fc1b 119 * @brief Get field id from marker message
shimniok 0:826c6171fc1b 120 *
shimniok 0:826c6171fc1b 121 * @return ID
shimniok 0:826c6171fc1b 122 */
shimniok 0:826c6171fc1b 123 static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 124 {
shimniok 0:826c6171fc1b 125 generic_16bit r;
shimniok 0:826c6171fc1b 126 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 127 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 128 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 129 }
shimniok 0:826c6171fc1b 130
shimniok 0:826c6171fc1b 131 /**
shimniok 0:826c6171fc1b 132 * @brief Get field x from marker message
shimniok 0:826c6171fc1b 133 *
shimniok 0:826c6171fc1b 134 * @return x position
shimniok 0:826c6171fc1b 135 */
shimniok 0:826c6171fc1b 136 static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 137 {
shimniok 0:826c6171fc1b 138 generic_32bit r;
shimniok 0:826c6171fc1b 139 r.b[3] = (msg->payload+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 140 r.b[2] = (msg->payload+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 141 r.b[1] = (msg->payload+sizeof(uint16_t))[2];
shimniok 0:826c6171fc1b 142 r.b[0] = (msg->payload+sizeof(uint16_t))[3];
shimniok 0:826c6171fc1b 143 return (float)r.f;
shimniok 0:826c6171fc1b 144 }
shimniok 0:826c6171fc1b 145
shimniok 0:826c6171fc1b 146 /**
shimniok 0:826c6171fc1b 147 * @brief Get field y from marker message
shimniok 0:826c6171fc1b 148 *
shimniok 0:826c6171fc1b 149 * @return y position
shimniok 0:826c6171fc1b 150 */
shimniok 0:826c6171fc1b 151 static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 152 {
shimniok 0:826c6171fc1b 153 generic_32bit r;
shimniok 0:826c6171fc1b 154 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 155 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 156 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 157 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 158 return (float)r.f;
shimniok 0:826c6171fc1b 159 }
shimniok 0:826c6171fc1b 160
shimniok 0:826c6171fc1b 161 /**
shimniok 0:826c6171fc1b 162 * @brief Get field z from marker message
shimniok 0:826c6171fc1b 163 *
shimniok 0:826c6171fc1b 164 * @return z position
shimniok 0:826c6171fc1b 165 */
shimniok 0:826c6171fc1b 166 static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 167 {
shimniok 0:826c6171fc1b 168 generic_32bit r;
shimniok 0:826c6171fc1b 169 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 170 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 171 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 172 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 173 return (float)r.f;
shimniok 0:826c6171fc1b 174 }
shimniok 0:826c6171fc1b 175
shimniok 0:826c6171fc1b 176 /**
shimniok 0:826c6171fc1b 177 * @brief Get field roll from marker message
shimniok 0:826c6171fc1b 178 *
shimniok 0:826c6171fc1b 179 * @return roll orientation
shimniok 0:826c6171fc1b 180 */
shimniok 0:826c6171fc1b 181 static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 182 {
shimniok 0:826c6171fc1b 183 generic_32bit r;
shimniok 0:826c6171fc1b 184 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 185 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 186 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 187 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 188 return (float)r.f;
shimniok 0:826c6171fc1b 189 }
shimniok 0:826c6171fc1b 190
shimniok 0:826c6171fc1b 191 /**
shimniok 0:826c6171fc1b 192 * @brief Get field pitch from marker message
shimniok 0:826c6171fc1b 193 *
shimniok 0:826c6171fc1b 194 * @return pitch orientation
shimniok 0:826c6171fc1b 195 */
shimniok 0:826c6171fc1b 196 static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 197 {
shimniok 0:826c6171fc1b 198 generic_32bit r;
shimniok 0:826c6171fc1b 199 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 200 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 201 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 202 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 203 return (float)r.f;
shimniok 0:826c6171fc1b 204 }
shimniok 0:826c6171fc1b 205
shimniok 0:826c6171fc1b 206 /**
shimniok 0:826c6171fc1b 207 * @brief Get field yaw from marker message
shimniok 0:826c6171fc1b 208 *
shimniok 0:826c6171fc1b 209 * @return yaw orientation
shimniok 0:826c6171fc1b 210 */
shimniok 0:826c6171fc1b 211 static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 212 {
shimniok 0:826c6171fc1b 213 generic_32bit r;
shimniok 0:826c6171fc1b 214 r.b[3] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 215 r.b[2] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 216 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 217 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 218 return (float)r.f;
shimniok 0:826c6171fc1b 219 }
shimniok 0:826c6171fc1b 220
shimniok 0:826c6171fc1b 221 /**
shimniok 0:826c6171fc1b 222 * @brief Decode a marker message into a struct
shimniok 0:826c6171fc1b 223 *
shimniok 0:826c6171fc1b 224 * @param msg The message to decode
shimniok 0:826c6171fc1b 225 * @param marker C-struct to decode the message contents into
shimniok 0:826c6171fc1b 226 */
shimniok 0:826c6171fc1b 227 static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker)
shimniok 0:826c6171fc1b 228 {
shimniok 0:826c6171fc1b 229 marker->id = mavlink_msg_marker_get_id(msg);
shimniok 0:826c6171fc1b 230 marker->x = mavlink_msg_marker_get_x(msg);
shimniok 0:826c6171fc1b 231 marker->y = mavlink_msg_marker_get_y(msg);
shimniok 0:826c6171fc1b 232 marker->z = mavlink_msg_marker_get_z(msg);
shimniok 0:826c6171fc1b 233 marker->roll = mavlink_msg_marker_get_roll(msg);
shimniok 0:826c6171fc1b 234 marker->pitch = mavlink_msg_marker_get_pitch(msg);
shimniok 0:826c6171fc1b 235 marker->yaw = mavlink_msg_marker_get_yaw(msg);
shimniok 0:826c6171fc1b 236 }