1 // MESSAGE SYSTEM_TIME PACKING
3 #define MAVLINK_MSG_ID_SYSTEM_TIME 2
5 typedef struct __mavlink_system_time_t
7 uint64_t time_unix_usec
; ///< Timestamp of the master clock in microseconds since UNIX epoch.
8 uint32_t time_boot_ms
; ///< Timestamp of the component clock since boot time in milliseconds.
9 } mavlink_system_time_t
;
11 #define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12
12 #define MAVLINK_MSG_ID_2_LEN 12
14 #define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137
15 #define MAVLINK_MSG_ID_2_CRC 137
19 #define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
22 { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
23 { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
29 * @brief Pack a system_time message
30 * @param system_id ID of this system
31 * @param component_id ID of this component (e.g. 200 for IMU)
32 * @param msg The MAVLink message to compress the data into
34 * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
35 * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
36 * @return length of the message in bytes (excluding serial stream start sign)
38 static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
39 uint64_t time_unix_usec
, uint32_t time_boot_ms
)
41 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
42 char buf
[MAVLINK_MSG_ID_SYSTEM_TIME_LEN
];
43 _mav_put_uint64_t(buf
, 0, time_unix_usec
);
44 _mav_put_uint32_t(buf
, 8, time_boot_ms
);
46 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
48 mavlink_system_time_t packet
;
49 packet
.time_unix_usec
= time_unix_usec
;
50 packet
.time_boot_ms
= time_boot_ms
;
52 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
55 msg
->msgid
= MAVLINK_MSG_ID_SYSTEM_TIME
;
57 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
59 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
64 * @brief Pack a system_time message on a channel
65 * @param system_id ID of this system
66 * @param component_id ID of this component (e.g. 200 for IMU)
67 * @param chan The MAVLink channel this message will be sent over
68 * @param msg The MAVLink message to compress the data into
69 * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
70 * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
71 * @return length of the message in bytes (excluding serial stream start sign)
73 static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
74 mavlink_message_t
* msg
,
75 uint64_t time_unix_usec
,uint32_t time_boot_ms
)
77 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
78 char buf
[MAVLINK_MSG_ID_SYSTEM_TIME_LEN
];
79 _mav_put_uint64_t(buf
, 0, time_unix_usec
);
80 _mav_put_uint32_t(buf
, 8, time_boot_ms
);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
84 mavlink_system_time_t packet
;
85 packet
.time_unix_usec
= time_unix_usec
;
86 packet
.time_boot_ms
= time_boot_ms
;
88 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
91 msg
->msgid
= MAVLINK_MSG_ID_SYSTEM_TIME
;
93 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
95 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
100 * @brief Encode a system_time struct
102 * @param system_id ID of this system
103 * @param component_id ID of this component (e.g. 200 for IMU)
104 * @param msg The MAVLink message to compress the data into
105 * @param system_time C-struct to read the message contents from
107 static 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
)
109 return mavlink_msg_system_time_pack(system_id
, component_id
, msg
, system_time
->time_unix_usec
, system_time
->time_boot_ms
);
113 * @brief Encode a system_time struct on a channel
115 * @param system_id ID of this system
116 * @param component_id ID of this component (e.g. 200 for IMU)
117 * @param chan The MAVLink channel this message will be sent over
118 * @param msg The MAVLink message to compress the data into
119 * @param system_time C-struct to read the message contents from
121 static 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
)
123 return mavlink_msg_system_time_pack_chan(system_id
, component_id
, chan
, msg
, system_time
->time_unix_usec
, system_time
->time_boot_ms
);
127 * @brief Send a system_time message
128 * @param chan MAVLink channel to send the message
130 * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
131 * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
133 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
135 static inline void mavlink_msg_system_time_send(mavlink_channel_t chan
, uint64_t time_unix_usec
, uint32_t time_boot_ms
)
137 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
138 char buf
[MAVLINK_MSG_ID_SYSTEM_TIME_LEN
];
139 _mav_put_uint64_t(buf
, 0, time_unix_usec
);
140 _mav_put_uint32_t(buf
, 8, time_boot_ms
);
142 #if MAVLINK_CRC_EXTRA
143 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
145 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
148 mavlink_system_time_t packet
;
149 packet
.time_unix_usec
= time_unix_usec
;
150 packet
.time_boot_ms
= time_boot_ms
;
152 #if MAVLINK_CRC_EXTRA
153 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, (const char *)&packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
155 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, (const char *)&packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
160 #if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN
162 This varient of _send() can be used to save stack space by re-using
163 memory from the receive buffer. The caller provides a
164 mavlink_message_t which is the size of a full mavlink message. This
165 is usually the receive buffer for the channel, and allows a reply to an
166 incoming message with minimum stack space usage.
168 static 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
)
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171 char *buf
= (char *)msgbuf
;
172 _mav_put_uint64_t(buf
, 0, time_unix_usec
);
173 _mav_put_uint32_t(buf
, 8, time_boot_ms
);
175 #if MAVLINK_CRC_EXTRA
176 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
178 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, buf
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
181 mavlink_system_time_t
*packet
= (mavlink_system_time_t
*)msgbuf
;
182 packet
->time_unix_usec
= time_unix_usec
;
183 packet
->time_boot_ms
= time_boot_ms
;
185 #if MAVLINK_CRC_EXTRA
186 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, (const char *)packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
, MAVLINK_MSG_ID_SYSTEM_TIME_CRC
);
188 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SYSTEM_TIME
, (const char *)packet
, MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);
196 // MESSAGE SYSTEM_TIME UNPACKING
200 * @brief Get field time_unix_usec from system_time message
202 * @return Timestamp of the master clock in microseconds since UNIX epoch.
204 static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t
* msg
)
206 return _MAV_RETURN_uint64_t(msg
, 0);
210 * @brief Get field time_boot_ms from system_time message
212 * @return Timestamp of the component clock since boot time in milliseconds.
214 static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t
* msg
)
216 return _MAV_RETURN_uint32_t(msg
, 8);
220 * @brief Decode a system_time message into a struct
222 * @param msg The message to decode
223 * @param system_time C-struct to decode the message contents into
225 static inline void mavlink_msg_system_time_decode(const mavlink_message_t
* msg
, mavlink_system_time_t
* system_time
)
227 #if MAVLINK_NEED_BYTE_SWAP
228 system_time
->time_unix_usec
= mavlink_msg_system_time_get_time_unix_usec(msg
);
229 system_time
->time_boot_ms
= mavlink_msg_system_time_get_time_boot_ms(msg
);
231 memcpy(system_time
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_SYSTEM_TIME_LEN
);