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_gps_raw_ugv.h
00001 // MESSAGE GPS_RAW_UGV PACKING 00002 00003 #define MAVLINK_MSG_ID_GPS_RAW_UGV 86 00004 00005 typedef struct __mavlink_gps_raw_ugv_t 00006 { 00007 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00008 uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00009 double lat; ///< Latitude in 1E15 degrees 00010 double lon; ///< Longitude in 1E15 degrees 00011 float eph; ///< GPS HDOP 00012 float epv; ///< GPS VDOP 00013 float v; ///< GPS ground speed 00014 float hdg; ///< Compass heading in degrees, 0..360 degrees 00015 00016 } mavlink_gps_raw_ugv_t; 00017 00018 00019 /** 00020 * @brief Pack a gps_raw 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 or microseconds since system boot) 00026 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00027 * @param lat Latitude in degrees 00028 * @param lon Longitude in degrees 00029 * @param eph GPS HDOP 00030 * @param epv GPS VDOP 00031 * @param v GPS ground speed 00032 * @param hdg Compass heading in degrees, 0..360 degrees 00033 * @return length of the message in bytes (excluding serial stream start sign) 00034 */ 00035 static inline uint16_t mavlink_msg_gps_raw_ugv_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg) 00036 { 00037 uint16_t i = 0; 00038 msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV; 00039 00040 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00041 i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00042 i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees 00043 i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees 00044 i += put_float_by_index(eph, i, msg->payload); // GPS HDOP 00045 i += put_float_by_index(epv, i, msg->payload); // GPS VDOP 00046 i += put_float_by_index(v, i, msg->payload); // GPS ground speed 00047 i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees 00048 00049 return mavlink_finalize_message(msg, system_id, component_id, i); 00050 } 00051 00052 /** 00053 * @brief Pack a gps_raw message 00054 * @param system_id ID of this system 00055 * @param component_id ID of this component (e.g. 200 for IMU) 00056 * @param chan The MAVLink channel this message was sent over 00057 * @param msg The MAVLink message to compress the data into 00058 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00059 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00060 * @param lat Latitude in degrees 00061 * @param lon Longitude in degrees 00062 * @param eph GPS HDOP 00063 * @param epv GPS VDOP 00064 * @param v GPS ground speed 00065 * @param hdg Compass heading in degrees, 0..360 degrees 00066 * @return length of the message in bytes (excluding serial stream start sign) 00067 */ 00068 static inline uint16_t mavlink_msg_gps_raw_ugv_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg) 00069 { 00070 uint16_t i = 0; 00071 msg->msgid = MAVLINK_MSG_ID_GPS_RAW_UGV; 00072 00073 i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00074 i += put_uint8_t_by_index(fix_type, i, msg->payload); // 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00075 i += put_double_by_index(lat, i, msg->payload); // Latitude in degrees 00076 i += put_double_by_index(lon, i, msg->payload); // Longitude in degrees 00077 i += put_float_by_index(eph, i, msg->payload); // GPS HDOP 00078 i += put_float_by_index(epv, i, msg->payload); // GPS VDOP 00079 i += put_float_by_index(v, i, msg->payload); // GPS ground speed 00080 i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees 00081 00082 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i); 00083 } 00084 00085 /** 00086 * @brief Encode a gps_raw struct into a message 00087 * 00088 * @param system_id ID of this system 00089 * @param component_id ID of this component (e.g. 200 for IMU) 00090 * @param msg The MAVLink message to compress the data into 00091 * @param gps_raw C-struct to read the message contents from 00092 */ 00093 static inline uint16_t mavlink_msg_gps_raw_ugv_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_ugv_t* gps_raw) 00094 { 00095 return mavlink_msg_gps_raw_ugv_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg); 00096 } 00097 00098 /** 00099 * @brief Send a gps_raw message 00100 * @param chan MAVLink channel to send the message 00101 * 00102 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00103 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00104 * @param lat Latitude in degrees 00105 * @param lon Longitude in degrees 00106 * @param eph GPS HDOP 00107 * @param epv GPS VDOP 00108 * @param v GPS ground speed 00109 * @param hdg Compass heading in degrees, 0..360 degrees 00110 */ 00111 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 00112 00113 static inline void mavlink_msg_gps_raw_ugv_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, double lat, double lon, float eph, float epv, float v, float hdg) 00114 { 00115 mavlink_message_t msg; 00116 mavlink_msg_gps_raw_ugv_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, eph, epv, v, hdg); 00117 mavlink_send_uart(chan, &msg); 00118 } 00119 00120 #endif 00121 // MESSAGE GPS_RAW UNPACKING 00122 00123 /** 00124 * @brief Get field usec from gps_raw message 00125 * 00126 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) 00127 */ 00128 static inline uint64_t mavlink_msg_gps_raw_ugv_get_usec(const mavlink_message_t* msg) 00129 { 00130 generic_64bit r; 00131 r.b[7] = (msg->payload)[0]; 00132 r.b[6] = (msg->payload)[1]; 00133 r.b[5] = (msg->payload)[2]; 00134 r.b[4] = (msg->payload)[3]; 00135 r.b[3] = (msg->payload)[4]; 00136 r.b[2] = (msg->payload)[5]; 00137 r.b[1] = (msg->payload)[6]; 00138 r.b[0] = (msg->payload)[7]; 00139 return (uint64_t)r.ll; 00140 } 00141 00142 /** 00143 * @brief Get field fix_type from gps_raw message 00144 * 00145 * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. 00146 */ 00147 static inline uint8_t mavlink_msg_gps_raw_ugv_get_fix_type(const mavlink_message_t* msg) 00148 { 00149 return (uint8_t)(msg->payload+sizeof(uint64_t))[0]; 00150 } 00151 00152 /** 00153 * @brief Get field lat from gps_raw message 00154 * 00155 * @return Latitude in degrees 00156 */ 00157 static inline double mavlink_msg_gps_raw_ugv_get_lat(const mavlink_message_t* msg) 00158 { 00159 generic_64bit r; 00160 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0]; 00161 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1]; 00162 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2]; 00163 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3]; 00164 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[4]; 00165 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[5]; 00166 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[6]; 00167 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[7]; 00168 return (double)r.d; 00169 } 00170 00171 /** 00172 * @brief Get field lon from gps_raw message 00173 * 00174 * @return Longitude in degrees 00175 */ 00176 static inline double mavlink_msg_gps_raw_ugv_get_lon(const mavlink_message_t* msg) 00177 { 00178 generic_64bit r; 00179 r.b[7] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[0]; 00180 r.b[6] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[1]; 00181 r.b[5] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[2]; 00182 r.b[4] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[3]; 00183 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[4]; 00184 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[5]; 00185 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[6]; 00186 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double))[7]; 00187 return (double)r.d; 00188 } 00189 00190 /** 00191 * @brief Get field eph from gps_raw message 00192 * 00193 * @return GPS HDOP 00194 */ 00195 static inline float mavlink_msg_gps_raw_ugv_get_eph(const mavlink_message_t* msg) 00196 { 00197 generic_32bit r; 00198 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[0]; 00199 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[1]; 00200 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[2]; 00201 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float))[3]; 00202 return (float)r.f; 00203 } 00204 00205 /** 00206 * @brief Get field epv from gps_raw message 00207 * 00208 * @return GPS VDOP 00209 */ 00210 static inline float mavlink_msg_gps_raw_ugv_get_epv(const mavlink_message_t* msg) 00211 { 00212 generic_32bit r; 00213 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[0]; 00214 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[1]; 00215 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[2]; 00216 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float))[3]; 00217 return (float)r.f; 00218 } 00219 00220 /** 00221 * @brief Get field v from gps_raw message 00222 * 00223 * @return GPS ground speed 00224 */ 00225 static inline float mavlink_msg_gps_raw_ugv_get_v(const mavlink_message_t* msg) 00226 { 00227 generic_32bit r; 00228 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00229 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00230 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00231 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00232 return (float)r.f; 00233 } 00234 00235 /** 00236 * @brief Get field hdg from gps_raw message 00237 * 00238 * @return Compass heading in degrees, 0..360 degrees 00239 */ 00240 static inline float mavlink_msg_gps_raw_ugv_get_hdg(const mavlink_message_t* msg) 00241 { 00242 generic_32bit r; 00243 r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0]; 00244 r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1]; 00245 r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2]; 00246 r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(double)+sizeof(double)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3]; 00247 return (float)r.f; 00248 } 00249 00250 /** 00251 * @brief Decode a gps_raw message into a struct 00252 * 00253 * @param msg The message to decode 00254 * @param gps_raw C-struct to decode the message contents into 00255 */ 00256 static inline void mavlink_msg_gps_raw_ugv_decode(const mavlink_message_t* msg, mavlink_gps_raw_ugv_t* gps_raw) 00257 { 00258 gps_raw->usec = mavlink_msg_gps_raw_ugv_get_usec(msg); 00259 gps_raw->fix_type = mavlink_msg_gps_raw_ugv_get_fix_type(msg); 00260 gps_raw->lat = mavlink_msg_gps_raw_ugv_get_lat(msg); 00261 gps_raw->lon = mavlink_msg_gps_raw_ugv_get_lon(msg); 00262 gps_raw->eph = mavlink_msg_gps_raw_ugv_get_eph(msg); 00263 gps_raw->epv = mavlink_msg_gps_raw_ugv_get_epv(msg); 00264 gps_raw->v = mavlink_msg_gps_raw_ugv_get_v(msg); 00265 gps_raw->hdg = mavlink_msg_gps_raw_ugv_get_hdg(msg); 00266 }
Generated on Tue Jul 12 2022 14:09:26 by 1.7.2