3 #define MAVLINK_MSG_ID_GPS_RTK 127 22 #define MAVLINK_MSG_ID_GPS_RTK_LEN 35 23 #define MAVLINK_MSG_ID_127_LEN 35 25 #define MAVLINK_MSG_ID_GPS_RTK_CRC 25 26 #define MAVLINK_MSG_ID_127_CRC 25 30 #define MAVLINK_MESSAGE_INFO_GPS_RTK { \ 33 { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ 34 { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ 35 { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ 36 { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ 37 { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ 38 { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ 39 { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ 40 { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ 41 { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ 42 { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ 43 { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ 44 { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ 45 { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ 72 uint32_t
time_last_baseline_ms, uint8_t
rtk_receiver_id, uint16_t
wn, uint32_t
tow, uint8_t
rtk_health, uint8_t
rtk_rate, uint8_t
nsats, uint8_t
baseline_coords_type, int32_t
baseline_a_mm, int32_t
baseline_b_mm, int32_t
baseline_c_mm, uint32_t
accuracy, int32_t
iar_num_hypotheses)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 111 #if MAVLINK_CRC_EXTRA 140 mavlink_message_t* msg,
141 uint32_t
time_last_baseline_ms,uint8_t
rtk_receiver_id,uint16_t
wn,uint32_t
tow,uint8_t
rtk_health,uint8_t
rtk_rate,uint8_t
nsats,uint8_t
baseline_coords_type,int32_t
baseline_a_mm,int32_t
baseline_b_mm,int32_t
baseline_c_mm,uint32_t
accuracy,int32_t
iar_num_hypotheses)
143 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 180 #if MAVLINK_CRC_EXTRA 197 return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->
time_last_baseline_ms, gps_rtk->
rtk_receiver_id, gps_rtk->
wn, gps_rtk->
tow, gps_rtk->
rtk_health, gps_rtk->
rtk_rate, gps_rtk->
nsats, gps_rtk->
baseline_coords_type, gps_rtk->
baseline_a_mm, gps_rtk->
baseline_b_mm, gps_rtk->
baseline_c_mm, gps_rtk->
accuracy, gps_rtk->
iar_num_hypotheses);
211 return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->
time_last_baseline_ms, gps_rtk->
rtk_receiver_id, gps_rtk->
wn, gps_rtk->
tow, gps_rtk->
rtk_health, gps_rtk->
rtk_rate, gps_rtk->
nsats, gps_rtk->
baseline_coords_type, gps_rtk->
baseline_a_mm, gps_rtk->
baseline_b_mm, gps_rtk->
baseline_c_mm, gps_rtk->
accuracy, gps_rtk->
iar_num_hypotheses);
232 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 234 static inline void mavlink_msg_gps_rtk_send(
mavlink_channel_t chan, uint32_t
time_last_baseline_ms, uint8_t
rtk_receiver_id, uint16_t
wn, uint32_t
tow, uint8_t
rtk_health, uint8_t
rtk_rate, uint8_t
nsats, uint8_t
baseline_coords_type, int32_t
baseline_a_mm, int32_t
baseline_b_mm, int32_t
baseline_c_mm, uint32_t
accuracy, int32_t
iar_num_hypotheses)
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 252 #if MAVLINK_CRC_EXTRA 273 #if MAVLINK_CRC_EXTRA 281 #if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN 289 static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t
time_last_baseline_ms, uint8_t
rtk_receiver_id, uint16_t
wn, uint32_t
tow, uint8_t
rtk_health, uint8_t
rtk_rate, uint8_t
nsats, uint8_t
baseline_coords_type, int32_t
baseline_a_mm, int32_t
baseline_b_mm, int32_t
baseline_c_mm, uint32_t
accuracy, int32_t
iar_num_hypotheses)
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_uint32_t(msg, 0);
369 return _MAV_RETURN_uint16_t(msg, 28);
379 return _MAV_RETURN_uint32_t(msg, 4);
429 return _MAV_RETURN_int32_t(msg, 8);
439 return _MAV_RETURN_int32_t(msg, 12);
449 return _MAV_RETURN_int32_t(msg, 16);
459 return _MAV_RETURN_uint32_t(msg, 20);
469 return _MAV_RETURN_int32_t(msg, 24);
480 #if MAVLINK_NEED_BYTE_SWAP struct __mavlink_gps_rtk_t mavlink_gps_rtk_t
int32_t iar_num_hypotheses
static uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t *msg)
Get field nsats from gps_rtk message.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t *msg)
Get field baseline_a_mm from gps_rtk message.
static uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t *msg)
Get field rtk_health from gps_rtk message.
static uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
Pack a gps_rtk message on a channel.
static uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_rtk_t *gps_rtk)
Encode a gps_rtk struct on a channel.
static uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t *msg)
Get field rtk_receiver_id from gps_rtk message.
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_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t *msg)
Get field rtk_rate from gps_rtk message.
uint32_t time_last_baseline_ms
static uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_rtk_t *gps_rtk)
Encode a gps_rtk struct.
static uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t *msg)
Send a gps_rtk message.
#define _MAV_PAYLOAD(msg)
static int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t *msg)
Get field baseline_c_mm from gps_rtk message.
static int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t *msg)
Get field iar_num_hypotheses from gps_rtk message.
#define MAVLINK_MSG_ID_GPS_RTK_CRC
static void mavlink_msg_gps_rtk_decode(const mavlink_message_t *msg, mavlink_gps_rtk_t *gps_rtk)
Decode a gps_rtk message into a struct.
static uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t *msg)
Get field accuracy from gps_rtk message.
static uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t *msg)
Get field tow from gps_rtk message.
static uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
Pack a gps_rtk message.
#define MAVLINK_MSG_ID_GPS_RTK
uint8_t baseline_coords_type
static uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t *msg)
Get field baseline_coords_type from gps_rtk message.
#define _mav_put_uint16_t(buf, wire_offset, b)
static uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t *msg)
Get field wn from gps_rtk 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.
#define MAVLINK_MSG_ID_GPS_RTK_LEN
static int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t *msg)
Get field baseline_b_mm from gps_rtk message.
#define _mav_put_uint32_t(buf, wire_offset, b)