4#define MAVLINK_MSG_ID_SYSTEM_TIME 2
7typedef struct __mavlink_system_time_t {
8 uint64_t time_unix_usec;
10}) mavlink_system_time_t;
12#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12
13#define MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN 12
14#define MAVLINK_MSG_ID_2_LEN 12
15#define MAVLINK_MSG_ID_2_MIN_LEN 12
17#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
18#define MAVLINK_MSG_ID_2_CRC 137
22#if MAVLINK_COMMAND_24BIT
23#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
27 { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
28 { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
32#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
35 { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
36 { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
51static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
52 uint64_t time_unix_usec, uint32_t time_boot_ms)
54#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55 char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
56 _mav_put_uint64_t(buf, 0, time_unix_usec);
57 _mav_put_uint32_t(buf, 8, time_boot_ms);
59 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
61 mavlink_system_time_t packet;
62 packet.time_unix_usec = time_unix_usec;
63 packet.time_boot_ms = time_boot_ms;
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
68 msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
69 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
82static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
83 mavlink_message_t* msg,
84 uint64_t time_unix_usec,uint32_t time_boot_ms)
86#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
87 char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
88 _mav_put_uint64_t(buf, 0, time_unix_usec);
89 _mav_put_uint32_t(buf, 8, time_boot_ms);
91 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
93 mavlink_system_time_t packet;
94 packet.time_unix_usec = time_unix_usec;
95 packet.time_boot_ms = time_boot_ms;
97 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
100 msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
101 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
112static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_system_time_t* system_time)
114 return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms);
126static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_system_time_t* system_time)
128 return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms);
138#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
140static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms)
142#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
143 char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN];
144 _mav_put_uint64_t(buf, 0, time_unix_usec);
145 _mav_put_uint32_t(buf, 8, time_boot_ms);
147 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
149 mavlink_system_time_t packet;
150 packet.time_unix_usec = time_unix_usec;
151 packet.time_boot_ms = time_boot_ms;
153 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (
const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
162static inline void mavlink_msg_system_time_send_struct(mavlink_channel_t chan,
const mavlink_system_time_t* system_time)
164#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
165 mavlink_msg_system_time_send(chan, system_time->time_unix_usec, system_time->time_boot_ms);
167 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (
const char *)system_time, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
171#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms)
181#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
183 _mav_put_uint64_t(buf, 0, time_unix_usec);
184 _mav_put_uint32_t(buf, 8, time_boot_ms);
186 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
188 mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf;
189 packet->time_unix_usec = time_unix_usec;
190 packet->time_boot_ms = time_boot_ms;
192 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (
const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_MIN_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC);
207static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(
const mavlink_message_t* msg)
209 return _MAV_RETURN_uint64_t(msg, 0);
217static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(
const mavlink_message_t* msg)
219 return _MAV_RETURN_uint32_t(msg, 8);
228static inline void mavlink_msg_system_time_decode(
const mavlink_message_t* msg, mavlink_system_time_t* system_time)
230#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
231 system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg);
232 system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg);
234 uint8_t len = msg->len < MAVLINK_MSG_ID_SYSTEM_TIME_LEN? msg->len : MAVLINK_MSG_ID_SYSTEM_TIME_LEN;
235 memset(system_time, 0, MAVLINK_MSG_ID_SYSTEM_TIME_LEN);
236 memcpy(system_time, _MAV_PAYLOAD(msg), len);