Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Committer:
shimniok
Date:
Fri Nov 30 16:11:53 2018 +0000
Revision:
25:bb5356402687
Parent:
0:a6a169de725f
Initial publish of revised version.

Who changed what in which revision?

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