mavlink_msg_gps2_raw.h
Go to the documentation of this file.
00001 // MESSAGE GPS2_RAW PACKING
00002 
00003 #define MAVLINK_MSG_ID_GPS2_RAW 124
00004 
00005 typedef struct __mavlink_gps2_raw_t
00006 {
00007  uint64_t time_usec; /*< Timestamp (microseconds since UNIX epoch or microseconds since system boot)*/
00008  int32_t lat; /*< Latitude (WGS84), in degrees * 1E7*/
00009  int32_t lon; /*< Longitude (WGS84), in degrees * 1E7*/
00010  int32_t alt; /*< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)*/
00011  uint32_t dgps_age; /*< Age of DGPS info*/
00012  uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
00013  uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX*/
00014  uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX*/
00015  uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
00016  uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.*/
00017  uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
00018  uint8_t dgps_numch; /*< Number of DGPS satellites*/
00019 } mavlink_gps2_raw_t;
00020 
00021 #define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
00022 #define MAVLINK_MSG_ID_124_LEN 35
00023 
00024 #define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
00025 #define MAVLINK_MSG_ID_124_CRC 87
00026 
00027 
00028 
00029 #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
00030         "GPS2_RAW", \
00031         12, \
00032         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
00033          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
00034          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
00035          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
00036          { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
00037          { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
00038          { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
00039          { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
00040          { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
00041          { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
00042          { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
00043          { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
00044          } \
00045 }
00046 
00047 
00068 static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00069                                                        uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
00070 {
00071 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00072         char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
00073         _mav_put_uint64_t(buf, 0, time_usec);
00074         _mav_put_int32_t(buf, 8, lat);
00075         _mav_put_int32_t(buf, 12, lon);
00076         _mav_put_int32_t(buf, 16, alt);
00077         _mav_put_uint32_t(buf, 20, dgps_age);
00078         _mav_put_uint16_t(buf, 24, eph);
00079         _mav_put_uint16_t(buf, 26, epv);
00080         _mav_put_uint16_t(buf, 28, vel);
00081         _mav_put_uint16_t(buf, 30, cog);
00082         _mav_put_uint8_t(buf, 32, fix_type);
00083         _mav_put_uint8_t(buf, 33, satellites_visible);
00084         _mav_put_uint8_t(buf, 34, dgps_numch);
00085 
00086         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00087 #else
00088         mavlink_gps2_raw_t packet;
00089         packet.time_usec = time_usec;
00090         packet.lat = lat;
00091         packet.lon = lon;
00092         packet.alt = alt;
00093         packet.dgps_age = dgps_age;
00094         packet.eph = eph;
00095         packet.epv = epv;
00096         packet.vel = vel;
00097         packet.cog = cog;
00098         packet.fix_type = fix_type;
00099         packet.satellites_visible = satellites_visible;
00100         packet.dgps_numch = dgps_numch;
00101 
00102         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00103 #endif
00104 
00105         msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
00106 #if MAVLINK_CRC_EXTRA
00107     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00108 #else
00109     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00110 #endif
00111 }
00112 
00133 static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00134                                                            mavlink_message_t* msg,
00135                                                            uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age)
00136 {
00137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00138         char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
00139         _mav_put_uint64_t(buf, 0, time_usec);
00140         _mav_put_int32_t(buf, 8, lat);
00141         _mav_put_int32_t(buf, 12, lon);
00142         _mav_put_int32_t(buf, 16, alt);
00143         _mav_put_uint32_t(buf, 20, dgps_age);
00144         _mav_put_uint16_t(buf, 24, eph);
00145         _mav_put_uint16_t(buf, 26, epv);
00146         _mav_put_uint16_t(buf, 28, vel);
00147         _mav_put_uint16_t(buf, 30, cog);
00148         _mav_put_uint8_t(buf, 32, fix_type);
00149         _mav_put_uint8_t(buf, 33, satellites_visible);
00150         _mav_put_uint8_t(buf, 34, dgps_numch);
00151 
00152         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00153 #else
00154         mavlink_gps2_raw_t packet;
00155         packet.time_usec = time_usec;
00156         packet.lat = lat;
00157         packet.lon = lon;
00158         packet.alt = alt;
00159         packet.dgps_age = dgps_age;
00160         packet.eph = eph;
00161         packet.epv = epv;
00162         packet.vel = vel;
00163         packet.cog = cog;
00164         packet.fix_type = fix_type;
00165         packet.satellites_visible = satellites_visible;
00166         packet.dgps_numch = dgps_numch;
00167 
00168         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00169 #endif
00170 
00171         msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
00172 #if MAVLINK_CRC_EXTRA
00173     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00174 #else
00175     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00176 #endif
00177 }
00178 
00187 static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
00188 {
00189         return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
00190 }
00191 
00201 static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
00202 {
00203         return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
00204 }
00205 
00223 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00224 
00225 static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
00226 {
00227 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00228         char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
00229         _mav_put_uint64_t(buf, 0, time_usec);
00230         _mav_put_int32_t(buf, 8, lat);
00231         _mav_put_int32_t(buf, 12, lon);
00232         _mav_put_int32_t(buf, 16, alt);
00233         _mav_put_uint32_t(buf, 20, dgps_age);
00234         _mav_put_uint16_t(buf, 24, eph);
00235         _mav_put_uint16_t(buf, 26, epv);
00236         _mav_put_uint16_t(buf, 28, vel);
00237         _mav_put_uint16_t(buf, 30, cog);
00238         _mav_put_uint8_t(buf, 32, fix_type);
00239         _mav_put_uint8_t(buf, 33, satellites_visible);
00240         _mav_put_uint8_t(buf, 34, dgps_numch);
00241 
00242 #if MAVLINK_CRC_EXTRA
00243     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00244 #else
00245     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00246 #endif
00247 #else
00248         mavlink_gps2_raw_t packet;
00249         packet.time_usec = time_usec;
00250         packet.lat = lat;
00251         packet.lon = lon;
00252         packet.alt = alt;
00253         packet.dgps_age = dgps_age;
00254         packet.eph = eph;
00255         packet.epv = epv;
00256         packet.vel = vel;
00257         packet.cog = cog;
00258         packet.fix_type = fix_type;
00259         packet.satellites_visible = satellites_visible;
00260         packet.dgps_numch = dgps_numch;
00261 
00262 #if MAVLINK_CRC_EXTRA
00263     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00264 #else
00265     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00266 #endif
00267 #endif
00268 }
00269 
00270 #if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00271 /*
00272   This varient of _send() can be used to save stack space by re-using
00273   memory from the receive buffer.  The caller provides a
00274   mavlink_message_t which is the size of a full mavlink message. This
00275   is usually the receive buffer for the channel, and allows a reply to an
00276   incoming message with minimum stack space usage.
00277  */
00278 static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age)
00279 {
00280 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00281         char *buf = (char *)msgbuf;
00282         _mav_put_uint64_t(buf, 0, time_usec);
00283         _mav_put_int32_t(buf, 8, lat);
00284         _mav_put_int32_t(buf, 12, lon);
00285         _mav_put_int32_t(buf, 16, alt);
00286         _mav_put_uint32_t(buf, 20, dgps_age);
00287         _mav_put_uint16_t(buf, 24, eph);
00288         _mav_put_uint16_t(buf, 26, epv);
00289         _mav_put_uint16_t(buf, 28, vel);
00290         _mav_put_uint16_t(buf, 30, cog);
00291         _mav_put_uint8_t(buf, 32, fix_type);
00292         _mav_put_uint8_t(buf, 33, satellites_visible);
00293         _mav_put_uint8_t(buf, 34, dgps_numch);
00294 
00295 #if MAVLINK_CRC_EXTRA
00296     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00297 #else
00298     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00299 #endif
00300 #else
00301         mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
00302         packet->time_usec = time_usec;
00303         packet->lat = lat;
00304         packet->lon = lon;
00305         packet->alt = alt;
00306         packet->dgps_age = dgps_age;
00307         packet->eph = eph;
00308         packet->epv = epv;
00309         packet->vel = vel;
00310         packet->cog = cog;
00311         packet->fix_type = fix_type;
00312         packet->satellites_visible = satellites_visible;
00313         packet->dgps_numch = dgps_numch;
00314 
00315 #if MAVLINK_CRC_EXTRA
00316     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
00317 #else
00318     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
00319 #endif
00320 #endif
00321 }
00322 #endif
00323 
00324 #endif
00325 
00326 // MESSAGE GPS2_RAW UNPACKING
00327 
00328 
00334 static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
00335 {
00336         return _MAV_RETURN_uint64_t(msg,  0);
00337 }
00338 
00344 static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
00345 {
00346         return _MAV_RETURN_uint8_t(msg,  32);
00347 }
00348 
00354 static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
00355 {
00356         return _MAV_RETURN_int32_t(msg,  8);
00357 }
00358 
00364 static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
00365 {
00366         return _MAV_RETURN_int32_t(msg,  12);
00367 }
00368 
00374 static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
00375 {
00376         return _MAV_RETURN_int32_t(msg,  16);
00377 }
00378 
00384 static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
00385 {
00386         return _MAV_RETURN_uint16_t(msg,  24);
00387 }
00388 
00394 static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
00395 {
00396         return _MAV_RETURN_uint16_t(msg,  26);
00397 }
00398 
00404 static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
00405 {
00406         return _MAV_RETURN_uint16_t(msg,  28);
00407 }
00408 
00414 static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
00415 {
00416         return _MAV_RETURN_uint16_t(msg,  30);
00417 }
00418 
00424 static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
00425 {
00426         return _MAV_RETURN_uint8_t(msg,  33);
00427 }
00428 
00434 static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
00435 {
00436         return _MAV_RETURN_uint8_t(msg,  34);
00437 }
00438 
00444 static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
00445 {
00446         return _MAV_RETURN_uint32_t(msg,  20);
00447 }
00448 
00455 static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
00456 {
00457 #if MAVLINK_NEED_BYTE_SWAP
00458         gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
00459         gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg);
00460         gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg);
00461         gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg);
00462         gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
00463         gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg);
00464         gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg);
00465         gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg);
00466         gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg);
00467         gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
00468         gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg);
00469         gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
00470 #else
00471         memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
00472 #endif
00473 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35