Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_sensor_offsets.h Source File

mavlink_msg_sensor_offsets.h

00001 // MESSAGE SENSOR_OFFSETS PACKING
00002 
00003 #define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
00004 
00005 typedef struct __mavlink_sensor_offsets_t 
00006 {
00007     int16_t mag_ofs_x; ///< magnetometer X offset
00008     int16_t mag_ofs_y; ///< magnetometer Y offset
00009     int16_t mag_ofs_z; ///< magnetometer Z offset
00010     float mag_declination; ///< magnetic declination (radians)
00011     int32_t raw_press; ///< raw pressure from barometer
00012     int32_t raw_temp; ///< raw temperature from barometer
00013     float gyro_cal_x; ///< gyro X calibration
00014     float gyro_cal_y; ///< gyro Y calibration
00015     float gyro_cal_z; ///< gyro Z calibration
00016     float accel_cal_x; ///< accel X calibration
00017     float accel_cal_y; ///< accel Y calibration
00018     float accel_cal_z; ///< accel Z calibration
00019 
00020 } mavlink_sensor_offsets_t;
00021 
00022 
00023 
00024 /**
00025  * @brief Pack a sensor_offsets message
00026  * @param system_id ID of this system
00027  * @param component_id ID of this component (e.g. 200 for IMU)
00028  * @param msg The MAVLink message to compress the data into
00029  *
00030  * @param mag_ofs_x magnetometer X offset
00031  * @param mag_ofs_y magnetometer Y offset
00032  * @param mag_ofs_z magnetometer Z offset
00033  * @param mag_declination magnetic declination (radians)
00034  * @param raw_press raw pressure from barometer
00035  * @param raw_temp raw temperature from barometer
00036  * @param gyro_cal_x gyro X calibration
00037  * @param gyro_cal_y gyro Y calibration
00038  * @param gyro_cal_z gyro Z calibration
00039  * @param accel_cal_x accel X calibration
00040  * @param accel_cal_y accel Y calibration
00041  * @param accel_cal_z accel Z calibration
00042  * @return length of the message in bytes (excluding serial stream start sign)
00043  */
00044 static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
00045 {
00046     uint16_t i = 0;
00047     msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
00048 
00049     i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
00050     i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
00051     i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
00052     i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
00053     i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
00054     i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
00055     i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
00056     i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
00057     i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
00058     i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
00059     i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
00060     i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
00061 
00062     return mavlink_finalize_message(msg, system_id, component_id, i);
00063 }
00064 
00065 /**
00066  * @brief Pack a sensor_offsets message
00067  * @param system_id ID of this system
00068  * @param component_id ID of this component (e.g. 200 for IMU)
00069  * @param chan The MAVLink channel this message was sent over
00070  * @param msg The MAVLink message to compress the data into
00071  * @param mag_ofs_x magnetometer X offset
00072  * @param mag_ofs_y magnetometer Y offset
00073  * @param mag_ofs_z magnetometer Z offset
00074  * @param mag_declination magnetic declination (radians)
00075  * @param raw_press raw pressure from barometer
00076  * @param raw_temp raw temperature from barometer
00077  * @param gyro_cal_x gyro X calibration
00078  * @param gyro_cal_y gyro Y calibration
00079  * @param gyro_cal_z gyro Z calibration
00080  * @param accel_cal_x accel X calibration
00081  * @param accel_cal_y accel Y calibration
00082  * @param accel_cal_z accel Z calibration
00083  * @return length of the message in bytes (excluding serial stream start sign)
00084  */
00085 static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
00086 {
00087     uint16_t i = 0;
00088     msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
00089 
00090     i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
00091     i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
00092     i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
00093     i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
00094     i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
00095     i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
00096     i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
00097     i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
00098     i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
00099     i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
00100     i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
00101     i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
00102 
00103     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00104 }
00105 
00106 /**
00107  * @brief Encode a sensor_offsets struct into a message
00108  *
00109  * @param system_id ID of this system
00110  * @param component_id ID of this component (e.g. 200 for IMU)
00111  * @param msg The MAVLink message to compress the data into
00112  * @param sensor_offsets C-struct to read the message contents from
00113  */
00114 static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
00115 {
00116     return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
00117 }
00118 
00119 /**
00120  * @brief Send a sensor_offsets message
00121  * @param chan MAVLink channel to send the message
00122  *
00123  * @param mag_ofs_x magnetometer X offset
00124  * @param mag_ofs_y magnetometer Y offset
00125  * @param mag_ofs_z magnetometer Z offset
00126  * @param mag_declination magnetic declination (radians)
00127  * @param raw_press raw pressure from barometer
00128  * @param raw_temp raw temperature from barometer
00129  * @param gyro_cal_x gyro X calibration
00130  * @param gyro_cal_y gyro Y calibration
00131  * @param gyro_cal_z gyro Z calibration
00132  * @param accel_cal_x accel X calibration
00133  * @param accel_cal_y accel Y calibration
00134  * @param accel_cal_z accel Z calibration
00135  */
00136 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00137 
00138 static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
00139 {
00140     mavlink_message_t msg;
00141     mavlink_msg_sensor_offsets_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, mag_ofs_x, mag_ofs_y, mag_ofs_z, mag_declination, raw_press, raw_temp, gyro_cal_x, gyro_cal_y, gyro_cal_z, accel_cal_x, accel_cal_y, accel_cal_z);
00142     mavlink_send_uart(chan, &msg);
00143 }
00144 
00145 #endif
00146 // MESSAGE SENSOR_OFFSETS UNPACKING
00147 
00148 /**
00149  * @brief Get field mag_ofs_x from sensor_offsets message
00150  *
00151  * @return magnetometer X offset
00152  */
00153 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
00154 {
00155     generic_16bit r;
00156     r.b[1] = (msg->payload)[0];
00157     r.b[0] = (msg->payload)[1];
00158     return (int16_t)r.s;
00159 }
00160 
00161 /**
00162  * @brief Get field mag_ofs_y from sensor_offsets message
00163  *
00164  * @return magnetometer Y offset
00165  */
00166 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
00167 {
00168     generic_16bit r;
00169     r.b[1] = (msg->payload+sizeof(int16_t))[0];
00170     r.b[0] = (msg->payload+sizeof(int16_t))[1];
00171     return (int16_t)r.s;
00172 }
00173 
00174 /**
00175  * @brief Get field mag_ofs_z from sensor_offsets message
00176  *
00177  * @return magnetometer Z offset
00178  */
00179 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
00180 {
00181     generic_16bit r;
00182     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0];
00183     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1];
00184     return (int16_t)r.s;
00185 }
00186 
00187 /**
00188  * @brief Get field mag_declination from sensor_offsets message
00189  *
00190  * @return magnetic declination (radians)
00191  */
00192 static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
00193 {
00194     generic_32bit r;
00195     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
00196     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
00197     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[2];
00198     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[3];
00199     return (float)r.f;
00200 }
00201 
00202 /**
00203  * @brief Get field raw_press from sensor_offsets message
00204  *
00205  * @return raw pressure from barometer
00206  */
00207 static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
00208 {
00209     generic_32bit r;
00210     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[0];
00211     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[1];
00212     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[2];
00213     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[3];
00214     return (int32_t)r.i;
00215 }
00216 
00217 /**
00218  * @brief Get field raw_temp from sensor_offsets message
00219  *
00220  * @return raw temperature from barometer
00221  */
00222 static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
00223 {
00224     generic_32bit r;
00225     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[0];
00226     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[1];
00227     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[2];
00228     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[3];
00229     return (int32_t)r.i;
00230 }
00231 
00232 /**
00233  * @brief Get field gyro_cal_x from sensor_offsets message
00234  *
00235  * @return gyro X calibration
00236  */
00237 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
00238 {
00239     generic_32bit r;
00240     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
00241     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
00242     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
00243     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
00244     return (float)r.f;
00245 }
00246 
00247 /**
00248  * @brief Get field gyro_cal_y from sensor_offsets message
00249  *
00250  * @return gyro Y calibration
00251  */
00252 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
00253 {
00254     generic_32bit r;
00255     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[0];
00256     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[1];
00257     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[2];
00258     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float))[3];
00259     return (float)r.f;
00260 }
00261 
00262 /**
00263  * @brief Get field gyro_cal_z from sensor_offsets message
00264  *
00265  * @return gyro Z calibration
00266  */
00267 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
00268 {
00269     generic_32bit r;
00270     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[0];
00271     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[1];
00272     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[2];
00273     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float))[3];
00274     return (float)r.f;
00275 }
00276 
00277 /**
00278  * @brief Get field accel_cal_x from sensor_offsets message
00279  *
00280  * @return accel X calibration
00281  */
00282 static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
00283 {
00284     generic_32bit r;
00285     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00286     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00287     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00288     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00289     return (float)r.f;
00290 }
00291 
00292 /**
00293  * @brief Get field accel_cal_y from sensor_offsets message
00294  *
00295  * @return accel Y calibration
00296  */
00297 static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
00298 {
00299     generic_32bit r;
00300     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00301     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00302     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00303     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00304     return (float)r.f;
00305 }
00306 
00307 /**
00308  * @brief Get field accel_cal_z from sensor_offsets message
00309  *
00310  * @return accel Z calibration
00311  */
00312 static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
00313 {
00314     generic_32bit r;
00315     r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00316     r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00317     r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00318     r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00319     return (float)r.f;
00320 }
00321 
00322 /**
00323  * @brief Decode a sensor_offsets message into a struct
00324  *
00325  * @param msg The message to decode
00326  * @param sensor_offsets C-struct to decode the message contents into
00327  */
00328 static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
00329 {
00330     sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
00331     sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
00332     sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
00333     sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
00334     sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
00335     sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
00336     sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
00337     sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
00338     sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
00339     sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
00340     sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
00341     sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
00342 }