Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE SYSTEM_TIME_UTC PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_SYSTEM_TIME_UTC 4 |
||
4 | |||
5 | typedef struct __mavlink_system_time_utc_t |
||
6 | { |
||
7 | uint32_t utc_date; ///< GPS UTC date ddmmyy |
||
8 | uint32_t utc_time; ///< GPS UTC time hhmmss |
||
9 | } mavlink_system_time_utc_t; |
||
10 | |||
11 | #define MAVLINK_MSG_ID_SYSTEM_TIME_UTC_LEN 8 |
||
12 | #define MAVLINK_MSG_ID_4_LEN 8 |
||
13 | |||
14 | |||
15 | |||
16 | #define MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC { \ |
||
17 | "SYSTEM_TIME_UTC", \ |
||
18 | 2, \ |
||
19 | { { "utc_date", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_system_time_utc_t, utc_date) }, \ |
||
20 | { "utc_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_system_time_utc_t, utc_time) }, \ |
||
21 | } \ |
||
22 | } |
||
23 | |||
24 | |||
25 | /** |
||
26 | * @brief Pack a system_time_utc message |
||
27 | * @param system_id ID of this system |
||
28 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
29 | * @param msg The MAVLink message to compress the data into |
||
30 | * |
||
31 | * @param utc_date GPS UTC date ddmmyy |
||
32 | * @param utc_time GPS UTC time hhmmss |
||
33 | * @return length of the message in bytes (excluding serial stream start sign) |
||
34 | */ |
||
35 | static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
36 | uint32_t utc_date, uint32_t utc_time) |
||
37 | { |
||
38 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
39 | char buf[8]; |
||
40 | _mav_put_uint32_t(buf, 0, utc_date); |
||
41 | _mav_put_uint32_t(buf, 4, utc_time); |
||
42 | |||
43 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); |
||
44 | #else |
||
45 | mavlink_system_time_utc_t packet; |
||
46 | packet.utc_date = utc_date; |
||
47 | packet.utc_time = utc_time; |
||
48 | |||
49 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); |
||
50 | #endif |
||
51 | |||
52 | msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; |
||
53 | return mavlink_finalize_message(msg, system_id, component_id, 8); |
||
54 | } |
||
55 | |||
56 | /** |
||
57 | * @brief Pack a system_time_utc message on a channel |
||
58 | * @param system_id ID of this system |
||
59 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
60 | * @param chan The MAVLink channel this message was sent over |
||
61 | * @param msg The MAVLink message to compress the data into |
||
62 | * @param utc_date GPS UTC date ddmmyy |
||
63 | * @param utc_time GPS UTC time hhmmss |
||
64 | * @return length of the message in bytes (excluding serial stream start sign) |
||
65 | */ |
||
66 | static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
67 | mavlink_message_t* msg, |
||
68 | uint32_t utc_date,uint32_t utc_time) |
||
69 | { |
||
70 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
71 | char buf[8]; |
||
72 | _mav_put_uint32_t(buf, 0, utc_date); |
||
73 | _mav_put_uint32_t(buf, 4, utc_time); |
||
74 | |||
75 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8); |
||
76 | #else |
||
77 | mavlink_system_time_utc_t packet; |
||
78 | packet.utc_date = utc_date; |
||
79 | packet.utc_time = utc_time; |
||
80 | |||
81 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8); |
||
82 | #endif |
||
83 | |||
84 | msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC; |
||
85 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8); |
||
86 | } |
||
87 | |||
88 | /** |
||
89 | * @brief Encode a system_time_utc struct into a message |
||
90 | * |
||
91 | * @param system_id ID of this system |
||
92 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
93 | * @param msg The MAVLink message to compress the data into |
||
94 | * @param system_time_utc C-struct to read the message contents from |
||
95 | */ |
||
96 | static inline uint16_t mavlink_msg_system_time_utc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_utc_t* system_time_utc) |
||
97 | { |
||
98 | return mavlink_msg_system_time_utc_pack(system_id, component_id, msg, system_time_utc->utc_date, system_time_utc->utc_time); |
||
99 | } |
||
100 | |||
101 | /** |
||
102 | * @brief Send a system_time_utc message |
||
103 | * @param chan MAVLink channel to send the message |
||
104 | * |
||
105 | * @param utc_date GPS UTC date ddmmyy |
||
106 | * @param utc_time GPS UTC time hhmmss |
||
107 | */ |
||
108 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
109 | |||
110 | static inline void mavlink_msg_system_time_utc_send(mavlink_channel_t chan, uint32_t utc_date, uint32_t utc_time) |
||
111 | { |
||
112 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
113 | char buf[8]; |
||
114 | _mav_put_uint32_t(buf, 0, utc_date); |
||
115 | _mav_put_uint32_t(buf, 4, utc_time); |
||
116 | |||
117 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, buf, 8); |
||
118 | #else |
||
119 | mavlink_system_time_utc_t packet; |
||
120 | packet.utc_date = utc_date; |
||
121 | packet.utc_time = utc_time; |
||
122 | |||
123 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, (const char *)&packet, 8); |
||
124 | #endif |
||
125 | } |
||
126 | |||
127 | #endif |
||
128 | |||
129 | // MESSAGE SYSTEM_TIME_UTC UNPACKING |
||
130 | |||
131 | |||
132 | /** |
||
133 | * @brief Get field utc_date from system_time_utc message |
||
134 | * |
||
135 | * @return GPS UTC date ddmmyy |
||
136 | */ |
||
137 | static inline uint32_t mavlink_msg_system_time_utc_get_utc_date(const mavlink_message_t* msg) |
||
138 | { |
||
139 | return _MAV_RETURN_uint32_t(msg, 0); |
||
140 | } |
||
141 | |||
142 | /** |
||
143 | * @brief Get field utc_time from system_time_utc message |
||
144 | * |
||
145 | * @return GPS UTC time hhmmss |
||
146 | */ |
||
147 | static inline uint32_t mavlink_msg_system_time_utc_get_utc_time(const mavlink_message_t* msg) |
||
148 | { |
||
149 | return _MAV_RETURN_uint32_t(msg, 4); |
||
150 | } |
||
151 | |||
152 | /** |
||
153 | * @brief Decode a system_time_utc message into a struct |
||
154 | * |
||
155 | * @param msg The message to decode |
||
156 | * @param system_time_utc C-struct to decode the message contents into |
||
157 | */ |
||
158 | static inline void mavlink_msg_system_time_utc_decode(const mavlink_message_t* msg, mavlink_system_time_utc_t* system_time_utc) |
||
159 | { |
||
160 | #if MAVLINK_NEED_BYTE_SWAP |
||
161 | system_time_utc->utc_date = mavlink_msg_system_time_utc_get_utc_date(msg); |
||
162 | system_time_utc->utc_time = mavlink_msg_system_time_utc_get_utc_time(msg); |
||
163 | #else |
||
164 | memcpy(system_time_utc, _MAV_PAYLOAD(msg), 8); |
||
165 | #endif |
||
166 | } |