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 SENSOR_OFFSETS PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_sensor_offsets_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 int16_t mag_ofs_x; ///< magnetometer X offset
shimniok 0:826c6171fc1b 8 int16_t mag_ofs_y; ///< magnetometer Y offset
shimniok 0:826c6171fc1b 9 int16_t mag_ofs_z; ///< magnetometer Z offset
shimniok 0:826c6171fc1b 10 float mag_declination; ///< magnetic declination (radians)
shimniok 0:826c6171fc1b 11 int32_t raw_press; ///< raw pressure from barometer
shimniok 0:826c6171fc1b 12 int32_t raw_temp; ///< raw temperature from barometer
shimniok 0:826c6171fc1b 13 float gyro_cal_x; ///< gyro X calibration
shimniok 0:826c6171fc1b 14 float gyro_cal_y; ///< gyro Y calibration
shimniok 0:826c6171fc1b 15 float gyro_cal_z; ///< gyro Z calibration
shimniok 0:826c6171fc1b 16 float accel_cal_x; ///< accel X calibration
shimniok 0:826c6171fc1b 17 float accel_cal_y; ///< accel Y calibration
shimniok 0:826c6171fc1b 18 float accel_cal_z; ///< accel Z calibration
shimniok 0:826c6171fc1b 19
shimniok 0:826c6171fc1b 20 } mavlink_sensor_offsets_t;
shimniok 0:826c6171fc1b 21
shimniok 0:826c6171fc1b 22
shimniok 0:826c6171fc1b 23
shimniok 0:826c6171fc1b 24 /**
shimniok 0:826c6171fc1b 25 * @brief Pack a sensor_offsets message
shimniok 0:826c6171fc1b 26 * @param system_id ID of this system
shimniok 0:826c6171fc1b 27 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 28 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 29 *
shimniok 0:826c6171fc1b 30 * @param mag_ofs_x magnetometer X offset
shimniok 0:826c6171fc1b 31 * @param mag_ofs_y magnetometer Y offset
shimniok 0:826c6171fc1b 32 * @param mag_ofs_z magnetometer Z offset
shimniok 0:826c6171fc1b 33 * @param mag_declination magnetic declination (radians)
shimniok 0:826c6171fc1b 34 * @param raw_press raw pressure from barometer
shimniok 0:826c6171fc1b 35 * @param raw_temp raw temperature from barometer
shimniok 0:826c6171fc1b 36 * @param gyro_cal_x gyro X calibration
shimniok 0:826c6171fc1b 37 * @param gyro_cal_y gyro Y calibration
shimniok 0:826c6171fc1b 38 * @param gyro_cal_z gyro Z calibration
shimniok 0:826c6171fc1b 39 * @param accel_cal_x accel X calibration
shimniok 0:826c6171fc1b 40 * @param accel_cal_y accel Y calibration
shimniok 0:826c6171fc1b 41 * @param accel_cal_z accel Z calibration
shimniok 0:826c6171fc1b 42 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 43 */
shimniok 0:826c6171fc1b 44 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)
shimniok 0:826c6171fc1b 45 {
shimniok 0:826c6171fc1b 46 uint16_t i = 0;
shimniok 0:826c6171fc1b 47 msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
shimniok 0:826c6171fc1b 48
shimniok 0:826c6171fc1b 49 i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
shimniok 0:826c6171fc1b 50 i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
shimniok 0:826c6171fc1b 51 i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
shimniok 0:826c6171fc1b 52 i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
shimniok 0:826c6171fc1b 53 i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
shimniok 0:826c6171fc1b 54 i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
shimniok 0:826c6171fc1b 55 i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
shimniok 0:826c6171fc1b 56 i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
shimniok 0:826c6171fc1b 57 i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
shimniok 0:826c6171fc1b 58 i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
shimniok 0:826c6171fc1b 59 i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
shimniok 0:826c6171fc1b 60 i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
shimniok 0:826c6171fc1b 61
shimniok 0:826c6171fc1b 62 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 63 }
shimniok 0:826c6171fc1b 64
shimniok 0:826c6171fc1b 65 /**
shimniok 0:826c6171fc1b 66 * @brief Pack a sensor_offsets message
shimniok 0:826c6171fc1b 67 * @param system_id ID of this system
shimniok 0:826c6171fc1b 68 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 69 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 70 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 71 * @param mag_ofs_x magnetometer X offset
shimniok 0:826c6171fc1b 72 * @param mag_ofs_y magnetometer Y offset
shimniok 0:826c6171fc1b 73 * @param mag_ofs_z magnetometer Z offset
shimniok 0:826c6171fc1b 74 * @param mag_declination magnetic declination (radians)
shimniok 0:826c6171fc1b 75 * @param raw_press raw pressure from barometer
shimniok 0:826c6171fc1b 76 * @param raw_temp raw temperature from barometer
shimniok 0:826c6171fc1b 77 * @param gyro_cal_x gyro X calibration
shimniok 0:826c6171fc1b 78 * @param gyro_cal_y gyro Y calibration
shimniok 0:826c6171fc1b 79 * @param gyro_cal_z gyro Z calibration
shimniok 0:826c6171fc1b 80 * @param accel_cal_x accel X calibration
shimniok 0:826c6171fc1b 81 * @param accel_cal_y accel Y calibration
shimniok 0:826c6171fc1b 82 * @param accel_cal_z accel Z calibration
shimniok 0:826c6171fc1b 83 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 84 */
shimniok 0:826c6171fc1b 85 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)
shimniok 0:826c6171fc1b 86 {
shimniok 0:826c6171fc1b 87 uint16_t i = 0;
shimniok 0:826c6171fc1b 88 msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
shimniok 0:826c6171fc1b 89
shimniok 0:826c6171fc1b 90 i += put_int16_t_by_index(mag_ofs_x, i, msg->payload); // magnetometer X offset
shimniok 0:826c6171fc1b 91 i += put_int16_t_by_index(mag_ofs_y, i, msg->payload); // magnetometer Y offset
shimniok 0:826c6171fc1b 92 i += put_int16_t_by_index(mag_ofs_z, i, msg->payload); // magnetometer Z offset
shimniok 0:826c6171fc1b 93 i += put_float_by_index(mag_declination, i, msg->payload); // magnetic declination (radians)
shimniok 0:826c6171fc1b 94 i += put_int32_t_by_index(raw_press, i, msg->payload); // raw pressure from barometer
shimniok 0:826c6171fc1b 95 i += put_int32_t_by_index(raw_temp, i, msg->payload); // raw temperature from barometer
shimniok 0:826c6171fc1b 96 i += put_float_by_index(gyro_cal_x, i, msg->payload); // gyro X calibration
shimniok 0:826c6171fc1b 97 i += put_float_by_index(gyro_cal_y, i, msg->payload); // gyro Y calibration
shimniok 0:826c6171fc1b 98 i += put_float_by_index(gyro_cal_z, i, msg->payload); // gyro Z calibration
shimniok 0:826c6171fc1b 99 i += put_float_by_index(accel_cal_x, i, msg->payload); // accel X calibration
shimniok 0:826c6171fc1b 100 i += put_float_by_index(accel_cal_y, i, msg->payload); // accel Y calibration
shimniok 0:826c6171fc1b 101 i += put_float_by_index(accel_cal_z, i, msg->payload); // accel Z calibration
shimniok 0:826c6171fc1b 102
shimniok 0:826c6171fc1b 103 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 104 }
shimniok 0:826c6171fc1b 105
shimniok 0:826c6171fc1b 106 /**
shimniok 0:826c6171fc1b 107 * @brief Encode a sensor_offsets struct into a message
shimniok 0:826c6171fc1b 108 *
shimniok 0:826c6171fc1b 109 * @param system_id ID of this system
shimniok 0:826c6171fc1b 110 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 111 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 112 * @param sensor_offsets C-struct to read the message contents from
shimniok 0:826c6171fc1b 113 */
shimniok 0:826c6171fc1b 114 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)
shimniok 0:826c6171fc1b 115 {
shimniok 0:826c6171fc1b 116 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);
shimniok 0:826c6171fc1b 117 }
shimniok 0:826c6171fc1b 118
shimniok 0:826c6171fc1b 119 /**
shimniok 0:826c6171fc1b 120 * @brief Send a sensor_offsets message
shimniok 0:826c6171fc1b 121 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 122 *
shimniok 0:826c6171fc1b 123 * @param mag_ofs_x magnetometer X offset
shimniok 0:826c6171fc1b 124 * @param mag_ofs_y magnetometer Y offset
shimniok 0:826c6171fc1b 125 * @param mag_ofs_z magnetometer Z offset
shimniok 0:826c6171fc1b 126 * @param mag_declination magnetic declination (radians)
shimniok 0:826c6171fc1b 127 * @param raw_press raw pressure from barometer
shimniok 0:826c6171fc1b 128 * @param raw_temp raw temperature from barometer
shimniok 0:826c6171fc1b 129 * @param gyro_cal_x gyro X calibration
shimniok 0:826c6171fc1b 130 * @param gyro_cal_y gyro Y calibration
shimniok 0:826c6171fc1b 131 * @param gyro_cal_z gyro Z calibration
shimniok 0:826c6171fc1b 132 * @param accel_cal_x accel X calibration
shimniok 0:826c6171fc1b 133 * @param accel_cal_y accel Y calibration
shimniok 0:826c6171fc1b 134 * @param accel_cal_z accel Z calibration
shimniok 0:826c6171fc1b 135 */
shimniok 0:826c6171fc1b 136 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 137
shimniok 0:826c6171fc1b 138 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)
shimniok 0:826c6171fc1b 139 {
shimniok 0:826c6171fc1b 140 mavlink_message_t msg;
shimniok 0:826c6171fc1b 141 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);
shimniok 0:826c6171fc1b 142 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 143 }
shimniok 0:826c6171fc1b 144
shimniok 0:826c6171fc1b 145 #endif
shimniok 0:826c6171fc1b 146 // MESSAGE SENSOR_OFFSETS UNPACKING
shimniok 0:826c6171fc1b 147
shimniok 0:826c6171fc1b 148 /**
shimniok 0:826c6171fc1b 149 * @brief Get field mag_ofs_x from sensor_offsets message
shimniok 0:826c6171fc1b 150 *
shimniok 0:826c6171fc1b 151 * @return magnetometer X offset
shimniok 0:826c6171fc1b 152 */
shimniok 0:826c6171fc1b 153 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 154 {
shimniok 0:826c6171fc1b 155 generic_16bit r;
shimniok 0:826c6171fc1b 156 r.b[1] = (msg->payload)[0];
shimniok 0:826c6171fc1b 157 r.b[0] = (msg->payload)[1];
shimniok 0:826c6171fc1b 158 return (int16_t)r.s;
shimniok 0:826c6171fc1b 159 }
shimniok 0:826c6171fc1b 160
shimniok 0:826c6171fc1b 161 /**
shimniok 0:826c6171fc1b 162 * @brief Get field mag_ofs_y from sensor_offsets message
shimniok 0:826c6171fc1b 163 *
shimniok 0:826c6171fc1b 164 * @return magnetometer Y offset
shimniok 0:826c6171fc1b 165 */
shimniok 0:826c6171fc1b 166 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 167 {
shimniok 0:826c6171fc1b 168 generic_16bit r;
shimniok 0:826c6171fc1b 169 r.b[1] = (msg->payload+sizeof(int16_t))[0];
shimniok 0:826c6171fc1b 170 r.b[0] = (msg->payload+sizeof(int16_t))[1];
shimniok 0:826c6171fc1b 171 return (int16_t)r.s;
shimniok 0:826c6171fc1b 172 }
shimniok 0:826c6171fc1b 173
shimniok 0:826c6171fc1b 174 /**
shimniok 0:826c6171fc1b 175 * @brief Get field mag_ofs_z from sensor_offsets message
shimniok 0:826c6171fc1b 176 *
shimniok 0:826c6171fc1b 177 * @return magnetometer Z offset
shimniok 0:826c6171fc1b 178 */
shimniok 0:826c6171fc1b 179 static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 180 {
shimniok 0:826c6171fc1b 181 generic_16bit r;
shimniok 0:826c6171fc1b 182 r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[0];
shimniok 0:826c6171fc1b 183 r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t))[1];
shimniok 0:826c6171fc1b 184 return (int16_t)r.s;
shimniok 0:826c6171fc1b 185 }
shimniok 0:826c6171fc1b 186
shimniok 0:826c6171fc1b 187 /**
shimniok 0:826c6171fc1b 188 * @brief Get field mag_declination from sensor_offsets message
shimniok 0:826c6171fc1b 189 *
shimniok 0:826c6171fc1b 190 * @return magnetic declination (radians)
shimniok 0:826c6171fc1b 191 */
shimniok 0:826c6171fc1b 192 static inline float mavlink_msg_sensor_offsets_get_mag_declination(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(int16_t)+sizeof(int16_t)+sizeof(int16_t))[0];
shimniok 0:826c6171fc1b 196 r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[1];
shimniok 0:826c6171fc1b 197 r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[2];
shimniok 0:826c6171fc1b 198 r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t))[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 Get field raw_press from sensor_offsets message
shimniok 0:826c6171fc1b 204 *
shimniok 0:826c6171fc1b 205 * @return raw pressure from barometer
shimniok 0:826c6171fc1b 206 */
shimniok 0:826c6171fc1b 207 static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 208 {
shimniok 0:826c6171fc1b 209 generic_32bit r;
shimniok 0:826c6171fc1b 210 r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[0];
shimniok 0:826c6171fc1b 211 r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[1];
shimniok 0:826c6171fc1b 212 r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[2];
shimniok 0:826c6171fc1b 213 r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float))[3];
shimniok 0:826c6171fc1b 214 return (int32_t)r.i;
shimniok 0:826c6171fc1b 215 }
shimniok 0:826c6171fc1b 216
shimniok 0:826c6171fc1b 217 /**
shimniok 0:826c6171fc1b 218 * @brief Get field raw_temp from sensor_offsets message
shimniok 0:826c6171fc1b 219 *
shimniok 0:826c6171fc1b 220 * @return raw temperature from barometer
shimniok 0:826c6171fc1b 221 */
shimniok 0:826c6171fc1b 222 static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 223 {
shimniok 0:826c6171fc1b 224 generic_32bit r;
shimniok 0:826c6171fc1b 225 r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[0];
shimniok 0:826c6171fc1b 226 r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[1];
shimniok 0:826c6171fc1b 227 r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[2];
shimniok 0:826c6171fc1b 228 r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t))[3];
shimniok 0:826c6171fc1b 229 return (int32_t)r.i;
shimniok 0:826c6171fc1b 230 }
shimniok 0:826c6171fc1b 231
shimniok 0:826c6171fc1b 232 /**
shimniok 0:826c6171fc1b 233 * @brief Get field gyro_cal_x from sensor_offsets message
shimniok 0:826c6171fc1b 234 *
shimniok 0:826c6171fc1b 235 * @return gyro X calibration
shimniok 0:826c6171fc1b 236 */
shimniok 0:826c6171fc1b 237 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 238 {
shimniok 0:826c6171fc1b 239 generic_32bit r;
shimniok 0:826c6171fc1b 240 r.b[3] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[0];
shimniok 0:826c6171fc1b 241 r.b[2] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[1];
shimniok 0:826c6171fc1b 242 r.b[1] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[2];
shimniok 0:826c6171fc1b 243 r.b[0] = (msg->payload+sizeof(int16_t)+sizeof(int16_t)+sizeof(int16_t)+sizeof(float)+sizeof(int32_t)+sizeof(int32_t))[3];
shimniok 0:826c6171fc1b 244 return (float)r.f;
shimniok 0:826c6171fc1b 245 }
shimniok 0:826c6171fc1b 246
shimniok 0:826c6171fc1b 247 /**
shimniok 0:826c6171fc1b 248 * @brief Get field gyro_cal_y from sensor_offsets message
shimniok 0:826c6171fc1b 249 *
shimniok 0:826c6171fc1b 250 * @return gyro Y calibration
shimniok 0:826c6171fc1b 251 */
shimniok 0:826c6171fc1b 252 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 253 {
shimniok 0:826c6171fc1b 254 generic_32bit r;
shimniok 0:826c6171fc1b 255 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];
shimniok 0:826c6171fc1b 256 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];
shimniok 0:826c6171fc1b 257 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];
shimniok 0:826c6171fc1b 258 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];
shimniok 0:826c6171fc1b 259 return (float)r.f;
shimniok 0:826c6171fc1b 260 }
shimniok 0:826c6171fc1b 261
shimniok 0:826c6171fc1b 262 /**
shimniok 0:826c6171fc1b 263 * @brief Get field gyro_cal_z from sensor_offsets message
shimniok 0:826c6171fc1b 264 *
shimniok 0:826c6171fc1b 265 * @return gyro Z calibration
shimniok 0:826c6171fc1b 266 */
shimniok 0:826c6171fc1b 267 static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 268 {
shimniok 0:826c6171fc1b 269 generic_32bit r;
shimniok 0:826c6171fc1b 270 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];
shimniok 0:826c6171fc1b 271 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];
shimniok 0:826c6171fc1b 272 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];
shimniok 0:826c6171fc1b 273 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];
shimniok 0:826c6171fc1b 274 return (float)r.f;
shimniok 0:826c6171fc1b 275 }
shimniok 0:826c6171fc1b 276
shimniok 0:826c6171fc1b 277 /**
shimniok 0:826c6171fc1b 278 * @brief Get field accel_cal_x from sensor_offsets message
shimniok 0:826c6171fc1b 279 *
shimniok 0:826c6171fc1b 280 * @return accel X calibration
shimniok 0:826c6171fc1b 281 */
shimniok 0:826c6171fc1b 282 static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 283 {
shimniok 0:826c6171fc1b 284 generic_32bit r;
shimniok 0:826c6171fc1b 285 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];
shimniok 0:826c6171fc1b 286 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];
shimniok 0:826c6171fc1b 287 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];
shimniok 0:826c6171fc1b 288 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];
shimniok 0:826c6171fc1b 289 return (float)r.f;
shimniok 0:826c6171fc1b 290 }
shimniok 0:826c6171fc1b 291
shimniok 0:826c6171fc1b 292 /**
shimniok 0:826c6171fc1b 293 * @brief Get field accel_cal_y from sensor_offsets message
shimniok 0:826c6171fc1b 294 *
shimniok 0:826c6171fc1b 295 * @return accel Y calibration
shimniok 0:826c6171fc1b 296 */
shimniok 0:826c6171fc1b 297 static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 298 {
shimniok 0:826c6171fc1b 299 generic_32bit r;
shimniok 0:826c6171fc1b 300 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];
shimniok 0:826c6171fc1b 301 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];
shimniok 0:826c6171fc1b 302 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];
shimniok 0:826c6171fc1b 303 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];
shimniok 0:826c6171fc1b 304 return (float)r.f;
shimniok 0:826c6171fc1b 305 }
shimniok 0:826c6171fc1b 306
shimniok 0:826c6171fc1b 307 /**
shimniok 0:826c6171fc1b 308 * @brief Get field accel_cal_z from sensor_offsets message
shimniok 0:826c6171fc1b 309 *
shimniok 0:826c6171fc1b 310 * @return accel Z calibration
shimniok 0:826c6171fc1b 311 */
shimniok 0:826c6171fc1b 312 static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 313 {
shimniok 0:826c6171fc1b 314 generic_32bit r;
shimniok 0:826c6171fc1b 315 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];
shimniok 0:826c6171fc1b 316 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];
shimniok 0:826c6171fc1b 317 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];
shimniok 0:826c6171fc1b 318 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];
shimniok 0:826c6171fc1b 319 return (float)r.f;
shimniok 0:826c6171fc1b 320 }
shimniok 0:826c6171fc1b 321
shimniok 0:826c6171fc1b 322 /**
shimniok 0:826c6171fc1b 323 * @brief Decode a sensor_offsets message into a struct
shimniok 0:826c6171fc1b 324 *
shimniok 0:826c6171fc1b 325 * @param msg The message to decode
shimniok 0:826c6171fc1b 326 * @param sensor_offsets C-struct to decode the message contents into
shimniok 0:826c6171fc1b 327 */
shimniok 0:826c6171fc1b 328 static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
shimniok 0:826c6171fc1b 329 {
shimniok 0:826c6171fc1b 330 sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
shimniok 0:826c6171fc1b 331 sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
shimniok 0:826c6171fc1b 332 sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
shimniok 0:826c6171fc1b 333 sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
shimniok 0:826c6171fc1b 334 sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
shimniok 0:826c6171fc1b 335 sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
shimniok 0:826c6171fc1b 336 sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
shimniok 0:826c6171fc1b 337 sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
shimniok 0:826c6171fc1b 338 sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
shimniok 0:826c6171fc1b 339 sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
shimniok 0:826c6171fc1b 340 sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
shimniok 0:826c6171fc1b 341 sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
shimniok 0:826c6171fc1b 342 }