mavlink_msg_hil_gps.h
Go to the documentation of this file.
00001 // MESSAGE HIL_GPS PACKING
00002 
00003 #define MAVLINK_MSG_ID_HIL_GPS 113
00004 
00005 typedef struct __mavlink_hil_gps_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  uint16_t eph; /*< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535*/
00012  uint16_t epv; /*< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535*/
00013  uint16_t vel; /*< GPS ground speed (m/s * 100). If unknown, set to: 65535*/
00014  int16_t vn; /*< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame*/
00015  int16_t ve; /*< GPS velocity in cm/s in EAST direction in earth-fixed NED frame*/
00016  int16_t vd; /*< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame*/
00017  uint16_t cog; /*< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535*/
00018  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.*/
00019  uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
00020 } mavlink_hil_gps_t;
00021 
00022 #define MAVLINK_MSG_ID_HIL_GPS_LEN 36
00023 #define MAVLINK_MSG_ID_113_LEN 36
00024 
00025 #define MAVLINK_MSG_ID_HIL_GPS_CRC 124
00026 #define MAVLINK_MSG_ID_113_CRC 124
00027 
00028 
00029 
00030 #define MAVLINK_MESSAGE_INFO_HIL_GPS { \
00031         "HIL_GPS", \
00032         13, \
00033         {  { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
00034          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
00035          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
00036          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
00037          { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \
00038          { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \
00039          { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \
00040          { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \
00041          { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
00042          { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
00043          { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
00044          { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
00045          { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
00046          } \
00047 }
00048 
00049 
00071 static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00072                                                        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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
00073 {
00074 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00075         char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
00076         _mav_put_uint64_t(buf, 0, time_usec);
00077         _mav_put_int32_t(buf, 8, lat);
00078         _mav_put_int32_t(buf, 12, lon);
00079         _mav_put_int32_t(buf, 16, alt);
00080         _mav_put_uint16_t(buf, 20, eph);
00081         _mav_put_uint16_t(buf, 22, epv);
00082         _mav_put_uint16_t(buf, 24, vel);
00083         _mav_put_int16_t(buf, 26, vn);
00084         _mav_put_int16_t(buf, 28, ve);
00085         _mav_put_int16_t(buf, 30, vd);
00086         _mav_put_uint16_t(buf, 32, cog);
00087         _mav_put_uint8_t(buf, 34, fix_type);
00088         _mav_put_uint8_t(buf, 35, satellites_visible);
00089 
00090         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
00091 #else
00092         mavlink_hil_gps_t packet;
00093         packet.time_usec = time_usec;
00094         packet.lat = lat;
00095         packet.lon = lon;
00096         packet.alt = alt;
00097         packet.eph = eph;
00098         packet.epv = epv;
00099         packet.vel = vel;
00100         packet.vn = vn;
00101         packet.ve = ve;
00102         packet.vd = vd;
00103         packet.cog = cog;
00104         packet.fix_type = fix_type;
00105         packet.satellites_visible = satellites_visible;
00106 
00107         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
00108 #endif
00109 
00110         msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
00111 #if MAVLINK_CRC_EXTRA
00112     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00113 #else
00114     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN);
00115 #endif
00116 }
00117 
00139 static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00140                                                            mavlink_message_t* msg,
00141                                                            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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible)
00142 {
00143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00144         char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
00145         _mav_put_uint64_t(buf, 0, time_usec);
00146         _mav_put_int32_t(buf, 8, lat);
00147         _mav_put_int32_t(buf, 12, lon);
00148         _mav_put_int32_t(buf, 16, alt);
00149         _mav_put_uint16_t(buf, 20, eph);
00150         _mav_put_uint16_t(buf, 22, epv);
00151         _mav_put_uint16_t(buf, 24, vel);
00152         _mav_put_int16_t(buf, 26, vn);
00153         _mav_put_int16_t(buf, 28, ve);
00154         _mav_put_int16_t(buf, 30, vd);
00155         _mav_put_uint16_t(buf, 32, cog);
00156         _mav_put_uint8_t(buf, 34, fix_type);
00157         _mav_put_uint8_t(buf, 35, satellites_visible);
00158 
00159         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
00160 #else
00161         mavlink_hil_gps_t packet;
00162         packet.time_usec = time_usec;
00163         packet.lat = lat;
00164         packet.lon = lon;
00165         packet.alt = alt;
00166         packet.eph = eph;
00167         packet.epv = epv;
00168         packet.vel = vel;
00169         packet.vn = vn;
00170         packet.ve = ve;
00171         packet.vd = vd;
00172         packet.cog = cog;
00173         packet.fix_type = fix_type;
00174         packet.satellites_visible = satellites_visible;
00175 
00176         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
00177 #endif
00178 
00179         msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
00180 #if MAVLINK_CRC_EXTRA
00181     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00182 #else
00183     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN);
00184 #endif
00185 }
00186 
00195 static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
00196 {
00197         return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
00198 }
00199 
00209 static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
00210 {
00211         return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
00212 }
00213 
00232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00233 
00234 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
00235 {
00236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00237         char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
00238         _mav_put_uint64_t(buf, 0, time_usec);
00239         _mav_put_int32_t(buf, 8, lat);
00240         _mav_put_int32_t(buf, 12, lon);
00241         _mav_put_int32_t(buf, 16, alt);
00242         _mav_put_uint16_t(buf, 20, eph);
00243         _mav_put_uint16_t(buf, 22, epv);
00244         _mav_put_uint16_t(buf, 24, vel);
00245         _mav_put_int16_t(buf, 26, vn);
00246         _mav_put_int16_t(buf, 28, ve);
00247         _mav_put_int16_t(buf, 30, vd);
00248         _mav_put_uint16_t(buf, 32, cog);
00249         _mav_put_uint8_t(buf, 34, fix_type);
00250         _mav_put_uint8_t(buf, 35, satellites_visible);
00251 
00252 #if MAVLINK_CRC_EXTRA
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00254 #else
00255     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
00256 #endif
00257 #else
00258         mavlink_hil_gps_t packet;
00259         packet.time_usec = time_usec;
00260         packet.lat = lat;
00261         packet.lon = lon;
00262         packet.alt = alt;
00263         packet.eph = eph;
00264         packet.epv = epv;
00265         packet.vel = vel;
00266         packet.vn = vn;
00267         packet.ve = ve;
00268         packet.vd = vd;
00269         packet.cog = cog;
00270         packet.fix_type = fix_type;
00271         packet.satellites_visible = satellites_visible;
00272 
00273 #if MAVLINK_CRC_EXTRA
00274     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00275 #else
00276     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
00277 #endif
00278 #endif
00279 }
00280 
00281 #if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00282 /*
00283   This varient of _send() can be used to save stack space by re-using
00284   memory from the receive buffer.  The caller provides a
00285   mavlink_message_t which is the size of a full mavlink message. This
00286   is usually the receive buffer for the channel, and allows a reply to an
00287   incoming message with minimum stack space usage.
00288  */
00289 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
00290 {
00291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00292         char *buf = (char *)msgbuf;
00293         _mav_put_uint64_t(buf, 0, time_usec);
00294         _mav_put_int32_t(buf, 8, lat);
00295         _mav_put_int32_t(buf, 12, lon);
00296         _mav_put_int32_t(buf, 16, alt);
00297         _mav_put_uint16_t(buf, 20, eph);
00298         _mav_put_uint16_t(buf, 22, epv);
00299         _mav_put_uint16_t(buf, 24, vel);
00300         _mav_put_int16_t(buf, 26, vn);
00301         _mav_put_int16_t(buf, 28, ve);
00302         _mav_put_int16_t(buf, 30, vd);
00303         _mav_put_uint16_t(buf, 32, cog);
00304         _mav_put_uint8_t(buf, 34, fix_type);
00305         _mav_put_uint8_t(buf, 35, satellites_visible);
00306 
00307 #if MAVLINK_CRC_EXTRA
00308     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00309 #else
00310     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
00311 #endif
00312 #else
00313         mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
00314         packet->time_usec = time_usec;
00315         packet->lat = lat;
00316         packet->lon = lon;
00317         packet->alt = alt;
00318         packet->eph = eph;
00319         packet->epv = epv;
00320         packet->vel = vel;
00321         packet->vn = vn;
00322         packet->ve = ve;
00323         packet->vd = vd;
00324         packet->cog = cog;
00325         packet->fix_type = fix_type;
00326         packet->satellites_visible = satellites_visible;
00327 
00328 #if MAVLINK_CRC_EXTRA
00329     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
00330 #else
00331     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
00332 #endif
00333 #endif
00334 }
00335 #endif
00336 
00337 #endif
00338 
00339 // MESSAGE HIL_GPS UNPACKING
00340 
00341 
00347 static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
00348 {
00349         return _MAV_RETURN_uint64_t(msg,  0);
00350 }
00351 
00357 static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg)
00358 {
00359         return _MAV_RETURN_uint8_t(msg,  34);
00360 }
00361 
00367 static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
00368 {
00369         return _MAV_RETURN_int32_t(msg,  8);
00370 }
00371 
00377 static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
00378 {
00379         return _MAV_RETURN_int32_t(msg,  12);
00380 }
00381 
00387 static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
00388 {
00389         return _MAV_RETURN_int32_t(msg,  16);
00390 }
00391 
00397 static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
00398 {
00399         return _MAV_RETURN_uint16_t(msg,  20);
00400 }
00401 
00407 static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
00408 {
00409         return _MAV_RETURN_uint16_t(msg,  22);
00410 }
00411 
00417 static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
00418 {
00419         return _MAV_RETURN_uint16_t(msg,  24);
00420 }
00421 
00427 static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
00428 {
00429         return _MAV_RETURN_int16_t(msg,  26);
00430 }
00431 
00437 static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
00438 {
00439         return _MAV_RETURN_int16_t(msg,  28);
00440 }
00441 
00447 static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
00448 {
00449         return _MAV_RETURN_int16_t(msg,  30);
00450 }
00451 
00457 static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg)
00458 {
00459         return _MAV_RETURN_uint16_t(msg,  32);
00460 }
00461 
00467 static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg)
00468 {
00469         return _MAV_RETURN_uint8_t(msg,  35);
00470 }
00471 
00478 static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps)
00479 {
00480 #if MAVLINK_NEED_BYTE_SWAP
00481         hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg);
00482         hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg);
00483         hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg);
00484         hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg);
00485         hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg);
00486         hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg);
00487         hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg);
00488         hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg);
00489         hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg);
00490         hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg);
00491         hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg);
00492         hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg);
00493         hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg);
00494 #else
00495         memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN);
00496 #endif
00497 }


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