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) }, \
38 static inline uint16_t mavlink_msg_timesync_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
39 int64_t tc1, int64_t ts1)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 static inline uint16_t mavlink_msg_timesync_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
74 mavlink_message_t* msg,
75 int64_t tc1,int64_t ts1)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 static inline uint16_t mavlink_msg_timesync_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_timesync_t* timesync)
109 return mavlink_msg_timesync_pack(system_id, component_id, msg, timesync->
tc1, timesync->
ts1);
121 static inline 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)
123 return mavlink_msg_timesync_pack_chan(system_id, component_id, chan, msg, timesync->
tc1, timesync->
ts1);
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_timesync_send(
mavlink_channel_t chan, int64_t tc1, int64_t ts1)
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
204 static inline int64_t mavlink_msg_timesync_get_tc1(
const mavlink_message_t* msg)
206 return _MAV_RETURN_int64_t(msg, 0);
214 static inline int64_t mavlink_msg_timesync_get_ts1(
const mavlink_message_t* msg)
216 return _MAV_RETURN_int64_t(msg, 8);
225 static inline void mavlink_msg_timesync_decode(
const mavlink_message_t* msg,
mavlink_timesync_t* timesync)
227 #if MAVLINK_NEED_BYTE_SWAP
228 timesync->
tc1 = mavlink_msg_timesync_get_tc1(msg);
229 timesync->
ts1 = mavlink_msg_timesync_get_ts1(msg);
Definition: mavlink_msg_timesync.h:5
#define MAVLINK_MSG_ID_TIMESYNC
Definition: mavlink_msg_timesync.h:3
#define MAVLINK_MSG_ID_TIMESYNC_CRC
Definition: mavlink_msg_timesync.h:14
#define _mav_put_int64_t(buf, wire_offset, b)
Definition: protocol.h:144
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.
Definition: mavlink_helpers.h:105
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
struct __mavlink_timesync_t mavlink_timesync_t
int64_t ts1
Time sync timestamp 2.
Definition: mavlink_msg_timesync.h:8
#define MAVLINK_MSG_ID_TIMESYNC_LEN
Definition: mavlink_msg_timesync.h:11
int64_t tc1
Time sync timestamp 1.
Definition: mavlink_msg_timesync.h:7
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.
Definition: mavlink_helpers.h:71