3 #define MAVLINK_MSG_ID_HIL_GPS 113 22 #define MAVLINK_MSG_ID_HIL_GPS_LEN 36 23 #define MAVLINK_MSG_ID_113_LEN 36 25 #define MAVLINK_MSG_ID_HIL_GPS_CRC 124 26 #define MAVLINK_MSG_ID_113_CRC 124 30 #define MAVLINK_MESSAGE_INFO_HIL_GPS { \ 33 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ 34 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ 35 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ 36 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ 37 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ 38 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ 39 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ 40 { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ 41 { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ 42 { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ 43 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ 44 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ 45 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ 72 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, int16_t
vn, int16_t
ve, int16_t
vd, uint16_t
cog, uint8_t
satellites_visible)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 111 #if MAVLINK_CRC_EXTRA 140 mavlink_message_t* msg,
141 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,int16_t
vn,int16_t
ve,int16_t
vd,uint16_t
cog,uint8_t
satellites_visible)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 #if MAVLINK_CRC_EXTRA 197 return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->
time_usec, hil_gps->
fix_type, hil_gps->
lat, hil_gps->
lon, hil_gps->
alt, hil_gps->
eph, hil_gps->
epv, hil_gps->
vel, hil_gps->
vn, hil_gps->
ve, hil_gps->
vd, hil_gps->
cog, hil_gps->
satellites_visible);
211 return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->
time_usec, hil_gps->
fix_type, hil_gps->
lat, hil_gps->
lon, hil_gps->
alt, hil_gps->
eph, hil_gps->
epv, hil_gps->
vel, hil_gps->
vn, hil_gps->
ve, hil_gps->
vd, hil_gps->
cog, hil_gps->
satellites_visible);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 234 static inline void mavlink_msg_hil_gps_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, int16_t
vn, int16_t
ve, int16_t
vd, uint16_t
cog, uint8_t
satellites_visible)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 252 #if MAVLINK_CRC_EXTRA 273 #if MAVLINK_CRC_EXTRA 281 #if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN 289 static inline void mavlink_msg_hil_gps_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, int16_t
vn, int16_t
ve, int16_t
vd, uint16_t
cog, uint8_t
satellites_visible)
291 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 292 char *buf = (
char *)msgbuf;
307 #if MAVLINK_CRC_EXTRA 328 #if MAVLINK_CRC_EXTRA 349 return _MAV_RETURN_uint64_t(msg, 0);
369 return _MAV_RETURN_int32_t(msg, 8);
379 return _MAV_RETURN_int32_t(msg, 12);
389 return _MAV_RETURN_int32_t(msg, 16);
399 return _MAV_RETURN_uint16_t(msg, 20);
409 return _MAV_RETURN_uint16_t(msg, 22);
419 return _MAV_RETURN_uint16_t(msg, 24);
429 return _MAV_RETURN_int16_t(msg, 26);
439 return _MAV_RETURN_int16_t(msg, 28);
449 return _MAV_RETURN_int16_t(msg, 30);
459 return _MAV_RETURN_uint16_t(msg, 32);
480 #if MAVLINK_NEED_BYTE_SWAP static uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t *msg)
Get field satellites_visible from hil_gps message.
static uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_hil_gps_t *hil_gps)
Encode a hil_gps struct.
struct __mavlink_hil_gps_t mavlink_hil_gps_t
static void mavlink_msg_hil_gps_decode(const mavlink_message_t *msg, mavlink_hil_gps_t *hil_gps)
Decode a hil_gps message into a struct.
static uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t *msg)
Send a hil_gps message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t *msg)
Get field cog from hil_gps message.
#define MAVLINK_MSG_ID_HIL_GPS
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 _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 MAVLINK_MSG_ID_HIL_GPS_LEN
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
Pack a hil_gps message.
static uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t *msg)
Get field fix_type from hil_gps message.
#define MAVLINK_MSG_ID_HIL_GPS_CRC
static int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t *msg)
Get field alt from hil_gps message.
static uint16_t mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
Pack a hil_gps message on a channel.
#define _MAV_PAYLOAD(msg)
static int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t *msg)
Get field lat from hil_gps message.
static int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t *msg)
Get field ve from hil_gps message.
uint8_t satellites_visible
static uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_hil_gps_t *hil_gps)
Encode a hil_gps struct on a channel.
static uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t *msg)
Get field vel from hil_gps message.
static int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t *msg)
Get field vn from hil_gps message.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t *msg)
Get field eph from hil_gps message.
static int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t *msg)
Get field lon from hil_gps message.
static uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t *msg)
Get field epv from hil_gps 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 int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t *msg)
Get field vd from hil_gps message.
#define _mav_put_int16_t(buf, wire_offset, b)