1 // MESSAGE GLOBAL_POSITION_INT PACKING
3 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
5 typedef struct __mavlink_global_position_int_t
7 uint32_t time_boot_ms
; ///< Timestamp (milliseconds since system boot)
8 int32_t lat
; ///< Latitude, expressed as * 1E7
9 int32_t lon
; ///< Longitude, expressed as * 1E7
10 int32_t alt
; ///< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
11 int32_t relative_alt
; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
12 int16_t vx
; ///< Ground X Speed (Latitude), expressed as m/s * 100
13 int16_t vy
; ///< Ground Y Speed (Longitude), expressed as m/s * 100
14 int16_t vz
; ///< Ground Z Speed (Altitude), expressed as m/s * 100
15 uint16_t hdg
; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
16 } mavlink_global_position_int_t
;
18 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
19 #define MAVLINK_MSG_ID_33_LEN 28
21 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
22 #define MAVLINK_MSG_ID_33_CRC 104
26 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
27 "GLOBAL_POSITION_INT", \
29 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
30 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
31 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
32 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
33 { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
34 { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
35 { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
36 { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
37 { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
43 * @brief Pack a global_position_int message
44 * @param system_id ID of this system
45 * @param component_id ID of this component (e.g. 200 for IMU)
46 * @param msg The MAVLink message to compress the data into
48 * @param time_boot_ms Timestamp (milliseconds since system boot)
49 * @param lat Latitude, expressed as * 1E7
50 * @param lon Longitude, expressed as * 1E7
51 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
52 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
53 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
54 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
55 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
56 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
57 * @return length of the message in bytes (excluding serial stream start sign)
59 static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
60 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
)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
63 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
64 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
65 _mav_put_int32_t(buf
, 4, lat
);
66 _mav_put_int32_t(buf
, 8, lon
);
67 _mav_put_int32_t(buf
, 12, alt
);
68 _mav_put_int32_t(buf
, 16, relative_alt
);
69 _mav_put_int16_t(buf
, 20, vx
);
70 _mav_put_int16_t(buf
, 22, vy
);
71 _mav_put_int16_t(buf
, 24, vz
);
72 _mav_put_uint16_t(buf
, 26, hdg
);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
76 mavlink_global_position_int_t packet
;
77 packet
.time_boot_ms
= time_boot_ms
;
81 packet
.relative_alt
= relative_alt
;
87 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
90 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_INT
;
92 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
94 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
99 * @brief Pack a global_position_int message on a channel
100 * @param system_id ID of this system
101 * @param component_id ID of this component (e.g. 200 for IMU)
102 * @param chan The MAVLink channel this message will be sent over
103 * @param msg The MAVLink message to compress the data into
104 * @param time_boot_ms Timestamp (milliseconds since system boot)
105 * @param lat Latitude, expressed as * 1E7
106 * @param lon Longitude, expressed as * 1E7
107 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
108 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
109 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
110 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
111 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
112 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
113 * @return length of the message in bytes (excluding serial stream start sign)
115 static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
116 mavlink_message_t
* msg
,
117 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
)
119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
120 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
121 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
122 _mav_put_int32_t(buf
, 4, lat
);
123 _mav_put_int32_t(buf
, 8, lon
);
124 _mav_put_int32_t(buf
, 12, alt
);
125 _mav_put_int32_t(buf
, 16, relative_alt
);
126 _mav_put_int16_t(buf
, 20, vx
);
127 _mav_put_int16_t(buf
, 22, vy
);
128 _mav_put_int16_t(buf
, 24, vz
);
129 _mav_put_uint16_t(buf
, 26, hdg
);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
133 mavlink_global_position_int_t packet
;
134 packet
.time_boot_ms
= time_boot_ms
;
138 packet
.relative_alt
= relative_alt
;
144 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
147 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_INT
;
148 #if MAVLINK_CRC_EXTRA
149 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
);
151 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
156 * @brief Encode a global_position_int struct
158 * @param system_id ID of this system
159 * @param component_id ID of this component (e.g. 200 for IMU)
160 * @param msg The MAVLink message to compress the data into
161 * @param global_position_int C-struct to read the message contents from
163 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
)
165 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
);
169 * @brief Encode a global_position_int struct on a channel
171 * @param system_id ID of this system
172 * @param component_id ID of this component (e.g. 200 for IMU)
173 * @param chan The MAVLink channel this message will be sent over
174 * @param msg The MAVLink message to compress the data into
175 * @param global_position_int C-struct to read the message contents from
177 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
)
179 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
);
183 * @brief Send a global_position_int message
184 * @param chan MAVLink channel to send the message
186 * @param time_boot_ms Timestamp (milliseconds since system boot)
187 * @param lat Latitude, expressed as * 1E7
188 * @param lon Longitude, expressed as * 1E7
189 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
190 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
191 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
192 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
193 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
194 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
196 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
198 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
)
200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
202 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
203 _mav_put_int32_t(buf
, 4, lat
);
204 _mav_put_int32_t(buf
, 8, lon
);
205 _mav_put_int32_t(buf
, 12, alt
);
206 _mav_put_int32_t(buf
, 16, relative_alt
);
207 _mav_put_int16_t(buf
, 20, vx
);
208 _mav_put_int16_t(buf
, 22, vy
);
209 _mav_put_int16_t(buf
, 24, vz
);
210 _mav_put_uint16_t(buf
, 26, hdg
);
212 #if MAVLINK_CRC_EXTRA
213 _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
);
215 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
218 mavlink_global_position_int_t packet
;
219 packet
.time_boot_ms
= time_boot_ms
;
223 packet
.relative_alt
= relative_alt
;
229 #if MAVLINK_CRC_EXTRA
230 _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
);
232 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, (const char *)&packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
237 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
239 This varient of _send() can be used to save stack space by re-using
240 memory from the receive buffer. The caller provides a
241 mavlink_message_t which is the size of a full mavlink message. This
242 is usually the receive buffer for the channel, and allows a reply to an
243 incoming message with minimum stack space usage.
245 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
)
247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248 char *buf
= (char *)msgbuf
;
249 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
250 _mav_put_int32_t(buf
, 4, lat
);
251 _mav_put_int32_t(buf
, 8, lon
);
252 _mav_put_int32_t(buf
, 12, alt
);
253 _mav_put_int32_t(buf
, 16, relative_alt
);
254 _mav_put_int16_t(buf
, 20, vx
);
255 _mav_put_int16_t(buf
, 22, vy
);
256 _mav_put_int16_t(buf
, 24, vz
);
257 _mav_put_uint16_t(buf
, 26, hdg
);
259 #if MAVLINK_CRC_EXTRA
260 _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
);
262 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
265 mavlink_global_position_int_t
*packet
= (mavlink_global_position_int_t
*)msgbuf
;
266 packet
->time_boot_ms
= time_boot_ms
;
270 packet
->relative_alt
= relative_alt
;
276 #if MAVLINK_CRC_EXTRA
277 _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
);
279 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, (const char *)packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
287 // MESSAGE GLOBAL_POSITION_INT UNPACKING
291 * @brief Get field time_boot_ms from global_position_int message
293 * @return Timestamp (milliseconds since system boot)
295 static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t
* msg
)
297 return _MAV_RETURN_uint32_t(msg
, 0);
301 * @brief Get field lat from global_position_int message
303 * @return Latitude, expressed as * 1E7
305 static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t
* msg
)
307 return _MAV_RETURN_int32_t(msg
, 4);
311 * @brief Get field lon from global_position_int message
313 * @return Longitude, expressed as * 1E7
315 static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t
* msg
)
317 return _MAV_RETURN_int32_t(msg
, 8);
321 * @brief Get field alt from global_position_int message
323 * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
325 static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t
* msg
)
327 return _MAV_RETURN_int32_t(msg
, 12);
331 * @brief Get field relative_alt from global_position_int message
333 * @return Altitude above ground in meters, expressed as * 1000 (millimeters)
335 static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t
* msg
)
337 return _MAV_RETURN_int32_t(msg
, 16);
341 * @brief Get field vx from global_position_int message
343 * @return Ground X Speed (Latitude), expressed as m/s * 100
345 static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t
* msg
)
347 return _MAV_RETURN_int16_t(msg
, 20);
351 * @brief Get field vy from global_position_int message
353 * @return Ground Y Speed (Longitude), expressed as m/s * 100
355 static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t
* msg
)
357 return _MAV_RETURN_int16_t(msg
, 22);
361 * @brief Get field vz from global_position_int message
363 * @return Ground Z Speed (Altitude), expressed as m/s * 100
365 static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t
* msg
)
367 return _MAV_RETURN_int16_t(msg
, 24);
371 * @brief Get field hdg from global_position_int message
373 * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
375 static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t
* msg
)
377 return _MAV_RETURN_uint16_t(msg
, 26);
381 * @brief Decode a global_position_int message into a struct
383 * @param msg The message to decode
384 * @param global_position_int C-struct to decode the message contents into
386 static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t
* msg
, mavlink_global_position_int_t
* global_position_int
)
388 #if MAVLINK_NEED_BYTE_SWAP
389 global_position_int
->time_boot_ms
= mavlink_msg_global_position_int_get_time_boot_ms(msg
);
390 global_position_int
->lat
= mavlink_msg_global_position_int_get_lat(msg
);
391 global_position_int
->lon
= mavlink_msg_global_position_int_get_lon(msg
);
392 global_position_int
->alt
= mavlink_msg_global_position_int_get_alt(msg
);
393 global_position_int
->relative_alt
= mavlink_msg_global_position_int_get_relative_alt(msg
);
394 global_position_int
->vx
= mavlink_msg_global_position_int_get_vx(msg
);
395 global_position_int
->vy
= mavlink_msg_global_position_int_get_vy(msg
);
396 global_position_int
->vz
= mavlink_msg_global_position_int_get_vz(msg
);
397 global_position_int
->hdg
= mavlink_msg_global_position_int_get_hdg(msg
);
399 memcpy(global_position_int
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);