mavlink_msg_global_position_int.h
Go to the documentation of this file.
00001 // MESSAGE GLOBAL_POSITION_INT PACKING
00002 
00003 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
00004 
00005 typedef struct __mavlink_global_position_int_t
00006 {
00007  uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
00008  int32_t lat; /*< Latitude, expressed as * 1E7*/
00009  int32_t lon; /*< Longitude, expressed as * 1E7*/
00010  int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/
00011  int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
00012  int16_t vx; /*< Ground X Speed (Latitude), expressed as m/s * 100*/
00013  int16_t vy; /*< Ground Y Speed (Longitude), expressed as m/s * 100*/
00014  int16_t vz; /*< Ground Z Speed (Altitude), expressed as m/s * 100*/
00015  uint16_t hdg; /*< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
00016 } mavlink_global_position_int_t;
00017 
00018 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
00019 #define MAVLINK_MSG_ID_33_LEN 28
00020 
00021 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
00022 #define MAVLINK_MSG_ID_33_CRC 104
00023 
00024 
00025 
00026 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
00027         "GLOBAL_POSITION_INT", \
00028         9, \
00029         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
00030          { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
00031          { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
00032          { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
00033          { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
00034          { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
00035          { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
00036          { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
00037          { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
00038          } \
00039 }
00040 
00041 
00059 static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00060                                                        uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
00061 {
00062 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00063         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
00064         _mav_put_uint32_t(buf, 0, time_boot_ms);
00065         _mav_put_int32_t(buf, 4, lat);
00066         _mav_put_int32_t(buf, 8, lon);
00067         _mav_put_int32_t(buf, 12, alt);
00068         _mav_put_int32_t(buf, 16, relative_alt);
00069         _mav_put_int16_t(buf, 20, vx);
00070         _mav_put_int16_t(buf, 22, vy);
00071         _mav_put_int16_t(buf, 24, vz);
00072         _mav_put_uint16_t(buf, 26, hdg);
00073 
00074         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00075 #else
00076         mavlink_global_position_int_t packet;
00077         packet.time_boot_ms = time_boot_ms;
00078         packet.lat = lat;
00079         packet.lon = lon;
00080         packet.alt = alt;
00081         packet.relative_alt = relative_alt;
00082         packet.vx = vx;
00083         packet.vy = vy;
00084         packet.vz = vz;
00085         packet.hdg = hdg;
00086 
00087         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00088 #endif
00089 
00090         msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
00091 #if MAVLINK_CRC_EXTRA
00092     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00093 #else
00094     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00095 #endif
00096 }
00097 
00115 static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00116                                                            mavlink_message_t* msg,
00117                                                            uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
00118 {
00119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00120         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
00121         _mav_put_uint32_t(buf, 0, time_boot_ms);
00122         _mav_put_int32_t(buf, 4, lat);
00123         _mav_put_int32_t(buf, 8, lon);
00124         _mav_put_int32_t(buf, 12, alt);
00125         _mav_put_int32_t(buf, 16, relative_alt);
00126         _mav_put_int16_t(buf, 20, vx);
00127         _mav_put_int16_t(buf, 22, vy);
00128         _mav_put_int16_t(buf, 24, vz);
00129         _mav_put_uint16_t(buf, 26, hdg);
00130 
00131         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00132 #else
00133         mavlink_global_position_int_t packet;
00134         packet.time_boot_ms = time_boot_ms;
00135         packet.lat = lat;
00136         packet.lon = lon;
00137         packet.alt = alt;
00138         packet.relative_alt = relative_alt;
00139         packet.vx = vx;
00140         packet.vy = vy;
00141         packet.vz = vz;
00142         packet.hdg = hdg;
00143 
00144         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00145 #endif
00146 
00147         msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
00148 #if MAVLINK_CRC_EXTRA
00149     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00150 #else
00151     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00152 #endif
00153 }
00154 
00163 static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
00164 {
00165         return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
00166 }
00167 
00177 static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
00178 {
00179         return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
00180 }
00181 
00196 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00197 
00198 static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
00199 {
00200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00201         char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
00202         _mav_put_uint32_t(buf, 0, time_boot_ms);
00203         _mav_put_int32_t(buf, 4, lat);
00204         _mav_put_int32_t(buf, 8, lon);
00205         _mav_put_int32_t(buf, 12, alt);
00206         _mav_put_int32_t(buf, 16, relative_alt);
00207         _mav_put_int16_t(buf, 20, vx);
00208         _mav_put_int16_t(buf, 22, vy);
00209         _mav_put_int16_t(buf, 24, vz);
00210         _mav_put_uint16_t(buf, 26, hdg);
00211 
00212 #if MAVLINK_CRC_EXTRA
00213     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00214 #else
00215     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00216 #endif
00217 #else
00218         mavlink_global_position_int_t packet;
00219         packet.time_boot_ms = time_boot_ms;
00220         packet.lat = lat;
00221         packet.lon = lon;
00222         packet.alt = alt;
00223         packet.relative_alt = relative_alt;
00224         packet.vx = vx;
00225         packet.vy = vy;
00226         packet.vz = vz;
00227         packet.hdg = hdg;
00228 
00229 #if MAVLINK_CRC_EXTRA
00230     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00231 #else
00232     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00233 #endif
00234 #endif
00235 }
00236 
00237 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00238 /*
00239   This varient of _send() can be used to save stack space by re-using
00240   memory from the receive buffer.  The caller provides a
00241   mavlink_message_t which is the size of a full mavlink message. This
00242   is usually the receive buffer for the channel, and allows a reply to an
00243   incoming message with minimum stack space usage.
00244  */
00245 static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
00246 {
00247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00248         char *buf = (char *)msgbuf;
00249         _mav_put_uint32_t(buf, 0, time_boot_ms);
00250         _mav_put_int32_t(buf, 4, lat);
00251         _mav_put_int32_t(buf, 8, lon);
00252         _mav_put_int32_t(buf, 12, alt);
00253         _mav_put_int32_t(buf, 16, relative_alt);
00254         _mav_put_int16_t(buf, 20, vx);
00255         _mav_put_int16_t(buf, 22, vy);
00256         _mav_put_int16_t(buf, 24, vz);
00257         _mav_put_uint16_t(buf, 26, hdg);
00258 
00259 #if MAVLINK_CRC_EXTRA
00260     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00261 #else
00262     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00263 #endif
00264 #else
00265         mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf;
00266         packet->time_boot_ms = time_boot_ms;
00267         packet->lat = lat;
00268         packet->lon = lon;
00269         packet->alt = alt;
00270         packet->relative_alt = relative_alt;
00271         packet->vx = vx;
00272         packet->vy = vy;
00273         packet->vz = vz;
00274         packet->hdg = hdg;
00275 
00276 #if MAVLINK_CRC_EXTRA
00277     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
00278 #else
00279     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00280 #endif
00281 #endif
00282 }
00283 #endif
00284 
00285 #endif
00286 
00287 // MESSAGE GLOBAL_POSITION_INT UNPACKING
00288 
00289 
00295 static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
00296 {
00297         return _MAV_RETURN_uint32_t(msg,  0);
00298 }
00299 
00305 static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
00306 {
00307         return _MAV_RETURN_int32_t(msg,  4);
00308 }
00309 
00315 static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
00316 {
00317         return _MAV_RETURN_int32_t(msg,  8);
00318 }
00319 
00325 static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
00326 {
00327         return _MAV_RETURN_int32_t(msg,  12);
00328 }
00329 
00335 static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
00336 {
00337         return _MAV_RETURN_int32_t(msg,  16);
00338 }
00339 
00345 static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
00346 {
00347         return _MAV_RETURN_int16_t(msg,  20);
00348 }
00349 
00355 static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
00356 {
00357         return _MAV_RETURN_int16_t(msg,  22);
00358 }
00359 
00365 static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
00366 {
00367         return _MAV_RETURN_int16_t(msg,  24);
00368 }
00369 
00375 static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
00376 {
00377         return _MAV_RETURN_uint16_t(msg,  26);
00378 }
00379 
00386 static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
00387 {
00388 #if MAVLINK_NEED_BYTE_SWAP
00389         global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
00390         global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
00391         global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
00392         global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
00393         global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg);
00394         global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
00395         global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
00396         global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
00397         global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
00398 #else
00399         memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
00400 #endif
00401 }


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