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