mavlink_msg_gps_global_origin.h
Go to the documentation of this file.
00001 // MESSAGE GPS_GLOBAL_ORIGIN PACKING
00002 
00003 #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
00004 
00005 typedef struct __mavlink_gps_global_origin_t
00006 {
00007  int32_t latitude; /*< Latitude (WGS84), in degrees * 1E7*/
00008  int32_t longitude; /*< Longitude (WGS84), in degrees * 1E7*/
00009  int32_t altitude; /*< Altitude (AMSL), in meters * 1000 (positive for up)*/
00010 } mavlink_gps_global_origin_t;
00011 
00012 #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
00013 #define MAVLINK_MSG_ID_49_LEN 12
00014 
00015 #define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39
00016 #define MAVLINK_MSG_ID_49_CRC 39
00017 
00018 
00019 
00020 #define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
00021         "GPS_GLOBAL_ORIGIN", \
00022         3, \
00023         {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \
00024          { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \
00025          { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \
00026          } \
00027 }
00028 
00029 
00041 static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00042                                                        int32_t latitude, int32_t longitude, int32_t altitude)
00043 {
00044 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00045         char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
00046         _mav_put_int32_t(buf, 0, latitude);
00047         _mav_put_int32_t(buf, 4, longitude);
00048         _mav_put_int32_t(buf, 8, altitude);
00049 
00050         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00051 #else
00052         mavlink_gps_global_origin_t packet;
00053         packet.latitude = latitude;
00054         packet.longitude = longitude;
00055         packet.altitude = altitude;
00056 
00057         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00058 #endif
00059 
00060         msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
00061 #if MAVLINK_CRC_EXTRA
00062     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00063 #else
00064     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00065 #endif
00066 }
00067 
00079 static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00080                                                            mavlink_message_t* msg,
00081                                                            int32_t latitude,int32_t longitude,int32_t altitude)
00082 {
00083 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00084         char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
00085         _mav_put_int32_t(buf, 0, latitude);
00086         _mav_put_int32_t(buf, 4, longitude);
00087         _mav_put_int32_t(buf, 8, altitude);
00088 
00089         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00090 #else
00091         mavlink_gps_global_origin_t packet;
00092         packet.latitude = latitude;
00093         packet.longitude = longitude;
00094         packet.altitude = altitude;
00095 
00096         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00097 #endif
00098 
00099         msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
00100 #if MAVLINK_CRC_EXTRA
00101     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00102 #else
00103     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00104 #endif
00105 }
00106 
00115 static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
00116 {
00117         return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
00118 }
00119 
00129 static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
00130 {
00131         return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
00132 }
00133 
00142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00143 
00144 static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
00145 {
00146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00147         char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
00148         _mav_put_int32_t(buf, 0, latitude);
00149         _mav_put_int32_t(buf, 4, longitude);
00150         _mav_put_int32_t(buf, 8, altitude);
00151 
00152 #if MAVLINK_CRC_EXTRA
00153     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00154 #else
00155     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00156 #endif
00157 #else
00158         mavlink_gps_global_origin_t packet;
00159         packet.latitude = latitude;
00160         packet.longitude = longitude;
00161         packet.altitude = altitude;
00162 
00163 #if MAVLINK_CRC_EXTRA
00164     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00165 #else
00166     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00167 #endif
00168 #endif
00169 }
00170 
00171 #if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00172 /*
00173   This varient of _send() can be used to save stack space by re-using
00174   memory from the receive buffer.  The caller provides a
00175   mavlink_message_t which is the size of a full mavlink message. This
00176   is usually the receive buffer for the channel, and allows a reply to an
00177   incoming message with minimum stack space usage.
00178  */
00179 static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int32_t latitude, int32_t longitude, int32_t altitude)
00180 {
00181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00182         char *buf = (char *)msgbuf;
00183         _mav_put_int32_t(buf, 0, latitude);
00184         _mav_put_int32_t(buf, 4, longitude);
00185         _mav_put_int32_t(buf, 8, altitude);
00186 
00187 #if MAVLINK_CRC_EXTRA
00188     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00189 #else
00190     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00191 #endif
00192 #else
00193         mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf;
00194         packet->latitude = latitude;
00195         packet->longitude = longitude;
00196         packet->altitude = altitude;
00197 
00198 #if MAVLINK_CRC_EXTRA
00199     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
00200 #else
00201     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00202 #endif
00203 #endif
00204 }
00205 #endif
00206 
00207 #endif
00208 
00209 // MESSAGE GPS_GLOBAL_ORIGIN UNPACKING
00210 
00211 
00217 static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg)
00218 {
00219         return _MAV_RETURN_int32_t(msg,  0);
00220 }
00221 
00227 static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg)
00228 {
00229         return _MAV_RETURN_int32_t(msg,  4);
00230 }
00231 
00237 static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg)
00238 {
00239         return _MAV_RETURN_int32_t(msg,  8);
00240 }
00241 
00248 static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin)
00249 {
00250 #if MAVLINK_NEED_BYTE_SWAP
00251         gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg);
00252         gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg);
00253         gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg);
00254 #else
00255         memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
00256 #endif
00257 }


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