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:
Mon May 27 13:26:03 2013 +0000
Revision:
0:a6a169de725f
Working version with priorities set and update time display

Who changed what in which revision?

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