Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_aux_status.h
00001 // MESSAGE AUX_STATUS PACKING 00002 00003 #define MAVLINK_MSG_ID_AUX_STATUS 142 00004 00005 typedef struct __mavlink_aux_status_t 00006 { 00007 uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 00008 uint16_t i2c0_err_count; ///< Number of I2C errors since startup 00009 uint16_t i2c1_err_count; ///< Number of I2C errors since startup 00010 uint16_t spi0_err_count; ///< Number of I2C errors since startup 00011 uint16_t spi1_err_count; ///< Number of I2C errors since startup 00012 uint16_t uart_total_err_count; ///< Number of I2C errors since startup 00013 00014 } mavlink_aux_status_t; 00015 00016 00017 00018 /** 00019 * @brief Pack a aux_status message 00020 * @param system_id ID of this system 00021 * @param component_id ID of this component (e.g. 200 for IMU) 00022 * @param msg The MAVLink message to compress the data into 00023 * 00024 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 00025 * @param i2c0_err_count Number of I2C errors since startup 00026 * @param i2c1_err_count Number of I2C errors since startup 00027 * @param spi0_err_count Number of I2C errors since startup 00028 * @param spi1_err_count Number of I2C errors since startup 00029 * @param uart_total_err_count Number of I2C errors since startup 00030 * @return length of the message in bytes (excluding serial stream start sign) 00031 */ 00032 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) 00033 { 00034 uint16_t i = 0; 00035 msg->msgid = MAVLINK_MSG_ID_AUX_STATUS; 00036 00037 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 00038 i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup 00039 i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup 00040 i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup 00041 i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup 00042 i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup 00043 00044 return mavlink_finalize_message(msg, system_id, component_id, i); 00045 } 00046 00047 /** 00048 * @brief Pack a aux_status message 00049 * @param system_id ID of this system 00050 * @param component_id ID of this component (e.g. 200 for IMU) 00051 * @param chan The MAVLink channel this message was sent over 00052 * @param msg The MAVLink message to compress the data into 00053 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 00054 * @param i2c0_err_count Number of I2C errors since startup 00055 * @param i2c1_err_count Number of I2C errors since startup 00056 * @param spi0_err_count Number of I2C errors since startup 00057 * @param spi1_err_count Number of I2C errors since startup 00058 * @param uart_total_err_count Number of I2C errors since startup 00059 * @return length of the message in bytes (excluding serial stream start sign) 00060 */ 00061 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) 00062 { 00063 uint16_t i = 0; 00064 msg->msgid = MAVLINK_MSG_ID_AUX_STATUS; 00065 00066 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 00067 i += put_uint16_t_by_index(i2c0_err_count, i, msg->payload); // Number of I2C errors since startup 00068 i += put_uint16_t_by_index(i2c1_err_count, i, msg->payload); // Number of I2C errors since startup 00069 i += put_uint16_t_by_index(spi0_err_count, i, msg->payload); // Number of I2C errors since startup 00070 i += put_uint16_t_by_index(spi1_err_count, i, msg->payload); // Number of I2C errors since startup 00071 i += put_uint16_t_by_index(uart_total_err_count, i, msg->payload); // Number of I2C errors since startup 00072 00073 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00074 } 00075 00076 /** 00077 * @brief Encode a aux_status struct into a message 00078 * 00079 * @param system_id ID of this system 00080 * @param component_id ID of this component (e.g. 200 for IMU) 00081 * @param msg The MAVLink message to compress the data into 00082 * @param aux_status C-struct to read the message contents from 00083 */ 00084 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) 00085 { 00086 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); 00087 } 00088 00089 /** 00090 * @brief Send a aux_status message 00091 * @param chan MAVLink channel to send the message 00092 * 00093 * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 00094 * @param i2c0_err_count Number of I2C errors since startup 00095 * @param i2c1_err_count Number of I2C errors since startup 00096 * @param spi0_err_count Number of I2C errors since startup 00097 * @param spi1_err_count Number of I2C errors since startup 00098 * @param uart_total_err_count Number of I2C errors since startup 00099 */ 00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00101 00102 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) 00103 { 00104 mavlink_message_t msg; 00105 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); 00106 mavlink_send_uart(chan, &msg); 00107 } 00108 00109 #endif 00110 // MESSAGE AUX_STATUS UNPACKING 00111 00112 /** 00113 * @brief Get field load from aux_status message 00114 * 00115 * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 00116 */ 00117 static inline uint16_t mavlink_msg_aux_status_get_load(const mavlink_message_t* msg) 00118 { 00119 generic_16bit r; 00120 r.b[1] = (msg->payload)[0]; 00121 r.b[0] = (msg->payload)[1]; 00122 return (uint16_t)r.s; 00123 } 00124 00125 /** 00126 * @brief Get field i2c0_err_count from aux_status message 00127 * 00128 * @return Number of I2C errors since startup 00129 */ 00130 static inline uint16_t mavlink_msg_aux_status_get_i2c0_err_count(const mavlink_message_t* msg) 00131 { 00132 generic_16bit r; 00133 r.b[1] = (msg->payload+sizeof(uint16_t))[0]; 00134 r.b[0] = (msg->payload+sizeof(uint16_t))[1]; 00135 return (uint16_t)r.s; 00136 } 00137 00138 /** 00139 * @brief Get field i2c1_err_count from aux_status message 00140 * 00141 * @return Number of I2C errors since startup 00142 */ 00143 static inline uint16_t mavlink_msg_aux_status_get_i2c1_err_count(const mavlink_message_t* msg) 00144 { 00145 generic_16bit r; 00146 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00147 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t))[1]; 00148 return (uint16_t)r.s; 00149 } 00150 00151 /** 00152 * @brief Get field spi0_err_count from aux_status message 00153 * 00154 * @return Number of I2C errors since startup 00155 */ 00156 static inline uint16_t mavlink_msg_aux_status_get_spi0_err_count(const mavlink_message_t* msg) 00157 { 00158 generic_16bit r; 00159 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00160 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; 00161 return (uint16_t)r.s; 00162 } 00163 00164 /** 00165 * @brief Get field spi1_err_count from aux_status message 00166 * 00167 * @return Number of I2C errors since startup 00168 */ 00169 static inline uint16_t mavlink_msg_aux_status_get_spi1_err_count(const mavlink_message_t* msg) 00170 { 00171 generic_16bit r; 00172 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00173 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; 00174 return (uint16_t)r.s; 00175 } 00176 00177 /** 00178 * @brief Get field uart_total_err_count from aux_status message 00179 * 00180 * @return Number of I2C errors since startup 00181 */ 00182 static inline uint16_t mavlink_msg_aux_status_get_uart_total_err_count(const mavlink_message_t* msg) 00183 { 00184 generic_16bit r; 00185 r.b[1] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00186 r.b[0] = (msg->payload+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; 00187 return (uint16_t)r.s; 00188 } 00189 00190 /** 00191 * @brief Decode a aux_status message into a struct 00192 * 00193 * @param msg The message to decode 00194 * @param aux_status C-struct to decode the message contents into 00195 */ 00196 static inline void mavlink_msg_aux_status_decode(const mavlink_message_t* msg, mavlink_aux_status_t* aux_status) 00197 { 00198 aux_status->load = mavlink_msg_aux_status_get_load(msg); 00199 aux_status->i2c0_err_count = mavlink_msg_aux_status_get_i2c0_err_count(msg); 00200 aux_status->i2c1_err_count = mavlink_msg_aux_status_get_i2c1_err_count(msg); 00201 aux_status->spi0_err_count = mavlink_msg_aux_status_get_spi0_err_count(msg); 00202 aux_status->spi1_err_count = mavlink_msg_aux_status_get_spi1_err_count(msg); 00203 aux_status->uart_total_err_count = mavlink_msg_aux_status_get_uart_total_err_count(msg); 00204 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2