Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.
Dependencies: Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo
mavlink_msg_image_available.h
00001 // MESSAGE IMAGE_AVAILABLE PACKING 00002 00003 #define MAVLINK_MSG_ID_IMAGE_AVAILABLE 103 00004 00005 typedef struct __mavlink_image_available_t 00006 { 00007 uint64_t cam_id; ///< Camera id 00008 uint8_t cam_no; ///< Camera # (starts with 0) 00009 uint64_t timestamp; ///< Timestamp 00010 uint64_t valid_until; ///< Until which timestamp this buffer will stay valid 00011 uint32_t img_seq; ///< The image sequence number 00012 uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 00013 uint16_t width; ///< Image width 00014 uint16_t height; ///< Image height 00015 uint16_t depth; ///< Image depth 00016 uint8_t channels; ///< Image channels 00017 uint32_t key; ///< Shared memory area key 00018 uint32_t exposure; ///< Exposure time, in microseconds 00019 float gain; ///< Camera gain 00020 float roll; ///< Roll angle in rad 00021 float pitch; ///< Pitch angle in rad 00022 float yaw; ///< Yaw angle in rad 00023 float local_z; ///< Local frame Z coordinate (height over ground) 00024 float lat; ///< GPS X coordinate 00025 float lon; ///< GPS Y coordinate 00026 float alt; ///< Global frame altitude 00027 float ground_x; ///< Ground truth X 00028 float ground_y; ///< Ground truth Y 00029 float ground_z; ///< Ground truth Z 00030 00031 } mavlink_image_available_t; 00032 00033 00034 00035 /** 00036 * @brief Pack a image_available message 00037 * @param system_id ID of this system 00038 * @param component_id ID of this component (e.g. 200 for IMU) 00039 * @param msg The MAVLink message to compress the data into 00040 * 00041 * @param cam_id Camera id 00042 * @param cam_no Camera # (starts with 0) 00043 * @param timestamp Timestamp 00044 * @param valid_until Until which timestamp this buffer will stay valid 00045 * @param img_seq The image sequence number 00046 * @param img_buf_index Position of the image in the buffer, starts with 0 00047 * @param width Image width 00048 * @param height Image height 00049 * @param depth Image depth 00050 * @param channels Image channels 00051 * @param key Shared memory area key 00052 * @param exposure Exposure time, in microseconds 00053 * @param gain Camera gain 00054 * @param roll Roll angle in rad 00055 * @param pitch Pitch angle in rad 00056 * @param yaw Yaw angle in rad 00057 * @param local_z Local frame Z coordinate (height over ground) 00058 * @param lat GPS X coordinate 00059 * @param lon GPS Y coordinate 00060 * @param alt Global frame altitude 00061 * @param ground_x Ground truth X 00062 * @param ground_y Ground truth Y 00063 * @param ground_z Ground truth Z 00064 * @return length of the message in bytes (excluding serial stream start sign) 00065 */ 00066 static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00067 { 00068 uint16_t i = 0; 00069 msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; 00070 00071 i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id 00072 i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0) 00073 i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp 00074 i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid 00075 i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number 00076 i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0 00077 i += put_uint16_t_by_index(width, i, msg->payload); // Image width 00078 i += put_uint16_t_by_index(height, i, msg->payload); // Image height 00079 i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth 00080 i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels 00081 i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key 00082 i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds 00083 i += put_float_by_index(gain, i, msg->payload); // Camera gain 00084 i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad 00085 i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad 00086 i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad 00087 i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) 00088 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate 00089 i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate 00090 i += put_float_by_index(alt, i, msg->payload); // Global frame altitude 00091 i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X 00092 i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y 00093 i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z 00094 00095 return mavlink_finalize_message(msg, system_id, component_id, i); 00096 } 00097 00098 /** 00099 * @brief Pack a image_available message 00100 * @param system_id ID of this system 00101 * @param component_id ID of this component (e.g. 200 for IMU) 00102 * @param chan The MAVLink channel this message was sent over 00103 * @param msg The MAVLink message to compress the data into 00104 * @param cam_id Camera id 00105 * @param cam_no Camera # (starts with 0) 00106 * @param timestamp Timestamp 00107 * @param valid_until Until which timestamp this buffer will stay valid 00108 * @param img_seq The image sequence number 00109 * @param img_buf_index Position of the image in the buffer, starts with 0 00110 * @param width Image width 00111 * @param height Image height 00112 * @param depth Image depth 00113 * @param channels Image channels 00114 * @param key Shared memory area key 00115 * @param exposure Exposure time, in microseconds 00116 * @param gain Camera gain 00117 * @param roll Roll angle in rad 00118 * @param pitch Pitch angle in rad 00119 * @param yaw Yaw angle in rad 00120 * @param local_z Local frame Z coordinate (height over ground) 00121 * @param lat GPS X coordinate 00122 * @param lon GPS Y coordinate 00123 * @param alt Global frame altitude 00124 * @param ground_x Ground truth X 00125 * @param ground_y Ground truth Y 00126 * @param ground_z Ground truth Z 00127 * @return length of the message in bytes (excluding serial stream start sign) 00128 */ 00129 static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00130 { 00131 uint16_t i = 0; 00132 msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; 00133 00134 i += put_uint64_t_by_index(cam_id, i, msg->payload); // Camera id 00135 i += put_uint8_t_by_index(cam_no, i, msg->payload); // Camera # (starts with 0) 00136 i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp 00137 i += put_uint64_t_by_index(valid_until, i, msg->payload); // Until which timestamp this buffer will stay valid 00138 i += put_uint32_t_by_index(img_seq, i, msg->payload); // The image sequence number 00139 i += put_uint32_t_by_index(img_buf_index, i, msg->payload); // Position of the image in the buffer, starts with 0 00140 i += put_uint16_t_by_index(width, i, msg->payload); // Image width 00141 i += put_uint16_t_by_index(height, i, msg->payload); // Image height 00142 i += put_uint16_t_by_index(depth, i, msg->payload); // Image depth 00143 i += put_uint8_t_by_index(channels, i, msg->payload); // Image channels 00144 i += put_uint32_t_by_index(key, i, msg->payload); // Shared memory area key 00145 i += put_uint32_t_by_index(exposure, i, msg->payload); // Exposure time, in microseconds 00146 i += put_float_by_index(gain, i, msg->payload); // Camera gain 00147 i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad 00148 i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad 00149 i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad 00150 i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) 00151 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate 00152 i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate 00153 i += put_float_by_index(alt, i, msg->payload); // Global frame altitude 00154 i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X 00155 i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y 00156 i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z 00157 00158 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00159 } 00160 00161 /** 00162 * @brief Encode a image_available struct into a message 00163 * 00164 * @param system_id ID of this system 00165 * @param component_id ID of this component (e.g. 200 for IMU) 00166 * @param msg The MAVLink message to compress the data into 00167 * @param image_available C-struct to read the message contents from 00168 */ 00169 static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) 00170 { 00171 return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z); 00172 } 00173 00174 /** 00175 * @brief Send a image_available message 00176 * @param chan MAVLink channel to send the message 00177 * 00178 * @param cam_id Camera id 00179 * @param cam_no Camera # (starts with 0) 00180 * @param timestamp Timestamp 00181 * @param valid_until Until which timestamp this buffer will stay valid 00182 * @param img_seq The image sequence number 00183 * @param img_buf_index Position of the image in the buffer, starts with 0 00184 * @param width Image width 00185 * @param height Image height 00186 * @param depth Image depth 00187 * @param channels Image channels 00188 * @param key Shared memory area key 00189 * @param exposure Exposure time, in microseconds 00190 * @param gain Camera gain 00191 * @param roll Roll angle in rad 00192 * @param pitch Pitch angle in rad 00193 * @param yaw Yaw angle in rad 00194 * @param local_z Local frame Z coordinate (height over ground) 00195 * @param lat GPS X coordinate 00196 * @param lon GPS Y coordinate 00197 * @param alt Global frame altitude 00198 * @param ground_x Ground truth X 00199 * @param ground_y Ground truth Y 00200 * @param ground_z Ground truth Z 00201 */ 00202 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00203 00204 static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00205 { 00206 mavlink_message_t msg; 00207 mavlink_msg_image_available_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, cam_id, cam_no, timestamp, valid_until, img_seq, img_buf_index, width, height, depth, channels, key, exposure, gain, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z); 00208 mavlink_send_uart(chan, &msg); 00209 } 00210 00211 #endif 00212 // MESSAGE IMAGE_AVAILABLE UNPACKING 00213 00214 /** 00215 * @brief Get field cam_id from image_available message 00216 * 00217 * @return Camera id 00218 */ 00219 static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg) 00220 { 00221 generic_64bit r; 00222 r.b[7] = (msg->payload)[0]; 00223 r.b[6] = (msg->payload)[1]; 00224 r.b[5] = (msg->payload)[2]; 00225 r.b[4] = (msg->payload)[3]; 00226 r.b[3] = (msg->payload)[4]; 00227 r.b[2] = (msg->payload)[5]; 00228 r.b[1] = (msg->payload)[6]; 00229 r.b[0] = (msg->payload)[7]; 00230 return (uint64_t)r.ll; 00231 } 00232 00233 /** 00234 * @brief Get field cam_no from image_available message 00235 * 00236 * @return Camera # (starts with 0) 00237 */ 00238 static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) 00239 { 00240 return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; 00241 } 00242 00243 /** 00244 * @brief Get field timestamp from image_available message 00245 * 00246 * @return Timestamp 00247 */ 00248 static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) 00249 { 00250 generic_64bit r; 00251 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; 00252 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; 00253 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; 00254 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; 00255 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4]; 00256 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5]; 00257 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6]; 00258 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7]; 00259 return (uint64_t)r.ll; 00260 } 00261 00262 /** 00263 * @brief Get field valid_until from image_available message 00264 * 00265 * @return Until which timestamp this buffer will stay valid 00266 */ 00267 static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) 00268 { 00269 generic_64bit r; 00270 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[0]; 00271 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[1]; 00272 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[2]; 00273 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[3]; 00274 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[4]; 00275 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[5]; 00276 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[6]; 00277 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t))[7]; 00278 return (uint64_t)r.ll; 00279 } 00280 00281 /** 00282 * @brief Get field img_seq from image_available message 00283 * 00284 * @return The image sequence number 00285 */ 00286 static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) 00287 { 00288 generic_32bit r; 00289 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[0]; 00290 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[1]; 00291 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[2]; 00292 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t))[3]; 00293 return (uint32_t)r.i; 00294 } 00295 00296 /** 00297 * @brief Get field img_buf_index from image_available message 00298 * 00299 * @return Position of the image in the buffer, starts with 0 00300 */ 00301 static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) 00302 { 00303 generic_32bit r; 00304 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[0]; 00305 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[1]; 00306 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[2]; 00307 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t))[3]; 00308 return (uint32_t)r.i; 00309 } 00310 00311 /** 00312 * @brief Get field width from image_available message 00313 * 00314 * @return Image width 00315 */ 00316 static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) 00317 { 00318 generic_16bit r; 00319 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; 00320 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; 00321 return (uint16_t)r.s; 00322 } 00323 00324 /** 00325 * @brief Get field height from image_available message 00326 * 00327 * @return Image height 00328 */ 00329 static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) 00330 { 00331 generic_16bit r; 00332 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[0]; 00333 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t))[1]; 00334 return (uint16_t)r.s; 00335 } 00336 00337 /** 00338 * @brief Get field depth from image_available message 00339 * 00340 * @return Image depth 00341 */ 00342 static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) 00343 { 00344 generic_16bit r; 00345 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00346 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t))[1]; 00347 return (uint16_t)r.s; 00348 } 00349 00350 /** 00351 * @brief Get field channels from image_available message 00352 * 00353 * @return Image channels 00354 */ 00355 static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) 00356 { 00357 return (uint8_t)(msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t))[0]; 00358 } 00359 00360 /** 00361 * @brief Get field key from image_available message 00362 * 00363 * @return Shared memory area key 00364 */ 00365 static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) 00366 { 00367 generic_32bit r; 00368 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[0]; 00369 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[1]; 00370 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[2]; 00371 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t))[3]; 00372 return (uint32_t)r.i; 00373 } 00374 00375 /** 00376 * @brief Get field exposure from image_available message 00377 * 00378 * @return Exposure time, in microseconds 00379 */ 00380 static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) 00381 { 00382 generic_32bit r; 00383 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[0]; 00384 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[1]; 00385 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[2]; 00386 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t))[3]; 00387 return (uint32_t)r.i; 00388 } 00389 00390 /** 00391 * @brief Get field gain from image_available message 00392 * 00393 * @return Camera gain 00394 */ 00395 static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) 00396 { 00397 generic_32bit r; 00398 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[0]; 00399 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[1]; 00400 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[2]; 00401 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t))[3]; 00402 return (float)r.f; 00403 } 00404 00405 /** 00406 * @brief Get field roll from image_available message 00407 * 00408 * @return Roll angle in rad 00409 */ 00410 static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) 00411 { 00412 generic_32bit r; 00413 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[0]; 00414 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[1]; 00415 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[2]; 00416 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float))[3]; 00417 return (float)r.f; 00418 } 00419 00420 /** 00421 * @brief Get field pitch from image_available message 00422 * 00423 * @return Pitch angle in rad 00424 */ 00425 static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) 00426 { 00427 generic_32bit r; 00428 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0]; 00429 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1]; 00430 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2]; 00431 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3]; 00432 return (float)r.f; 00433 } 00434 00435 /** 00436 * @brief Get field yaw from image_available message 00437 * 00438 * @return Yaw angle in rad 00439 */ 00440 static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg) 00441 { 00442 generic_32bit r; 00443 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00444 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00445 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00446 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00447 return (float)r.f; 00448 } 00449 00450 /** 00451 * @brief Get field local_z from image_available message 00452 * 00453 * @return Local frame Z coordinate (height over ground) 00454 */ 00455 static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg) 00456 { 00457 generic_32bit r; 00458 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00459 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00460 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00461 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00462 return (float)r.f; 00463 } 00464 00465 /** 00466 * @brief Get field lat from image_available message 00467 * 00468 * @return GPS X coordinate 00469 */ 00470 static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg) 00471 { 00472 generic_32bit r; 00473 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00474 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00475 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00476 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00477 return (float)r.f; 00478 } 00479 00480 /** 00481 * @brief Get field lon from image_available message 00482 * 00483 * @return GPS Y coordinate 00484 */ 00485 static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg) 00486 { 00487 generic_32bit r; 00488 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00489 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00490 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00491 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00492 return (float)r.f; 00493 } 00494 00495 /** 00496 * @brief Get field alt from image_available message 00497 * 00498 * @return Global frame altitude 00499 */ 00500 static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg) 00501 { 00502 generic_32bit r; 00503 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00504 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00505 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00506 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00507 return (float)r.f; 00508 } 00509 00510 /** 00511 * @brief Get field ground_x from image_available message 00512 * 00513 * @return Ground truth X 00514 */ 00515 static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg) 00516 { 00517 generic_32bit r; 00518 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00519 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00520 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00521 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00522 return (float)r.f; 00523 } 00524 00525 /** 00526 * @brief Get field ground_y from image_available message 00527 * 00528 * @return Ground truth Y 00529 */ 00530 static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg) 00531 { 00532 generic_32bit r; 00533 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00534 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00535 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00536 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00537 return (float)r.f; 00538 } 00539 00540 /** 00541 * @brief Get field ground_z from image_available message 00542 * 00543 * @return Ground truth Z 00544 */ 00545 static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg) 00546 { 00547 generic_32bit r; 00548 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00549 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00550 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00551 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(uint64_t)+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint16_t)+sizeof(uint8_t)+sizeof(uint32_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00552 return (float)r.f; 00553 } 00554 00555 /** 00556 * @brief Decode a image_available message into a struct 00557 * 00558 * @param msg The message to decode 00559 * @param image_available C-struct to decode the message contents into 00560 */ 00561 static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available) 00562 { 00563 image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); 00564 image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); 00565 image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); 00566 image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); 00567 image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); 00568 image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); 00569 image_available->width = mavlink_msg_image_available_get_width(msg); 00570 image_available->height = mavlink_msg_image_available_get_height(msg); 00571 image_available->depth = mavlink_msg_image_available_get_depth(msg); 00572 image_available->channels = mavlink_msg_image_available_get_channels(msg); 00573 image_available->key = mavlink_msg_image_available_get_key(msg); 00574 image_available->exposure = mavlink_msg_image_available_get_exposure(msg); 00575 image_available->gain = mavlink_msg_image_available_get_gain(msg); 00576 image_available->roll = mavlink_msg_image_available_get_roll(msg); 00577 image_available->pitch = mavlink_msg_image_available_get_pitch(msg); 00578 image_available->yaw = mavlink_msg_image_available_get_yaw(msg); 00579 image_available->local_z = mavlink_msg_image_available_get_local_z(msg); 00580 image_available->lat = mavlink_msg_image_available_get_lat(msg); 00581 image_available->lon = mavlink_msg_image_available_get_lon(msg); 00582 image_available->alt = mavlink_msg_image_available_get_alt(msg); 00583 image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg); 00584 image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg); 00585 image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg); 00586 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2