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 STATE_CORRECTION PACKING
shimniok 0:826c6171fc1b 2
shimniok 0:826c6171fc1b 3 #define MAVLINK_MSG_ID_STATE_CORRECTION 64
shimniok 0:826c6171fc1b 4
shimniok 0:826c6171fc1b 5 typedef struct __mavlink_state_correction_t
shimniok 0:826c6171fc1b 6 {
shimniok 0:826c6171fc1b 7 float xErr; ///< x position error
shimniok 0:826c6171fc1b 8 float yErr; ///< y position error
shimniok 0:826c6171fc1b 9 float zErr; ///< z position error
shimniok 0:826c6171fc1b 10 float rollErr; ///< roll error (radians)
shimniok 0:826c6171fc1b 11 float pitchErr; ///< pitch error (radians)
shimniok 0:826c6171fc1b 12 float yawErr; ///< yaw error (radians)
shimniok 0:826c6171fc1b 13 float vxErr; ///< x velocity
shimniok 0:826c6171fc1b 14 float vyErr; ///< y velocity
shimniok 0:826c6171fc1b 15 float vzErr; ///< z velocity
shimniok 0:826c6171fc1b 16
shimniok 0:826c6171fc1b 17 } mavlink_state_correction_t;
shimniok 0:826c6171fc1b 18
shimniok 0:826c6171fc1b 19
shimniok 0:826c6171fc1b 20
shimniok 0:826c6171fc1b 21 /**
shimniok 0:826c6171fc1b 22 * @brief Pack a state_correction message
shimniok 0:826c6171fc1b 23 * @param system_id ID of this system
shimniok 0:826c6171fc1b 24 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 25 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 26 *
shimniok 0:826c6171fc1b 27 * @param xErr x position error
shimniok 0:826c6171fc1b 28 * @param yErr y position error
shimniok 0:826c6171fc1b 29 * @param zErr z position error
shimniok 0:826c6171fc1b 30 * @param rollErr roll error (radians)
shimniok 0:826c6171fc1b 31 * @param pitchErr pitch error (radians)
shimniok 0:826c6171fc1b 32 * @param yawErr yaw error (radians)
shimniok 0:826c6171fc1b 33 * @param vxErr x velocity
shimniok 0:826c6171fc1b 34 * @param vyErr y velocity
shimniok 0:826c6171fc1b 35 * @param vzErr z velocity
shimniok 0:826c6171fc1b 36 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 37 */
shimniok 0:826c6171fc1b 38 static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
shimniok 0:826c6171fc1b 39 {
shimniok 0:826c6171fc1b 40 uint16_t i = 0;
shimniok 0:826c6171fc1b 41 msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
shimniok 0:826c6171fc1b 42
shimniok 0:826c6171fc1b 43 i += put_float_by_index(xErr, i, msg->payload); // x position error
shimniok 0:826c6171fc1b 44 i += put_float_by_index(yErr, i, msg->payload); // y position error
shimniok 0:826c6171fc1b 45 i += put_float_by_index(zErr, i, msg->payload); // z position error
shimniok 0:826c6171fc1b 46 i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
shimniok 0:826c6171fc1b 47 i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
shimniok 0:826c6171fc1b 48 i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
shimniok 0:826c6171fc1b 49 i += put_float_by_index(vxErr, i, msg->payload); // x velocity
shimniok 0:826c6171fc1b 50 i += put_float_by_index(vyErr, i, msg->payload); // y velocity
shimniok 0:826c6171fc1b 51 i += put_float_by_index(vzErr, i, msg->payload); // z velocity
shimniok 0:826c6171fc1b 52
shimniok 0:826c6171fc1b 53 return mavlink_finalize_message(msg, system_id, component_id, i);
shimniok 0:826c6171fc1b 54 }
shimniok 0:826c6171fc1b 55
shimniok 0:826c6171fc1b 56 /**
shimniok 0:826c6171fc1b 57 * @brief Pack a state_correction message
shimniok 0:826c6171fc1b 58 * @param system_id ID of this system
shimniok 0:826c6171fc1b 59 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 60 * @param chan The MAVLink channel this message was sent over
shimniok 0:826c6171fc1b 61 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 62 * @param xErr x position error
shimniok 0:826c6171fc1b 63 * @param yErr y position error
shimniok 0:826c6171fc1b 64 * @param zErr z position error
shimniok 0:826c6171fc1b 65 * @param rollErr roll error (radians)
shimniok 0:826c6171fc1b 66 * @param pitchErr pitch error (radians)
shimniok 0:826c6171fc1b 67 * @param yawErr yaw error (radians)
shimniok 0:826c6171fc1b 68 * @param vxErr x velocity
shimniok 0:826c6171fc1b 69 * @param vyErr y velocity
shimniok 0:826c6171fc1b 70 * @param vzErr z velocity
shimniok 0:826c6171fc1b 71 * @return length of the message in bytes (excluding serial stream start sign)
shimniok 0:826c6171fc1b 72 */
shimniok 0:826c6171fc1b 73 static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
shimniok 0:826c6171fc1b 74 {
shimniok 0:826c6171fc1b 75 uint16_t i = 0;
shimniok 0:826c6171fc1b 76 msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
shimniok 0:826c6171fc1b 77
shimniok 0:826c6171fc1b 78 i += put_float_by_index(xErr, i, msg->payload); // x position error
shimniok 0:826c6171fc1b 79 i += put_float_by_index(yErr, i, msg->payload); // y position error
shimniok 0:826c6171fc1b 80 i += put_float_by_index(zErr, i, msg->payload); // z position error
shimniok 0:826c6171fc1b 81 i += put_float_by_index(rollErr, i, msg->payload); // roll error (radians)
shimniok 0:826c6171fc1b 82 i += put_float_by_index(pitchErr, i, msg->payload); // pitch error (radians)
shimniok 0:826c6171fc1b 83 i += put_float_by_index(yawErr, i, msg->payload); // yaw error (radians)
shimniok 0:826c6171fc1b 84 i += put_float_by_index(vxErr, i, msg->payload); // x velocity
shimniok 0:826c6171fc1b 85 i += put_float_by_index(vyErr, i, msg->payload); // y velocity
shimniok 0:826c6171fc1b 86 i += put_float_by_index(vzErr, i, msg->payload); // z velocity
shimniok 0:826c6171fc1b 87
shimniok 0:826c6171fc1b 88 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
shimniok 0:826c6171fc1b 89 }
shimniok 0:826c6171fc1b 90
shimniok 0:826c6171fc1b 91 /**
shimniok 0:826c6171fc1b 92 * @brief Encode a state_correction struct into a message
shimniok 0:826c6171fc1b 93 *
shimniok 0:826c6171fc1b 94 * @param system_id ID of this system
shimniok 0:826c6171fc1b 95 * @param component_id ID of this component (e.g. 200 for IMU)
shimniok 0:826c6171fc1b 96 * @param msg The MAVLink message to compress the data into
shimniok 0:826c6171fc1b 97 * @param state_correction C-struct to read the message contents from
shimniok 0:826c6171fc1b 98 */
shimniok 0:826c6171fc1b 99 static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
shimniok 0:826c6171fc1b 100 {
shimniok 0:826c6171fc1b 101 return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
shimniok 0:826c6171fc1b 102 }
shimniok 0:826c6171fc1b 103
shimniok 0:826c6171fc1b 104 /**
shimniok 0:826c6171fc1b 105 * @brief Send a state_correction message
shimniok 0:826c6171fc1b 106 * @param chan MAVLink channel to send the message
shimniok 0:826c6171fc1b 107 *
shimniok 0:826c6171fc1b 108 * @param xErr x position error
shimniok 0:826c6171fc1b 109 * @param yErr y position error
shimniok 0:826c6171fc1b 110 * @param zErr z position error
shimniok 0:826c6171fc1b 111 * @param rollErr roll error (radians)
shimniok 0:826c6171fc1b 112 * @param pitchErr pitch error (radians)
shimniok 0:826c6171fc1b 113 * @param yawErr yaw error (radians)
shimniok 0:826c6171fc1b 114 * @param vxErr x velocity
shimniok 0:826c6171fc1b 115 * @param vyErr y velocity
shimniok 0:826c6171fc1b 116 * @param vzErr z velocity
shimniok 0:826c6171fc1b 117 */
shimniok 0:826c6171fc1b 118 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
shimniok 0:826c6171fc1b 119
shimniok 0:826c6171fc1b 120 static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
shimniok 0:826c6171fc1b 121 {
shimniok 0:826c6171fc1b 122 mavlink_message_t msg;
shimniok 0:826c6171fc1b 123 mavlink_msg_state_correction_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr);
shimniok 0:826c6171fc1b 124 mavlink_send_uart(chan, &msg);
shimniok 0:826c6171fc1b 125 }
shimniok 0:826c6171fc1b 126
shimniok 0:826c6171fc1b 127 #endif
shimniok 0:826c6171fc1b 128 // MESSAGE STATE_CORRECTION UNPACKING
shimniok 0:826c6171fc1b 129
shimniok 0:826c6171fc1b 130 /**
shimniok 0:826c6171fc1b 131 * @brief Get field xErr from state_correction message
shimniok 0:826c6171fc1b 132 *
shimniok 0:826c6171fc1b 133 * @return x position error
shimniok 0:826c6171fc1b 134 */
shimniok 0:826c6171fc1b 135 static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 136 {
shimniok 0:826c6171fc1b 137 generic_32bit r;
shimniok 0:826c6171fc1b 138 r.b[3] = (msg->payload)[0];
shimniok 0:826c6171fc1b 139 r.b[2] = (msg->payload)[1];
shimniok 0:826c6171fc1b 140 r.b[1] = (msg->payload)[2];
shimniok 0:826c6171fc1b 141 r.b[0] = (msg->payload)[3];
shimniok 0:826c6171fc1b 142 return (float)r.f;
shimniok 0:826c6171fc1b 143 }
shimniok 0:826c6171fc1b 144
shimniok 0:826c6171fc1b 145 /**
shimniok 0:826c6171fc1b 146 * @brief Get field yErr from state_correction message
shimniok 0:826c6171fc1b 147 *
shimniok 0:826c6171fc1b 148 * @return y position error
shimniok 0:826c6171fc1b 149 */
shimniok 0:826c6171fc1b 150 static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 151 {
shimniok 0:826c6171fc1b 152 generic_32bit r;
shimniok 0:826c6171fc1b 153 r.b[3] = (msg->payload+sizeof(float))[0];
shimniok 0:826c6171fc1b 154 r.b[2] = (msg->payload+sizeof(float))[1];
shimniok 0:826c6171fc1b 155 r.b[1] = (msg->payload+sizeof(float))[2];
shimniok 0:826c6171fc1b 156 r.b[0] = (msg->payload+sizeof(float))[3];
shimniok 0:826c6171fc1b 157 return (float)r.f;
shimniok 0:826c6171fc1b 158 }
shimniok 0:826c6171fc1b 159
shimniok 0:826c6171fc1b 160 /**
shimniok 0:826c6171fc1b 161 * @brief Get field zErr from state_correction message
shimniok 0:826c6171fc1b 162 *
shimniok 0:826c6171fc1b 163 * @return z position error
shimniok 0:826c6171fc1b 164 */
shimniok 0:826c6171fc1b 165 static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 166 {
shimniok 0:826c6171fc1b 167 generic_32bit r;
shimniok 0:826c6171fc1b 168 r.b[3] = (msg->payload+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 169 r.b[2] = (msg->payload+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 170 r.b[1] = (msg->payload+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 171 r.b[0] = (msg->payload+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 172 return (float)r.f;
shimniok 0:826c6171fc1b 173 }
shimniok 0:826c6171fc1b 174
shimniok 0:826c6171fc1b 175 /**
shimniok 0:826c6171fc1b 176 * @brief Get field rollErr from state_correction message
shimniok 0:826c6171fc1b 177 *
shimniok 0:826c6171fc1b 178 * @return roll error (radians)
shimniok 0:826c6171fc1b 179 */
shimniok 0:826c6171fc1b 180 static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 181 {
shimniok 0:826c6171fc1b 182 generic_32bit r;
shimniok 0:826c6171fc1b 183 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 184 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 185 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 186 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 187 return (float)r.f;
shimniok 0:826c6171fc1b 188 }
shimniok 0:826c6171fc1b 189
shimniok 0:826c6171fc1b 190 /**
shimniok 0:826c6171fc1b 191 * @brief Get field pitchErr from state_correction message
shimniok 0:826c6171fc1b 192 *
shimniok 0:826c6171fc1b 193 * @return pitch error (radians)
shimniok 0:826c6171fc1b 194 */
shimniok 0:826c6171fc1b 195 static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 196 {
shimniok 0:826c6171fc1b 197 generic_32bit r;
shimniok 0:826c6171fc1b 198 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 199 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 200 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 201 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 202 return (float)r.f;
shimniok 0:826c6171fc1b 203 }
shimniok 0:826c6171fc1b 204
shimniok 0:826c6171fc1b 205 /**
shimniok 0:826c6171fc1b 206 * @brief Get field yawErr from state_correction message
shimniok 0:826c6171fc1b 207 *
shimniok 0:826c6171fc1b 208 * @return yaw error (radians)
shimniok 0:826c6171fc1b 209 */
shimniok 0:826c6171fc1b 210 static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 211 {
shimniok 0:826c6171fc1b 212 generic_32bit r;
shimniok 0:826c6171fc1b 213 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 214 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 215 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 216 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 217 return (float)r.f;
shimniok 0:826c6171fc1b 218 }
shimniok 0:826c6171fc1b 219
shimniok 0:826c6171fc1b 220 /**
shimniok 0:826c6171fc1b 221 * @brief Get field vxErr from state_correction message
shimniok 0:826c6171fc1b 222 *
shimniok 0:826c6171fc1b 223 * @return x velocity
shimniok 0:826c6171fc1b 224 */
shimniok 0:826c6171fc1b 225 static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 226 {
shimniok 0:826c6171fc1b 227 generic_32bit r;
shimniok 0:826c6171fc1b 228 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 229 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 230 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 231 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 232 return (float)r.f;
shimniok 0:826c6171fc1b 233 }
shimniok 0:826c6171fc1b 234
shimniok 0:826c6171fc1b 235 /**
shimniok 0:826c6171fc1b 236 * @brief Get field vyErr from state_correction message
shimniok 0:826c6171fc1b 237 *
shimniok 0:826c6171fc1b 238 * @return y velocity
shimniok 0:826c6171fc1b 239 */
shimniok 0:826c6171fc1b 240 static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 241 {
shimniok 0:826c6171fc1b 242 generic_32bit r;
shimniok 0:826c6171fc1b 243 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 244 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 245 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 246 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 247 return (float)r.f;
shimniok 0:826c6171fc1b 248 }
shimniok 0:826c6171fc1b 249
shimniok 0:826c6171fc1b 250 /**
shimniok 0:826c6171fc1b 251 * @brief Get field vzErr from state_correction message
shimniok 0:826c6171fc1b 252 *
shimniok 0:826c6171fc1b 253 * @return z velocity
shimniok 0:826c6171fc1b 254 */
shimniok 0:826c6171fc1b 255 static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg)
shimniok 0:826c6171fc1b 256 {
shimniok 0:826c6171fc1b 257 generic_32bit r;
shimniok 0:826c6171fc1b 258 r.b[3] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
shimniok 0:826c6171fc1b 259 r.b[2] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
shimniok 0:826c6171fc1b 260 r.b[1] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
shimniok 0:826c6171fc1b 261 r.b[0] = (msg->payload+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
shimniok 0:826c6171fc1b 262 return (float)r.f;
shimniok 0:826c6171fc1b 263 }
shimniok 0:826c6171fc1b 264
shimniok 0:826c6171fc1b 265 /**
shimniok 0:826c6171fc1b 266 * @brief Decode a state_correction message into a struct
shimniok 0:826c6171fc1b 267 *
shimniok 0:826c6171fc1b 268 * @param msg The message to decode
shimniok 0:826c6171fc1b 269 * @param state_correction C-struct to decode the message contents into
shimniok 0:826c6171fc1b 270 */
shimniok 0:826c6171fc1b 271 static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction)
shimniok 0:826c6171fc1b 272 {
shimniok 0:826c6171fc1b 273 state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg);
shimniok 0:826c6171fc1b 274 state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg);
shimniok 0:826c6171fc1b 275 state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg);
shimniok 0:826c6171fc1b 276 state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg);
shimniok 0:826c6171fc1b 277 state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg);
shimniok 0:826c6171fc1b 278 state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg);
shimniok 0:826c6171fc1b 279 state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg);
shimniok 0:826c6171fc1b 280 state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg);
shimniok 0:826c6171fc1b 281 state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg);
shimniok 0:826c6171fc1b 282 }