Code for autonomous ground vehicle, Data Bus, 3rd place winner in 2012 Sparkfun AVC.

Dependencies:   Watchdog mbed Schedule SimpleFilter LSM303DLM PinDetect DebounceIn Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mavlink_msg_gps_raw.h Source File

mavlink_msg_gps_raw.h

00001 // MESSAGE GPS_RAW PACKING
00002 
00003 #define MAVLINK_MSG_ID_GPS_RAW 32
00004 
00005 typedef struct __mavlink_gps_raw_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     float lat; ///< Latitude in degrees
00010     float lon; ///< Longitude in degrees
00011     float alt; ///< Altitude in meters
00012     float eph; ///< GPS HDOP
00013     float epv; ///< GPS VDOP
00014     float v; ///< GPS ground speed
00015     float hdg; ///< Compass heading in degrees, 0..360 degrees
00016 
00017 } mavlink_gps_raw_t;
00018 
00019 
00020 
00021 /**
00022  * @brief Pack a gps_raw message
00023  * @param system_id ID of this system
00024  * @param component_id ID of this component (e.g. 200 for IMU)
00025  * @param msg The MAVLink message to compress the data into
00026  *
00027  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00028  * @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.
00029  * @param lat Latitude in degrees
00030  * @param lon Longitude in degrees
00031  * @param alt Altitude in meters
00032  * @param eph GPS HDOP
00033  * @param epv GPS VDOP
00034  * @param v GPS ground speed
00035  * @param hdg Compass heading in degrees, 0..360 degrees
00036  * @return length of the message in bytes (excluding serial stream start sign)
00037  */
00038 static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
00039 {
00040     uint16_t i = 0;
00041     msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
00042 
00043     i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00044     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.
00045     i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
00046     i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
00047     i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
00048     i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
00049     i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
00050     i += put_float_by_index(v, i, msg->payload); // GPS ground speed
00051     i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
00052 
00053     return mavlink_finalize_message(msg, system_id, component_id, i);
00054 }
00055 
00056 /**
00057  * @brief Pack a gps_raw message
00058  * @param system_id ID of this system
00059  * @param component_id ID of this component (e.g. 200 for IMU)
00060  * @param chan The MAVLink channel this message was sent over
00061  * @param msg The MAVLink message to compress the data into
00062  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00063  * @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.
00064  * @param lat Latitude in degrees
00065  * @param lon Longitude in degrees
00066  * @param alt Altitude in meters
00067  * @param eph GPS HDOP
00068  * @param epv GPS VDOP
00069  * @param v GPS ground speed
00070  * @param hdg Compass heading in degrees, 0..360 degrees
00071  * @return length of the message in bytes (excluding serial stream start sign)
00072  */
00073 static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
00074 {
00075     uint16_t i = 0;
00076     msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
00077 
00078     i += put_uint64_t_by_index(usec, i, msg->payload); // Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00079     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.
00080     i += put_float_by_index(lat, i, msg->payload); // Latitude in degrees
00081     i += put_float_by_index(lon, i, msg->payload); // Longitude in degrees
00082     i += put_float_by_index(alt, i, msg->payload); // Altitude in meters
00083     i += put_float_by_index(eph, i, msg->payload); // GPS HDOP
00084     i += put_float_by_index(epv, i, msg->payload); // GPS VDOP
00085     i += put_float_by_index(v, i, msg->payload); // GPS ground speed
00086     i += put_float_by_index(hdg, i, msg->payload); // Compass heading in degrees, 0..360 degrees
00087 
00088     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, i);
00089 }
00090 
00091 /**
00092  * @brief Encode a gps_raw struct into a message
00093  *
00094  * @param system_id ID of this system
00095  * @param component_id ID of this component (e.g. 200 for IMU)
00096  * @param msg The MAVLink message to compress the data into
00097  * @param gps_raw C-struct to read the message contents from
00098  */
00099 static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
00100 {
00101     return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
00102 }
00103 
00104 /**
00105  * @brief Send a gps_raw message
00106  * @param chan MAVLink channel to send the message
00107  *
00108  * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00109  * @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.
00110  * @param lat Latitude in degrees
00111  * @param lon Longitude in degrees
00112  * @param alt Altitude in meters
00113  * @param eph GPS HDOP
00114  * @param epv GPS VDOP
00115  * @param v GPS ground speed
00116  * @param hdg Compass heading in degrees, 0..360 degrees
00117  */
00118 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00119 
00120 static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
00121 {
00122     mavlink_message_t msg;
00123     mavlink_msg_gps_raw_pack_chan(mavlink_system.sysid, mavlink_system.compid, chan, &msg, usec, fix_type, lat, lon, alt, eph, epv, v, hdg);
00124     mavlink_send_uart(chan, &msg);
00125 }
00126 
00127 #endif
00128 // MESSAGE GPS_RAW UNPACKING
00129 
00130 /**
00131  * @brief Get field usec from gps_raw message
00132  *
00133  * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
00134  */
00135 static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
00136 {
00137     generic_64bit r;
00138     r.b[7] = (msg->payload)[0];
00139     r.b[6] = (msg->payload)[1];
00140     r.b[5] = (msg->payload)[2];
00141     r.b[4] = (msg->payload)[3];
00142     r.b[3] = (msg->payload)[4];
00143     r.b[2] = (msg->payload)[5];
00144     r.b[1] = (msg->payload)[6];
00145     r.b[0] = (msg->payload)[7];
00146     return (uint64_t)r.ll;
00147 }
00148 
00149 /**
00150  * @brief Get field fix_type from gps_raw message
00151  *
00152  * @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.
00153  */
00154 static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg)
00155 {
00156     return (uint8_t)(msg->payload+sizeof(uint64_t))[0];
00157 }
00158 
00159 /**
00160  * @brief Get field lat from gps_raw message
00161  *
00162  * @return Latitude in degrees
00163  */
00164 static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
00165 {
00166     generic_32bit r;
00167     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[0];
00168     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[1];
00169     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[2];
00170     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t))[3];
00171     return (float)r.f;
00172 }
00173 
00174 /**
00175  * @brief Get field lon from gps_raw message
00176  *
00177  * @return Longitude in degrees
00178  */
00179 static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
00180 {
00181     generic_32bit r;
00182     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[0];
00183     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[1];
00184     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[2];
00185     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float))[3];
00186     return (float)r.f;
00187 }
00188 
00189 /**
00190  * @brief Get field alt from gps_raw message
00191  *
00192  * @return Altitude in meters
00193  */
00194 static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
00195 {
00196     generic_32bit r;
00197     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[0];
00198     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[1];
00199     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[2];
00200     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float))[3];
00201     return (float)r.f;
00202 }
00203 
00204 /**
00205  * @brief Get field eph from gps_raw message
00206  *
00207  * @return GPS HDOP
00208  */
00209 static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
00210 {
00211     generic_32bit r;
00212     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00213     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00214     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00215     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00216     return (float)r.f;
00217 }
00218 
00219 /**
00220  * @brief Get field epv from gps_raw message
00221  *
00222  * @return GPS VDOP
00223  */
00224 static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
00225 {
00226     generic_32bit r;
00227     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00228     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00229     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00230     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00231     return (float)r.f;
00232 }
00233 
00234 /**
00235  * @brief Get field v from gps_raw message
00236  *
00237  * @return GPS ground speed
00238  */
00239 static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
00240 {
00241     generic_32bit r;
00242     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00243     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00244     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00245     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00246     return (float)r.f;
00247 }
00248 
00249 /**
00250  * @brief Get field hdg from gps_raw message
00251  *
00252  * @return Compass heading in degrees, 0..360 degrees
00253  */
00254 static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
00255 {
00256     generic_32bit r;
00257     r.b[3] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[0];
00258     r.b[2] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[1];
00259     r.b[1] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[2];
00260     r.b[0] = (msg->payload+sizeof(uint64_t)+sizeof(uint8_t)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float)+sizeof(float))[3];
00261     return (float)r.f;
00262 }
00263 
00264 /**
00265  * @brief Decode a gps_raw message into a struct
00266  *
00267  * @param msg The message to decode
00268  * @param gps_raw C-struct to decode the message contents into
00269  */
00270 static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
00271 {
00272     gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);
00273     gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg);
00274     gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg);
00275     gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg);
00276     gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg);
00277     gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg);
00278     gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg);
00279     gps_raw->v = mavlink_msg_gps_raw_get_v(msg);
00280     gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg);
00281 }