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_triggered.h
00001 // MESSAGE IMAGE_TRIGGERED PACKING 00002 00003 #define MAVLINK_MSG_ID_IMAGE_TRIGGERED 101 00004 00005 typedef struct __mavlink_image_triggered_t 00006 { 00007 uint64_t timestamp; ///< Timestamp 00008 uint32_t seq; ///< IMU seq 00009 float roll; ///< Roll angle in rad 00010 float pitch; ///< Pitch angle in rad 00011 float yaw; ///< Yaw angle in rad 00012 float local_z; ///< Local frame Z coordinate (height over ground) 00013 float lat; ///< GPS X coordinate 00014 float lon; ///< GPS Y coordinate 00015 float alt; ///< Global frame altitude 00016 float ground_x; ///< Ground truth X 00017 float ground_y; ///< Ground truth Y 00018 float ground_z; ///< Ground truth Z 00019 00020 } mavlink_image_triggered_t; 00021 00022 00023 00024 /** 00025 * @brief Pack a image_triggered message 00026 * @param system_id ID of this system 00027 * @param component_id ID of this component (e.g. 200 for IMU) 00028 * @param msg The MAVLink message to compress the data into 00029 * 00030 * @param timestamp Timestamp 00031 * @param seq IMU seq 00032 * @param roll Roll angle in rad 00033 * @param pitch Pitch angle in rad 00034 * @param yaw Yaw angle in rad 00035 * @param local_z Local frame Z coordinate (height over ground) 00036 * @param lat GPS X coordinate 00037 * @param lon GPS Y coordinate 00038 * @param alt Global frame altitude 00039 * @param ground_x Ground truth X 00040 * @param ground_y Ground truth Y 00041 * @param ground_z Ground truth Z 00042 * @return length of the message in bytes (excluding serial stream start sign) 00043 */ 00044 static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00045 { 00046 uint16_t i = 0; 00047 msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; 00048 00049 i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp 00050 i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq 00051 i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad 00052 i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad 00053 i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad 00054 i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) 00055 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate 00056 i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate 00057 i += put_float_by_index(alt, i, msg->payload); // Global frame altitude 00058 i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X 00059 i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y 00060 i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z 00061 00062 return mavlink_finalize_message(msg, system_id, component_id, i); 00063 } 00064 00065 /** 00066 * @brief Pack a image_triggered message 00067 * @param system_id ID of this system 00068 * @param component_id ID of this component (e.g. 200 for IMU) 00069 * @param chan The MAVLink channel this message was sent over 00070 * @param msg The MAVLink message to compress the data into 00071 * @param timestamp Timestamp 00072 * @param seq IMU seq 00073 * @param roll Roll angle in rad 00074 * @param pitch Pitch angle in rad 00075 * @param yaw Yaw angle in rad 00076 * @param local_z Local frame Z coordinate (height over ground) 00077 * @param lat GPS X coordinate 00078 * @param lon GPS Y coordinate 00079 * @param alt Global frame altitude 00080 * @param ground_x Ground truth X 00081 * @param ground_y Ground truth Y 00082 * @param ground_z Ground truth Z 00083 * @return length of the message in bytes (excluding serial stream start sign) 00084 */ 00085 static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00086 { 00087 uint16_t i = 0; 00088 msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; 00089 00090 i += put_uint64_t_by_index(timestamp, i, msg->payload); // Timestamp 00091 i += put_uint32_t_by_index(seq, i, msg->payload); // IMU seq 00092 i += put_float_by_index(roll, i, msg->payload); // Roll angle in rad 00093 i += put_float_by_index(pitch, i, msg->payload); // Pitch angle in rad 00094 i += put_float_by_index(yaw, i, msg->payload); // Yaw angle in rad 00095 i += put_float_by_index(local_z, i, msg->payload); // Local frame Z coordinate (height over ground) 00096 i += put_float_by_index(lat, i, msg->payload); // GPS X coordinate 00097 i += put_float_by_index(lon, i, msg->payload); // GPS Y coordinate 00098 i += put_float_by_index(alt, i, msg->payload); // Global frame altitude 00099 i += put_float_by_index(ground_x, i, msg->payload); // Ground truth X 00100 i += put_float_by_index(ground_y, i, msg->payload); // Ground truth Y 00101 i += put_float_by_index(ground_z, i, msg->payload); // Ground truth Z 00102 00103 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00104 } 00105 00106 /** 00107 * @brief Encode a image_triggered struct into a message 00108 * 00109 * @param system_id ID of this system 00110 * @param component_id ID of this component (e.g. 200 for IMU) 00111 * @param msg The MAVLink message to compress the data into 00112 * @param image_triggered C-struct to read the message contents from 00113 */ 00114 static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) 00115 { 00116 return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z); 00117 } 00118 00119 /** 00120 * @brief Send a image_triggered message 00121 * @param chan MAVLink channel to send the message 00122 * 00123 * @param timestamp Timestamp 00124 * @param seq IMU seq 00125 * @param roll Roll angle in rad 00126 * @param pitch Pitch angle in rad 00127 * @param yaw Yaw angle in rad 00128 * @param local_z Local frame Z coordinate (height over ground) 00129 * @param lat GPS X coordinate 00130 * @param lon GPS Y coordinate 00131 * @param alt Global frame altitude 00132 * @param ground_x Ground truth X 00133 * @param ground_y Ground truth Y 00134 * @param ground_z Ground truth Z 00135 */ 00136 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00137 00138 static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) 00139 { 00140 mavlink_message_t msg; 00141 mavlink_msg_image_triggered_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, timestamp, seq, roll, pitch, yaw, local_z, lat, lon, alt, ground_x, ground_y, ground_z); 00142 mavlink_send_uart(chan, &msg); 00143 } 00144 00145 #endif 00146 // MESSAGE IMAGE_TRIGGERED UNPACKING 00147 00148 /** 00149 * @brief Get field timestamp from image_triggered message 00150 * 00151 * @return Timestamp 00152 */ 00153 static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg) 00154 { 00155 generic_64bit r; 00156 r.b[7] = (msg->payload)[0]; 00157 r.b[6] = (msg->payload)[1]; 00158 r.b[5] = (msg->payload)[2]; 00159 r.b[4] = (msg->payload)[3]; 00160 r.b[3] = (msg->payload)[4]; 00161 r.b[2] = (msg->payload)[5]; 00162 r.b[1] = (msg->payload)[6]; 00163 r.b[0] = (msg->payload)[7]; 00164 return (uint64_t)r.ll; 00165 } 00166 00167 /** 00168 * @brief Get field seq from image_triggered message 00169 * 00170 * @return IMU seq 00171 */ 00172 static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg) 00173 { 00174 generic_32bit r; 00175 r.b[3] = (msg->payload+sizeof(uint64_t))[0]; 00176 r.b[2] = (msg->payload+sizeof(uint64_t))[1]; 00177 r.b[1] = (msg->payload+sizeof(uint64_t))[2]; 00178 r.b[0] = (msg->payload+sizeof(uint64_t))[3]; 00179 return (uint32_t)r.i; 00180 } 00181 00182 /** 00183 * @brief Get field roll from image_triggered message 00184 * 00185 * @return Roll angle in rad 00186 */ 00187 static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg) 00188 { 00189 generic_32bit r; 00190 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[0]; 00191 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[1]; 00192 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[2]; 00193 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t))[3]; 00194 return (float)r.f; 00195 } 00196 00197 /** 00198 * @brief Get field pitch from image_triggered message 00199 * 00200 * @return Pitch angle in rad 00201 */ 00202 static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg) 00203 { 00204 generic_32bit r; 00205 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[0]; 00206 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[1]; 00207 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[2]; 00208 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float))[3]; 00209 return (float)r.f; 00210 } 00211 00212 /** 00213 * @brief Get field yaw from image_triggered message 00214 * 00215 * @return Yaw angle in rad 00216 */ 00217 static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg) 00218 { 00219 generic_32bit r; 00220 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[0]; 00221 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[1]; 00222 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[2]; 00223 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float))[3]; 00224 return (float)r.f; 00225 } 00226 00227 /** 00228 * @brief Get field local_z from image_triggered message 00229 * 00230 * @return Local frame Z coordinate (height over ground) 00231 */ 00232 static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg) 00233 { 00234 generic_32bit r; 00235 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00236 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00237 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00238 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00239 return (float)r.f; 00240 } 00241 00242 /** 00243 * @brief Get field lat from image_triggered message 00244 * 00245 * @return GPS X coordinate 00246 */ 00247 static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg) 00248 { 00249 generic_32bit r; 00250 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00251 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00252 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00253 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00254 return (float)r.f; 00255 } 00256 00257 /** 00258 * @brief Get field lon from image_triggered message 00259 * 00260 * @return GPS Y coordinate 00261 */ 00262 static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg) 00263 { 00264 generic_32bit r; 00265 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00266 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00267 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00268 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00269 return (float)r.f; 00270 } 00271 00272 /** 00273 * @brief Get field alt from image_triggered message 00274 * 00275 * @return Global frame altitude 00276 */ 00277 static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg) 00278 { 00279 generic_32bit r; 00280 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00281 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00282 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00283 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00284 return (float)r.f; 00285 } 00286 00287 /** 00288 * @brief Get field ground_x from image_triggered message 00289 * 00290 * @return Ground truth X 00291 */ 00292 static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg) 00293 { 00294 generic_32bit r; 00295 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00296 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00297 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00298 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00299 return (float)r.f; 00300 } 00301 00302 /** 00303 * @brief Get field ground_y from image_triggered message 00304 * 00305 * @return Ground truth Y 00306 */ 00307 static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg) 00308 { 00309 generic_32bit r; 00310 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00311 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00312 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00313 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00314 return (float)r.f; 00315 } 00316 00317 /** 00318 * @brief Get field ground_z from image_triggered message 00319 * 00320 * @return Ground truth Z 00321 */ 00322 static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg) 00323 { 00324 generic_32bit r; 00325 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00326 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00327 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00328 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint32_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00329 return (float)r.f; 00330 } 00331 00332 /** 00333 * @brief Decode a image_triggered message into a struct 00334 * 00335 * @param msg The message to decode 00336 * @param image_triggered C-struct to decode the message contents into 00337 */ 00338 static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered) 00339 { 00340 image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg); 00341 image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg); 00342 image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg); 00343 image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg); 00344 image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg); 00345 image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg); 00346 image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg); 00347 image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg); 00348 image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg); 00349 image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg); 00350 image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg); 00351 image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg); 00352 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2