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 AUX_STATUS PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_AUX_STATUS 142
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_aux_status_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 8 uint16_t i2c0_err_count; ///< Number of I2C errors since startup
shimniok 0:826c6171fc1b 9 uint16_t i2c1_err_count; ///< Number of I2C errors since startup
shimniok 0:826c6171fc1b 10 uint16_t spi0_err_count; ///< Number of I2C errors since startup
shimniok 0:826c6171fc1b 11 uint16_t spi1_err_count; ///< Number of I2C errors since startup
shimniok 0:826c6171fc1b 12 uint16_t uart_total_err_count; ///< Number of I2C errors since startup
shimniok 0:826c6171fc1b 13
shimniok 0:826c6171fc1b 14 } mavlink_aux_status_t;
shimniok 0:826c6171fc1b 15
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17
shimniok 0:826c6171fc1b 18 /**
shimniok 0:826c6171fc1b 19 * @brief Pack a aux_status 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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 25 * @param i2c0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 26 * @param i2c1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 27 * @param spi0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 28 * @param spi1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 29 * @param uart_total_err_count Number of I2C errors since startup
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_aux_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
shimniok 0:826c6171fc1b 33 {
shimniok 0:826c6171fc1b 34 uint16_t i = 0;
shimniok 0:826c6171fc1b 35 msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
shimniok 0:826c6171fc1b 36
shimniok 0:826c6171fc1b 37 i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 38 i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 39 i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 40 i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 41 i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 42 i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
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 aux_status 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 load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 54 * @param i2c0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 55 * @param i2c1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 56 * @param spi0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 57 * @param spi1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 58 * @param uart_total_err_count Number of I2C errors since startup
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_aux_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
shimniok 0:826c6171fc1b 62 {
shimniok 0:826c6171fc1b 63 uint16_t i = 0;
shimniok 0:826c6171fc1b 64 msg->msgid = MAVLINK_MSG_ID_AUX_STATUS;
shimniok 0:826c6171fc1b 65
shimniok 0:826c6171fc1b 66 i += put_uint16_t_by_index(load, i, msg->payload); // Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 67 i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 68 i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 69 i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 70 i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup
shimniok 0:826c6171fc1b 71 i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup
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 aux_status 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 aux_status C-struct to read the message contents from
shimniok 0:826c6171fc1b 83 */
shimniok 0:826c6171fc1b 84 static inline uint16_t mavlink_msg_aux_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aux_status_t* aux_status)
shimniok 0:826c6171fc1b 85 {
shimniok 0:826c6171fc1b 86 return mavlink_msg_aux_status_pack(system_id, component_id, msg, aux_status->load, aux_status->i2c0_err_count, aux_status->i2c1_err_count, aux_status->spi0_err_count, aux_status->spi1_err_count, aux_status->uart_total_err_count);
shimniok 0:826c6171fc1b 87 }
shimniok 0:826c6171fc1b 88
shimniok 0:826c6171fc1b 89 /**
shimniok 0:826c6171fc1b 90 * @brief Send a aux_status message
shimniok 0:826c6171fc1b 91 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 92 *
shimniok 0:826c6171fc1b 93 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 94 * @param i2c0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 95 * @param i2c1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 96 * @param spi0_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 97 * @param spi1_err_count Number of I2C errors since startup
shimniok 0:826c6171fc1b 98 * @param uart_total_err_count Number of I2C errors since startup
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_aux_status_send(mavlink_channel_t chan, uint16_t load, uint16_t i2c0_err_count, uint16_t i2c1_err_count, uint16_t spi0_err_count, uint16_t spi1_err_count, uint16_t uart_total_err_count)
shimniok 0:826c6171fc1b 103 {
shimniok 0:826c6171fc1b 104 mavlink_message_t msg;
shimniok 0:826c6171fc1b 105 mavlink_msg_aux_status_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, load, i2c0_err_count, i2c1_err_count, spi0_err_count, spi1_err_count, uart_total_err_count);
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 AUX_STATUS UNPACKING
shimniok 0:826c6171fc1b 111
shimniok 0:826c6171fc1b 112 /**
shimniok 0:826c6171fc1b 113 * @brief Get field load from aux_status message
shimniok 0:826c6171fc1b 114 *
shimniok 0:826c6171fc1b 115 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
shimniok 0:826c6171fc1b 116 */
shimniok 0:826c6171fc1b 117 static inline uint16_t mavlink_msg_aux_status_get_load(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 118 {
shimniok 0:826c6171fc1b 119 generic_16bit r;
shimniok 0:826c6171fc1b 120 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 121 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 122 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 123 }
shimniok 0:826c6171fc1b 124
shimniok 0:826c6171fc1b 125 /**
shimniok 0:826c6171fc1b 126 * @brief Get field i2c0_err_count from aux_status message
shimniok 0:826c6171fc1b 127 *
shimniok 0:826c6171fc1b 128 * @return Number of I2C errors since startup
shimniok 0:826c6171fc1b 129 */
shimniok 0:826c6171fc1b 130 static inline uint16_t mavlink_msg_aux_status_get_i2c0_err_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 131 {
shimniok 0:826c6171fc1b 132 generic_16bit r;
shimniok 0:826c6171fc1b 133 r.b[1] = (msg->payload+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 134 r.b[0] = (msg->payload+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 135 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 136 }
shimniok 0:826c6171fc1b 137
shimniok 0:826c6171fc1b 138 /**
shimniok 0:826c6171fc1b 139 * @brief Get field i2c1_err_count from aux_status message
shimniok 0:826c6171fc1b 140 *
shimniok 0:826c6171fc1b 141 * @return Number of I2C errors since startup
shimniok 0:826c6171fc1b 142 */
shimniok 0:826c6171fc1b 143 static inline uint16_t mavlink_msg_aux_status_get_i2c1_err_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 144 {
shimniok 0:826c6171fc1b 145 generic_16bit r;
shimniok 0:826c6171fc1b 146 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 147 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 148 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 149 }
shimniok 0:826c6171fc1b 150
shimniok 0:826c6171fc1b 151 /**
shimniok 0:826c6171fc1b 152 * @brief Get field spi0_err_count from aux_status message
shimniok 0:826c6171fc1b 153 *
shimniok 0:826c6171fc1b 154 * @return Number of I2C errors since startup
shimniok 0:826c6171fc1b 155 */
shimniok 0:826c6171fc1b 156 static inline uint16_t mavlink_msg_aux_status_get_spi0_err_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 157 {
shimniok 0:826c6171fc1b 158 generic_16bit r;
shimniok 0:826c6171fc1b 159 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 160 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 161 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 162 }
shimniok 0:826c6171fc1b 163
shimniok 0:826c6171fc1b 164 /**
shimniok 0:826c6171fc1b 165 * @brief Get field spi1_err_count from aux_status message
shimniok 0:826c6171fc1b 166 *
shimniok 0:826c6171fc1b 167 * @return Number of I2C errors since startup
shimniok 0:826c6171fc1b 168 */
shimniok 0:826c6171fc1b 169 static inline uint16_t mavlink_msg_aux_status_get_spi1_err_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 170 {
shimniok 0:826c6171fc1b 171 generic_16bit r;
shimniok 0:826c6171fc1b 172 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 173 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 174 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 175 }
shimniok 0:826c6171fc1b 176
shimniok 0:826c6171fc1b 177 /**
shimniok 0:826c6171fc1b 178 * @brief Get field uart_total_err_count from aux_status message
shimniok 0:826c6171fc1b 179 *
shimniok 0:826c6171fc1b 180 * @return Number of I2C errors since startup
shimniok 0:826c6171fc1b 181 */
shimniok 0:826c6171fc1b 182 static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 183 {
shimniok 0:826c6171fc1b 184 generic_16bit r;
shimniok 0:826c6171fc1b 185 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0];
shimniok 0:826c6171fc1b 186 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1];
shimniok 0:826c6171fc1b 187 return (uint16_t)r.s;
shimniok 0:826c6171fc1b 188 }
shimniok 0:826c6171fc1b 189
shimniok 0:826c6171fc1b 190 /**
shimniok 0:826c6171fc1b 191 * @brief Decode a aux_status message into a struct
shimniok 0:826c6171fc1b 192 *
shimniok 0:826c6171fc1b 193 * @param msg The message to decode
shimniok 0:826c6171fc1b 194 * @param aux_status C-struct to decode the message contents into
shimniok 0:826c6171fc1b 195 */
shimniok 0:826c6171fc1b 196 static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status)
shimniok 0:826c6171fc1b 197 {
shimniok 0:826c6171fc1b 198 aux_status->load = mavlink_msg_aux_status_get_load(msg);
shimniok 0:826c6171fc1b 199 aux_status->i2c0_err_count = mavlink_msg_aux_status_get_i2c0_err_count(msg);
shimniok 0:826c6171fc1b 200 aux_status->i2c1_err_count = mavlink_msg_aux_status_get_i2c1_err_count(msg);
shimniok 0:826c6171fc1b 201 aux_status->spi0_err_count = mavlink_msg_aux_status_get_spi0_err_count(msg);
shimniok 0:826c6171fc1b 202 aux_status->spi1_err_count = mavlink_msg_aux_status_get_spi1_err_count(msg);
shimniok 0:826c6171fc1b 203 aux_status->uart_total_err_count = mavlink_msg_aux_status_get_uart_total_err_count(msg);
shimniok 0:826c6171fc1b 204 }