3 #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87    23 #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51    24 #define MAVLINK_MSG_ID_87_LEN 51    26 #define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150    27 #define MAVLINK_MSG_ID_87_CRC 150    31 #define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \    32         "POSITION_TARGET_GLOBAL_INT", \    34         {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \    35          { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \    36          { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \    37          { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \    38          { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \    39          { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \    40          { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \    41          { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \    42          { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \    43          { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \    44          { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \    45          { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \    46          { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \    47          { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \    75                                                        uint32_t 
time_boot_ms, uint8_t 
coordinate_frame, uint16_t 
type_mask, int32_t 
lat_int, int32_t 
lon_int, 
float alt, 
float vx, 
float vy, 
float vz, 
float afx, 
float afy, 
float afz, 
float yaw, 
float yaw_rate)
    77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   116 #if MAVLINK_CRC_EXTRA   146                                                            mavlink_message_t* msg,
   147                                                            uint32_t 
time_boot_ms,uint8_t 
coordinate_frame,uint16_t 
type_mask,int32_t 
lat_int,int32_t 
lon_int,
float alt,
float vx,
float vy,
float vz,
float afx,
float afy,
float afz,
float yaw,
float yaw_rate)
   149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   188 #if MAVLINK_CRC_EXTRA   205         return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->
time_boot_ms, position_target_global_int->
coordinate_frame, position_target_global_int->
type_mask, position_target_global_int->
lat_int, position_target_global_int->
lon_int, position_target_global_int->
alt, position_target_global_int->
vx, position_target_global_int->
vy, position_target_global_int->
vz, position_target_global_int->
afx, position_target_global_int->
afy, position_target_global_int->
afz, position_target_global_int->
yaw, position_target_global_int->
yaw_rate);
   219         return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->
time_boot_ms, position_target_global_int->
coordinate_frame, position_target_global_int->
type_mask, position_target_global_int->
lat_int, position_target_global_int->
lon_int, position_target_global_int->
alt, position_target_global_int->
vx, position_target_global_int->
vy, position_target_global_int->
vz, position_target_global_int->
afx, position_target_global_int->
afy, position_target_global_int->
afz, position_target_global_int->
yaw, position_target_global_int->
yaw_rate);
   241 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS   243 static inline void mavlink_msg_position_target_global_int_send(
mavlink_channel_t chan, uint32_t 
time_boot_ms, uint8_t 
coordinate_frame, uint16_t 
type_mask, int32_t 
lat_int, int32_t 
lon_int, 
float alt, 
float vx, 
float vy, 
float vz, 
float afx, 
float afy, 
float afz, 
float yaw, 
float yaw_rate)
   245 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   262 #if MAVLINK_CRC_EXTRA   284 #if MAVLINK_CRC_EXTRA   292 #if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN   300 static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, 
mavlink_channel_t chan,  uint32_t 
time_boot_ms, uint8_t 
coordinate_frame, uint16_t 
type_mask, int32_t 
lat_int, int32_t 
lon_int, 
float alt, 
float vx, 
float vy, 
float vz, 
float afx, 
float afy, 
float afz, 
float yaw, 
float yaw_rate)
   302 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS   303         char *buf = (
char *)msgbuf;
   319 #if MAVLINK_CRC_EXTRA   341 #if MAVLINK_CRC_EXTRA   362         return _MAV_RETURN_uint32_t(msg,  0);
   382         return _MAV_RETURN_uint16_t(msg,  48);
   392         return _MAV_RETURN_int32_t(msg,  4);
   402         return _MAV_RETURN_int32_t(msg,  8);
   412         return _MAV_RETURN_float(msg,  12);
   422         return _MAV_RETURN_float(msg,  16);
   432         return _MAV_RETURN_float(msg,  20);
   442         return _MAV_RETURN_float(msg,  24);
   452         return _MAV_RETURN_float(msg,  28);
   462         return _MAV_RETURN_float(msg,  32);
   472         return _MAV_RETURN_float(msg,  36);
   482         return _MAV_RETURN_float(msg,  40);
   492         return _MAV_RETURN_float(msg,  44);
   503 #if MAVLINK_NEED_BYTE_SWAP static uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t *msg)
Get field type_mask from position_target_global_int message. 
#define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t *msg)
Get field vy from position_target_global_int message. 
static float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t *msg)
Get field afz from position_target_global_int message. 
static float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t *msg)
Get field afy from position_target_global_int message. 
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_position_target_global_int_t *position_target_global_int)
Encode a position_target_global_int struct. 
static int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t *msg)
Get field lon_int from position_target_global_int message. 
static uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
Pack a position_target_global_int message on a channel. 
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_POSITION_TARGET_GLOBAL_INT_CRC
#define _mav_put_uint8_t(buf, wire_offset, b)
static void mavlink_msg_position_target_global_int_decode(const mavlink_message_t *msg, mavlink_position_target_global_int_t *position_target_global_int)
Decode a position_target_global_int message into a struct. 
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t *msg)
Get field alt from position_target_global_int message. 
#define _MAV_PAYLOAD(msg)
static uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t *msg)
Get field coordinate_frame from position_target_global_int message. 
static float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t *msg)
Get field vz from position_target_global_int message. 
static float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t *msg)
Get field yaw_rate from position_target_global_int message. 
static uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
Pack a position_target_global_int message. 
static uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t *msg)
Send a position_target_global_int message. 
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT
static float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t *msg)
Get field yaw from position_target_global_int message. 
static uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_position_target_global_int_t *position_target_global_int)
Encode a position_target_global_int struct on a channel. 
static float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t *msg)
Get field afx from position_target_global_int message. 
#define _mav_put_uint16_t(buf, wire_offset, b)
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN
struct __mavlink_position_target_global_int_t mavlink_position_target_global_int_t
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 float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t *msg)
Get field vx from position_target_global_int message. 
static int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t *msg)
Get field lat_int from position_target_global_int message. 
#define _mav_put_uint32_t(buf, wire_offset, b)