2 // MESSAGE GLOBAL_POSITION_INT PACKING
4 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
7 typedef struct __mavlink_global_position_int_t
{
8 uint32_t time_boot_ms
; /*< Timestamp (milliseconds since system boot)*/
9 int32_t lat
; /*< Latitude, expressed as degrees * 1E7*/
10 int32_t lon
; /*< Longitude, expressed as degrees * 1E7*/
11 int32_t alt
; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/
12 int32_t relative_alt
; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
13 int16_t vx
; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/
14 int16_t vy
; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/
15 int16_t vz
; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/
16 uint16_t hdg
; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
17 }) mavlink_global_position_int_t
;
19 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
20 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28
21 #define MAVLINK_MSG_ID_33_LEN 28
22 #define MAVLINK_MSG_ID_33_MIN_LEN 28
24 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
25 #define MAVLINK_MSG_ID_33_CRC 104
29 #if MAVLINK_COMMAND_24BIT
30 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
32 "GLOBAL_POSITION_INT", \
34 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
35 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
36 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
37 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
38 { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
39 { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
40 { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
41 { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
42 { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
46 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
47 "GLOBAL_POSITION_INT", \
49 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
50 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
51 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
52 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
53 { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
54 { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
55 { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
56 { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
57 { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
63 * @brief Pack a global_position_int message
64 * @param system_id ID of this system
65 * @param component_id ID of this component (e.g. 200 for IMU)
66 * @param msg The MAVLink message to compress the data into
68 * @param time_boot_ms Timestamp (milliseconds since system boot)
69 * @param lat Latitude, expressed as degrees * 1E7
70 * @param lon Longitude, expressed as degrees * 1E7
71 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
72 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
73 * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
74 * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
75 * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
76 * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
77 * @return length of the message in bytes (excluding serial stream start sign)
79 static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
80 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
)
82 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
84 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
85 _mav_put_int32_t(buf
, 4, lat
);
86 _mav_put_int32_t(buf
, 8, lon
);
87 _mav_put_int32_t(buf
, 12, alt
);
88 _mav_put_int32_t(buf
, 16, relative_alt
);
89 _mav_put_int16_t(buf
, 20, vx
);
90 _mav_put_int16_t(buf
, 22, vy
);
91 _mav_put_int16_t(buf
, 24, vz
);
92 _mav_put_uint16_t(buf
, 26, hdg
);
94 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
96 mavlink_global_position_int_t packet
;
97 packet
.time_boot_ms
= time_boot_ms
;
101 packet
.relative_alt
= relative_alt
;
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
110 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_INT
;
111 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
115 * @brief Pack a global_position_int message on a channel
116 * @param system_id ID of this system
117 * @param component_id ID of this component (e.g. 200 for IMU)
118 * @param chan The MAVLink channel this message will be sent over
119 * @param msg The MAVLink message to compress the data into
120 * @param time_boot_ms Timestamp (milliseconds since system boot)
121 * @param lat Latitude, expressed as degrees * 1E7
122 * @param lon Longitude, expressed as degrees * 1E7
123 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
124 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
125 * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
126 * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
127 * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
128 * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
129 * @return length of the message in bytes (excluding serial stream start sign)
131 static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
132 mavlink_message_t
* msg
,
133 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
)
135 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
136 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
137 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
138 _mav_put_int32_t(buf
, 4, lat
);
139 _mav_put_int32_t(buf
, 8, lon
);
140 _mav_put_int32_t(buf
, 12, alt
);
141 _mav_put_int32_t(buf
, 16, relative_alt
);
142 _mav_put_int16_t(buf
, 20, vx
);
143 _mav_put_int16_t(buf
, 22, vy
);
144 _mav_put_int16_t(buf
, 24, vz
);
145 _mav_put_uint16_t(buf
, 26, hdg
);
147 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
149 mavlink_global_position_int_t packet
;
150 packet
.time_boot_ms
= time_boot_ms
;
154 packet
.relative_alt
= relative_alt
;
160 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
163 msg
->msgid
= MAVLINK_MSG_ID_GLOBAL_POSITION_INT
;
164 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
168 * @brief Encode a global_position_int struct
170 * @param system_id ID of this system
171 * @param component_id ID of this component (e.g. 200 for IMU)
172 * @param msg The MAVLink message to compress the data into
173 * @param global_position_int C-struct to read the message contents from
175 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
)
177 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
);
181 * @brief Encode a global_position_int struct on a channel
183 * @param system_id ID of this system
184 * @param component_id ID of this component (e.g. 200 for IMU)
185 * @param chan The MAVLink channel this message will be sent over
186 * @param msg The MAVLink message to compress the data into
187 * @param global_position_int C-struct to read the message contents from
189 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
)
191 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
);
195 * @brief Send a global_position_int message
196 * @param chan MAVLink channel to send the message
198 * @param time_boot_ms Timestamp (milliseconds since system boot)
199 * @param lat Latitude, expressed as degrees * 1E7
200 * @param lon Longitude, expressed as degrees * 1E7
201 * @param alt Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
202 * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
203 * @param vx Ground X Speed (Latitude, positive north), expressed as m/s * 100
204 * @param vy Ground Y Speed (Longitude, positive east), expressed as m/s * 100
205 * @param vz Ground Z Speed (Altitude, positive down), expressed as m/s * 100
206 * @param hdg Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
208 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
210 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
)
212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 char buf
[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
];
214 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
215 _mav_put_int32_t(buf
, 4, lat
);
216 _mav_put_int32_t(buf
, 8, lon
);
217 _mav_put_int32_t(buf
, 12, alt
);
218 _mav_put_int32_t(buf
, 16, relative_alt
);
219 _mav_put_int16_t(buf
, 20, vx
);
220 _mav_put_int16_t(buf
, 22, vy
);
221 _mav_put_int16_t(buf
, 24, vz
);
222 _mav_put_uint16_t(buf
, 26, hdg
);
224 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
226 mavlink_global_position_int_t packet
;
227 packet
.time_boot_ms
= time_boot_ms
;
231 packet
.relative_alt
= relative_alt
;
237 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, (const char *)&packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
242 * @brief Send a global_position_int message
243 * @param chan MAVLink channel to send the message
244 * @param struct The MAVLink struct to serialize
246 static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan
, const mavlink_global_position_int_t
* global_position_int
)
248 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
249 mavlink_msg_global_position_int_send(chan
, 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
);
251 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, (const char *)global_position_int
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
255 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
257 This varient of _send() can be used to save stack space by re-using
258 memory from the receive buffer. The caller provides a
259 mavlink_message_t which is the size of a full mavlink message. This
260 is usually the receive buffer for the channel, and allows a reply to an
261 incoming message with minimum stack space usage.
263 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
)
265 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
266 char *buf
= (char *)msgbuf
;
267 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
268 _mav_put_int32_t(buf
, 4, lat
);
269 _mav_put_int32_t(buf
, 8, lon
);
270 _mav_put_int32_t(buf
, 12, alt
);
271 _mav_put_int32_t(buf
, 16, relative_alt
);
272 _mav_put_int16_t(buf
, 20, vx
);
273 _mav_put_int16_t(buf
, 22, vy
);
274 _mav_put_int16_t(buf
, 24, vz
);
275 _mav_put_uint16_t(buf
, 26, hdg
);
277 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, buf
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
279 mavlink_global_position_int_t
*packet
= (mavlink_global_position_int_t
*)msgbuf
;
280 packet
->time_boot_ms
= time_boot_ms
;
284 packet
->relative_alt
= relative_alt
;
290 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT
, (const char *)packet
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
);
297 // MESSAGE GLOBAL_POSITION_INT UNPACKING
301 * @brief Get field time_boot_ms from global_position_int message
303 * @return Timestamp (milliseconds since system boot)
305 static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t
* msg
)
307 return _MAV_RETURN_uint32_t(msg
, 0);
311 * @brief Get field lat from global_position_int message
313 * @return Latitude, expressed as degrees * 1E7
315 static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t
* msg
)
317 return _MAV_RETURN_int32_t(msg
, 4);
321 * @brief Get field lon from global_position_int message
323 * @return Longitude, expressed as degrees * 1E7
325 static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t
* msg
)
327 return _MAV_RETURN_int32_t(msg
, 8);
331 * @brief Get field alt from global_position_int message
333 * @return Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
335 static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t
* msg
)
337 return _MAV_RETURN_int32_t(msg
, 12);
341 * @brief Get field relative_alt from global_position_int message
343 * @return Altitude above ground in meters, expressed as * 1000 (millimeters)
345 static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t
* msg
)
347 return _MAV_RETURN_int32_t(msg
, 16);
351 * @brief Get field vx from global_position_int message
353 * @return Ground X Speed (Latitude, positive north), expressed as m/s * 100
355 static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t
* msg
)
357 return _MAV_RETURN_int16_t(msg
, 20);
361 * @brief Get field vy from global_position_int message
363 * @return Ground Y Speed (Longitude, positive east), expressed as m/s * 100
365 static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t
* msg
)
367 return _MAV_RETURN_int16_t(msg
, 22);
371 * @brief Get field vz from global_position_int message
373 * @return Ground Z Speed (Altitude, positive down), expressed as m/s * 100
375 static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t
* msg
)
377 return _MAV_RETURN_int16_t(msg
, 24);
381 * @brief Get field hdg from global_position_int message
383 * @return Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
385 static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t
* msg
)
387 return _MAV_RETURN_uint16_t(msg
, 26);
391 * @brief Decode a global_position_int message into a struct
393 * @param msg The message to decode
394 * @param global_position_int C-struct to decode the message contents into
396 static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t
* msg
, mavlink_global_position_int_t
* global_position_int
)
398 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
399 global_position_int
->time_boot_ms
= mavlink_msg_global_position_int_get_time_boot_ms(msg
);
400 global_position_int
->lat
= mavlink_msg_global_position_int_get_lat(msg
);
401 global_position_int
->lon
= mavlink_msg_global_position_int_get_lon(msg
);
402 global_position_int
->alt
= mavlink_msg_global_position_int_get_alt(msg
);
403 global_position_int
->relative_alt
= mavlink_msg_global_position_int_get_relative_alt(msg
);
404 global_position_int
->vx
= mavlink_msg_global_position_int_get_vx(msg
);
405 global_position_int
->vy
= mavlink_msg_global_position_int_get_vy(msg
);
406 global_position_int
->vz
= mavlink_msg_global_position_int_get_vz(msg
);
407 global_position_int
->hdg
= mavlink_msg_global_position_int_get_hdg(msg
);
409 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
? msg
->len
: MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
;
410 memset(global_position_int
, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
);
411 memcpy(global_position_int
, _MAV_PAYLOAD(msg
), len
);