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_sensor_bias.h
00001 // MESSAGE SENSOR_BIAS PACKING 00002 00003 #define MAVLINK_MSG_ID_SENSOR_BIAS 172 00004 00005 typedef struct __mavlink_sensor_bias_t 00006 { 00007 float axBias; ///< Accelerometer X bias (m/s) 00008 float ayBias; ///< Accelerometer Y bias (m/s) 00009 float azBias; ///< Accelerometer Z bias (m/s) 00010 float gxBias; ///< Gyro X bias (rad/s) 00011 float gyBias; ///< Gyro Y bias (rad/s) 00012 float gzBias; ///< Gyro Z bias (rad/s) 00013 00014 } mavlink_sensor_bias_t; 00015 00016 00017 00018 /** 00019 * @brief Pack a sensor_bias 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 axBias Accelerometer X bias (m/s) 00025 * @param ayBias Accelerometer Y bias (m/s) 00026 * @param azBias Accelerometer Z bias (m/s) 00027 * @param gxBias Gyro X bias (rad/s) 00028 * @param gyBias Gyro Y bias (rad/s) 00029 * @param gzBias Gyro Z bias (rad/s) 00030 * @return length of the message in bytes (excluding serial stream start sign) 00031 */ 00032 static inline uint16_t mavlink_msg_sensor_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) 00033 { 00034 uint16_t i = 0; 00035 msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; 00036 00037 i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s) 00038 i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s) 00039 i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s) 00040 i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s) 00041 i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s) 00042 i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s) 00043 00044 return mavlink_finalize_message(msg, system_id, component_id, i); 00045 } 00046 00047 /** 00048 * @brief Pack a sensor_bias 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 axBias Accelerometer X bias (m/s) 00054 * @param ayBias Accelerometer Y bias (m/s) 00055 * @param azBias Accelerometer Z bias (m/s) 00056 * @param gxBias Gyro X bias (rad/s) 00057 * @param gyBias Gyro Y bias (rad/s) 00058 * @param gzBias Gyro Z bias (rad/s) 00059 * @return length of the message in bytes (excluding serial stream start sign) 00060 */ 00061 static inline uint16_t mavlink_msg_sensor_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) 00062 { 00063 uint16_t i = 0; 00064 msg->msgid = MAVLINK_MSG_ID_SENSOR_BIAS; 00065 00066 i += put_float_by_index(axBias, i, msg->payload); // Accelerometer X bias (m/s) 00067 i += put_float_by_index(ayBias, i, msg->payload); // Accelerometer Y bias (m/s) 00068 i += put_float_by_index(azBias, i, msg->payload); // Accelerometer Z bias (m/s) 00069 i += put_float_by_index(gxBias, i, msg->payload); // Gyro X bias (rad/s) 00070 i += put_float_by_index(gyBias, i, msg->payload); // Gyro Y bias (rad/s) 00071 i += put_float_by_index(gzBias, i, msg->payload); // Gyro Z bias (rad/s) 00072 00073 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00074 } 00075 00076 /** 00077 * @brief Encode a sensor_bias 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 sensor_bias C-struct to read the message contents from 00083 */ 00084 static inline uint16_t mavlink_msg_sensor_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_bias_t* sensor_bias) 00085 { 00086 return mavlink_msg_sensor_bias_pack(system_id, component_id, msg, sensor_bias->axBias, sensor_bias->ayBias, sensor_bias->azBias, sensor_bias->gxBias, sensor_bias->gyBias, sensor_bias->gzBias); 00087 } 00088 00089 /** 00090 * @brief Send a sensor_bias message 00091 * @param chan MAVLink channel to send the message 00092 * 00093 * @param axBias Accelerometer X bias (m/s) 00094 * @param ayBias Accelerometer Y bias (m/s) 00095 * @param azBias Accelerometer Z bias (m/s) 00096 * @param gxBias Gyro X bias (rad/s) 00097 * @param gyBias Gyro Y bias (rad/s) 00098 * @param gzBias Gyro Z bias (rad/s) 00099 */ 00100 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00101 00102 static inline void mavlink_msg_sensor_bias_send(mavlink_channel_t chan, float axBias, float ayBias, float azBias, float gxBias, float gyBias, float gzBias) 00103 { 00104 mavlink_message_t msg; 00105 mavlink_msg_sensor_bias_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, axBias, ayBias, azBias, gxBias, gyBias, gzBias); 00106 mavlink_send_uart(chan, &msg); 00107 } 00108 00109 #endif 00110 // MESSAGE SENSOR_BIAS UNPACKING 00111 00112 /** 00113 * @brief Get field axBias from sensor_bias message 00114 * 00115 * @return Accelerometer X bias (m/s) 00116 */ 00117 static inline float mavlink_msg_sensor_bias_get_axBias(const mavlink_message_t* msg) 00118 { 00119 generic_32bit r; 00120 r.b[3] = (msg->payload)[0]; 00121 r.b[2] = (msg->payload)[1]; 00122 r.b[1] = (msg->payload)[2]; 00123 r.b[0] = (msg->payload)[3]; 00124 return (float)r.f; 00125 } 00126 00127 /** 00128 * @brief Get field ayBias from sensor_bias message 00129 * 00130 * @return Accelerometer Y bias (m/s) 00131 */ 00132 static inline float mavlink_msg_sensor_bias_get_ayBias(const mavlink_message_t* msg) 00133 { 00134 generic_32bit r; 00135 r.b[3] = (msg->payload+sizeof(float))[0]; 00136 r.b[2] = (msg->payload+sizeof(float))[1]; 00137 r.b[1] = (msg->payload+sizeof(float))[2]; 00138 r.b[0] = (msg->payload+sizeof(float))[3]; 00139 return (float)r.f; 00140 } 00141 00142 /** 00143 * @brief Get field azBias from sensor_bias message 00144 * 00145 * @return Accelerometer Z bias (m/s) 00146 */ 00147 static inline float mavlink_msg_sensor_bias_get_azBias(const mavlink_message_t* msg) 00148 { 00149 generic_32bit r; 00150 r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0]; 00151 r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1]; 00152 r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2]; 00153 r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3]; 00154 return (float)r.f; 00155 } 00156 00157 /** 00158 * @brief Get field gxBias from sensor_bias message 00159 * 00160 * @return Gyro X bias (rad/s) 00161 */ 00162 static inline float mavlink_msg_sensor_bias_get_gxBias(const mavlink_message_t* msg) 00163 { 00164 generic_32bit r; 00165 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00166 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00167 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00168 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00169 return (float)r.f; 00170 } 00171 00172 /** 00173 * @brief Get field gyBias from sensor_bias message 00174 * 00175 * @return Gyro Y bias (rad/s) 00176 */ 00177 static inline float mavlink_msg_sensor_bias_get_gyBias(const mavlink_message_t* msg) 00178 { 00179 generic_32bit r; 00180 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00181 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00182 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00183 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00184 return (float)r.f; 00185 } 00186 00187 /** 00188 * @brief Get field gzBias from sensor_bias message 00189 * 00190 * @return Gyro Z bias (rad/s) 00191 */ 00192 static inline float mavlink_msg_sensor_bias_get_gzBias(const mavlink_message_t* msg) 00193 { 00194 generic_32bit r; 00195 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00196 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00197 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00198 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00199 return (float)r.f; 00200 } 00201 00202 /** 00203 * @brief Decode a sensor_bias message into a struct 00204 * 00205 * @param msg The message to decode 00206 * @param sensor_bias C-struct to decode the message contents into 00207 */ 00208 static inline void mavlink_msg_sensor_bias_decode(const mavlink_message_t* msg, mavlink_sensor_bias_t* sensor_bias) 00209 { 00210 sensor_bias->axBias = mavlink_msg_sensor_bias_get_axBias(msg); 00211 sensor_bias->ayBias = mavlink_msg_sensor_bias_get_ayBias(msg); 00212 sensor_bias->azBias = mavlink_msg_sensor_bias_get_azBias(msg); 00213 sensor_bias->gxBias = mavlink_msg_sensor_bias_get_gxBias(msg); 00214 sensor_bias->gyBias = mavlink_msg_sensor_bias_get_gyBias(msg); 00215 sensor_bias->gzBias = mavlink_msg_sensor_bias_get_gzBias(msg); 00216 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2