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_global_position.h
00001 // MESSAGE GLOBAL_POSITION PACKING 00002 00003 #define MAVLINK_MSG_ID_GLOBAL_POSITION 33 00004 00005 typedef struct __mavlink_global_position_t 00006 { 00007 uint64_t usec; ///< Timestamp (microseconds since unix epoch) 00008 float lat; ///< Latitude, in degrees 00009 float lon; ///< Longitude, in degrees 00010 float alt; ///< Absolute altitude, in meters 00011 float vx; ///< X Speed (in Latitude direction, positive: going north) 00012 float vy; ///< Y Speed (in Longitude direction, positive: going east) 00013 float vz; ///< Z Speed (in Altitude direction, positive: going up) 00014 00015 } mavlink_global_position_t; 00016 00017 00018 00019 /** 00020 * @brief Pack a global_position message 00021 * @param system_id ID of this system 00022 * @param component_id ID of this component (e.g. 200 for IMU) 00023 * @param msg The MAVLink message to compress the data into 00024 * 00025 * @param usec Timestamp (microseconds since unix epoch) 00026 * @param lat Latitude, in degrees 00027 * @param lon Longitude, in degrees 00028 * @param alt Absolute altitude, in meters 00029 * @param vx X Speed (in Latitude direction, positive: going north) 00030 * @param vy Y Speed (in Longitude direction, positive: going east) 00031 * @param vz Z Speed (in Altitude direction, positive: going up) 00032 * @return length of the message in bytes (excluding serial stream start sign) 00033 */ 00034 static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) 00035 { 00036 uint16_t i = 0; 00037 msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; 00038 00039 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch) 00040 i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees 00041 i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees 00042 i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters 00043 i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north) 00044 i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east) 00045 i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up) 00046 00047 return mavlink_finalize_message(msg, system_id, component_id, i); 00048 } 00049 00050 /** 00051 * @brief Pack a global_position message 00052 * @param system_id ID of this system 00053 * @param component_id ID of this component (e.g. 200 for IMU) 00054 * @param chan The MAVLink channel this message was sent over 00055 * @param msg The MAVLink message to compress the data into 00056 * @param usec Timestamp (microseconds since unix epoch) 00057 * @param lat Latitude, in degrees 00058 * @param lon Longitude, in degrees 00059 * @param alt Absolute altitude, in meters 00060 * @param vx X Speed (in Latitude direction, positive: going north) 00061 * @param vy Y Speed (in Longitude direction, positive: going east) 00062 * @param vz Z Speed (in Altitude direction, positive: going up) 00063 * @return length of the message in bytes (excluding serial stream start sign) 00064 */ 00065 static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) 00066 { 00067 uint16_t i = 0; 00068 msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION; 00069 00070 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since unix epoch) 00071 i += put_float_by_index(lat, i, msg->payload); // Latitude, in degrees 00072 i += put_float_by_index(lon, i, msg->payload); // Longitude, in degrees 00073 i += put_float_by_index(alt, i, msg->payload); // Absolute altitude, in meters 00074 i += put_float_by_index(vx, i, msg->payload); // X Speed (in Latitude direction, positive: going north) 00075 i += put_float_by_index(vy, i, msg->payload); // Y Speed (in Longitude direction, positive: going east) 00076 i += put_float_by_index(vz, i, msg->payload); // Z Speed (in Altitude direction, positive: going up) 00077 00078 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00079 } 00080 00081 /** 00082 * @brief Encode a global_position struct into a message 00083 * 00084 * @param system_id ID of this system 00085 * @param component_id ID of this component (e.g. 200 for IMU) 00086 * @param msg The MAVLink message to compress the data into 00087 * @param global_position C-struct to read the message contents from 00088 */ 00089 static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position) 00090 { 00091 return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz); 00092 } 00093 00094 /** 00095 * @brief Send a global_position message 00096 * @param chan MAVLink channel to send the message 00097 * 00098 * @param usec Timestamp (microseconds since unix epoch) 00099 * @param lat Latitude, in degrees 00100 * @param lon Longitude, in degrees 00101 * @param alt Absolute altitude, in meters 00102 * @param vx X Speed (in Latitude direction, positive: going north) 00103 * @param vy Y Speed (in Longitude direction, positive: going east) 00104 * @param vz Z Speed (in Altitude direction, positive: going up) 00105 */ 00106 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00107 00108 static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz) 00109 { 00110 mavlink_message_t msg; 00111 mavlink_msg_global_position_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, lat, lon, alt, vx, vy, vz); 00112 mavlink_send_uart(chan, &msg); 00113 } 00114 00115 #endif 00116 // MESSAGE GLOBAL_POSITION UNPACKING 00117 00118 /** 00119 * @brief Get field usec from global_position message 00120 * 00121 * @return Timestamp (microseconds since unix epoch) 00122 */ 00123 static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg) 00124 { 00125 generic_64bit r; 00126 r.b[7] = (msg->payload)[0]; 00127 r.b[6] = (msg->payload)[1]; 00128 r.b[5] = (msg->payload)[2]; 00129 r.b[4] = (msg->payload)[3]; 00130 r.b[3] = (msg->payload)[4]; 00131 r.b[2] = (msg->payload)[5]; 00132 r.b[1] = (msg->payload)[6]; 00133 r.b[0] = (msg->payload)[7]; 00134 return (uint64_t)r.ll; 00135 } 00136 00137 /** 00138 * @brief Get field lat from global_position message 00139 * 00140 * @return Latitude, in degrees 00141 */ 00142 static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg) 00143 { 00144 generic_32bit r; 00145 r.b[3] = (msg->payload+sizeof(uint64_t))[0]; 00146 r.b[2] = (msg->payload+sizeof(uint64_t))[1]; 00147 r.b[1] = (msg->payload+sizeof(uint64_t))[2]; 00148 r.b[0] = (msg->payload+sizeof(uint64_t))[3]; 00149 return (float)r.f; 00150 } 00151 00152 /** 00153 * @brief Get field lon from global_position message 00154 * 00155 * @return Longitude, in degrees 00156 */ 00157 static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg) 00158 { 00159 generic_32bit r; 00160 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float))[0]; 00161 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float))[1]; 00162 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float))[2]; 00163 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float))[3]; 00164 return (float)r.f; 00165 } 00166 00167 /** 00168 * @brief Get field alt from global_position message 00169 * 00170 * @return Absolute altitude, in meters 00171 */ 00172 static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg) 00173 { 00174 generic_32bit r; 00175 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[0]; 00176 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[1]; 00177 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[2]; 00178 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float))[3]; 00179 return (float)r.f; 00180 } 00181 00182 /** 00183 * @brief Get field vx from global_position message 00184 * 00185 * @return X Speed (in Latitude direction, positive: going north) 00186 */ 00187 static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg) 00188 { 00189 generic_32bit r; 00190 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00191 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00192 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00193 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00194 return (float)r.f; 00195 } 00196 00197 /** 00198 * @brief Get field vy from global_position message 00199 * 00200 * @return Y Speed (in Longitude direction, positive: going east) 00201 */ 00202 static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg) 00203 { 00204 generic_32bit r; 00205 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00206 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00207 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00208 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00209 return (float)r.f; 00210 } 00211 00212 /** 00213 * @brief Get field vz from global_position message 00214 * 00215 * @return Z Speed (in Altitude direction, positive: going up) 00216 */ 00217 static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg) 00218 { 00219 generic_32bit r; 00220 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00221 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00222 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00223 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00224 return (float)r.f; 00225 } 00226 00227 /** 00228 * @brief Decode a global_position message into a struct 00229 * 00230 * @param msg The message to decode 00231 * @param global_position C-struct to decode the message contents into 00232 */ 00233 static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position) 00234 { 00235 global_position->usec = mavlink_msg_global_position_get_usec(msg); 00236 global_position->lat = mavlink_msg_global_position_get_lat(msg); 00237 global_position->lon = mavlink_msg_global_position_get_lon(msg); 00238 global_position->alt = mavlink_msg_global_position_get_alt(msg); 00239 global_position->vx = mavlink_msg_global_position_get_vx(msg); 00240 global_position->vy = mavlink_msg_global_position_get_vy(msg); 00241 global_position->vz = mavlink_msg_global_position_get_vz(msg); 00242 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2