3 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
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) }, \
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
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
148 #if MAVLINK_CRC_EXTRA
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);
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);
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
212 #if MAVLINK_CRC_EXTRA
229 #if MAVLINK_CRC_EXTRA
237 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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;
259 #if MAVLINK_CRC_EXTRA
276 #if MAVLINK_CRC_EXTRA
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
int32_t relative_alt
Altitude above ground in meters, expressed as * 1000 (millimeters)
Definition: mavlink_msg_global_position_int.h:11
int16_t vy
Ground Y Speed (Longitude), expressed as m/s * 100.
Definition: mavlink_msg_global_position_int.h:13
int32_t lon
Longitude, expressed as * 1E7.
Definition: mavlink_msg_global_position_int.h:9
Definition: mavlink_msg_global_position_int.h:5
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
uint16_t hdg
Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX.
Definition: mavlink_msg_global_position_int.h:15
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
int32_t lat
Latitude, expressed as * 1E7.
Definition: mavlink_msg_global_position_int.h:8
uint32_t time_boot_ms
Timestamp (milliseconds since system boot)
Definition: mavlink_msg_global_position_int.h:7
mavlink_channel_t
Definition: mavlink_types.h:178
int16_t vz
Ground Z Speed (Altitude), expressed as m/s * 100.
Definition: mavlink_msg_global_position_int.h:14
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN
Definition: mavlink_msg_global_position_int.h:18
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC
Definition: mavlink_msg_global_position_int.h:21
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT
Definition: mavlink_msg_global_position_int.h:3
int32_t alt
Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS ...
Definition: mavlink_msg_global_position_int.h:10
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:140
int16_t vx
Ground X Speed (Latitude), expressed as m/s * 100.
Definition: mavlink_msg_global_position_int.h:12
struct __mavlink_global_position_int_t mavlink_global_position_int_t
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141