3 #define MAVLINK_MSG_ID_TIMESYNC 111 11 #define MAVLINK_MSG_ID_TIMESYNC_LEN 16 12 #define MAVLINK_MSG_ID_111_LEN 16 14 #define MAVLINK_MSG_ID_TIMESYNC_CRC 34 15 #define MAVLINK_MSG_ID_111_CRC 34 19 #define MAVLINK_MESSAGE_INFO_TIMESYNC { \ 22 { { "tc1", NULL, MAVLINK_TYPE_INT64_T, 0, 0, offsetof(mavlink_timesync_t, tc1) }, \ 23 { "ts1", NULL, MAVLINK_TYPE_INT64_T, 0, 8, offsetof(mavlink_timesync_t, ts1) }, \ 41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 74 mavlink_message_t* msg,
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 142 #if MAVLINK_CRC_EXTRA 152 #if MAVLINK_CRC_EXTRA 160 #if MAVLINK_MSG_ID_TIMESYNC_LEN <= MAVLINK_MAX_PAYLOAD_LEN 168 static inline void mavlink_msg_timesync_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, int64_t
tc1, int64_t
ts1)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 171 char *buf = (
char *)msgbuf;
175 #if MAVLINK_CRC_EXTRA 185 #if MAVLINK_CRC_EXTRA 206 return _MAV_RETURN_int64_t(msg, 0);
216 return _MAV_RETURN_int64_t(msg, 8);
227 #if MAVLINK_NEED_BYTE_SWAP
static void mavlink_msg_timesync_decode(const mavlink_message_t *msg, mavlink_timesync_t *timesync)
Decode a timesync message into a struct.
#define MAVLINK_MSG_ID_TIMESYNC
static uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, int64_t tc1, int64_t ts1)
Pack a timesync message on a channel.
#define MAVLINK_MSG_ID_TIMESYNC_CRC
#define _mav_put_int64_t(buf, wire_offset, b)
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_PAYLOAD_NON_CONST(msg)
#define _MAV_PAYLOAD(msg)
static uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_timesync_t *timesync)
Encode a timesync struct.
struct __mavlink_timesync_t mavlink_timesync_t
static int64_t mavlink_msg_timesync_get_ts1(const mavlink_message_t *msg)
Get field ts1 from timesync message.
static int64_t mavlink_msg_timesync_get_tc1(const mavlink_message_t *msg)
Send a timesync message.
#define MAVLINK_MSG_ID_TIMESYNC_LEN
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_timesync_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_timesync_t *timesync)
Encode a timesync struct on a channel.
static uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, int64_t tc1, int64_t ts1)
Pack a timesync message.