3 #define MAVLINK_MSG_ID_GPS_RAW_INT 24 19 #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 20 #define MAVLINK_MSG_ID_24_LEN 30 22 #define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 23 #define MAVLINK_MSG_ID_24_CRC 24 27 #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ 30 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ 31 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ 32 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ 33 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ 34 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ 35 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ 36 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ 37 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ 38 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ 39 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ 65 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 122 mavlink_message_t* msg,
125 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 156 #if MAVLINK_CRC_EXTRA 173 return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->
time_usec, gps_raw_int->
fix_type, gps_raw_int->
lat, gps_raw_int->
lon, gps_raw_int->
alt, gps_raw_int->
eph, gps_raw_int->
epv, gps_raw_int->
vel, gps_raw_int->
cog, gps_raw_int->
satellites_visible);
187 return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->
time_usec, gps_raw_int->
fix_type, gps_raw_int->
lat, gps_raw_int->
lon, gps_raw_int->
alt, gps_raw_int->
eph, gps_raw_int->
epv, gps_raw_int->
vel, gps_raw_int->
cog, gps_raw_int->
satellites_visible);
205 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 207 static inline void mavlink_msg_gps_raw_int_send(
mavlink_channel_t chan, uint64_t
time_usec, uint8_t
fix_type, int32_t
lat, int32_t
lon, int32_t
alt, uint16_t
eph, uint16_t
epv, uint16_t
vel, uint16_t
cog, uint8_t
satellites_visible)
209 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 222 #if MAVLINK_CRC_EXTRA 240 #if MAVLINK_CRC_EXTRA 248 #if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN 256 static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
time_usec, uint8_t
fix_type, int32_t
lat, int32_t
lon, int32_t
alt, uint16_t
eph, uint16_t
epv, uint16_t
vel, uint16_t
cog, uint8_t
satellites_visible)
258 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 259 char *buf = (
char *)msgbuf;
271 #if MAVLINK_CRC_EXTRA 289 #if MAVLINK_CRC_EXTRA 310 return _MAV_RETURN_uint64_t(msg, 0);
330 return _MAV_RETURN_int32_t(msg, 8);
340 return _MAV_RETURN_int32_t(msg, 12);
350 return _MAV_RETURN_int32_t(msg, 16);
360 return _MAV_RETURN_uint16_t(msg, 20);
370 return _MAV_RETURN_uint16_t(msg, 22);
380 return _MAV_RETURN_uint16_t(msg, 24);
390 return _MAV_RETURN_uint16_t(msg, 26);
411 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
Pack a gps_raw_int message on a channel.
#define MAVLINK_MSG_ID_GPS_RAW_INT
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t *msg)
Get field fix_type from gps_raw_int message.
uint8_t satellites_visible
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.
#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t *msg)
Get field eph from gps_raw_int message.
struct __mavlink_gps_raw_int_t mavlink_gps_raw_int_t
static uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t *msg)
Get field epv from gps_raw_int message.
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
Pack a gps_raw_int message.
static uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t *msg)
Get field satellites_visible from gps_raw_int message.
static int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t *msg)
Get field alt from gps_raw_int message.
static uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_raw_int_t *gps_raw_int)
Encode a gps_raw_int struct.
static uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_raw_int_t *gps_raw_int)
Encode a gps_raw_int struct on a channel.
static int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t *msg)
Get field lat from gps_raw_int message.
static uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t *msg)
Get field cog from gps_raw_int message.
static void mavlink_msg_gps_raw_int_decode(const mavlink_message_t *msg, mavlink_gps_raw_int_t *gps_raw_int)
Decode a gps_raw_int message into a struct.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t *msg)
Send a gps_raw_int message.
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.
static uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t *msg)
Get field vel from gps_raw_int message.
static int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t *msg)
Get field lon from gps_raw_int message.