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