1 | // MESSAGE AUTH_KEY PACKING
|
---|
2 |
|
---|
3 | #define MAVLINK_MSG_ID_AUTH_KEY 7
|
---|
4 |
|
---|
5 | typedef struct MAVLINK_PACKED __mavlink_auth_key_t
|
---|
6 | {
|
---|
7 | char key[32]; /*< key*/
|
---|
8 | } mavlink_auth_key_t;
|
---|
9 |
|
---|
10 | #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
|
---|
11 | #define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32
|
---|
12 | #define MAVLINK_MSG_ID_7_LEN 32
|
---|
13 | #define MAVLINK_MSG_ID_7_MIN_LEN 32
|
---|
14 |
|
---|
15 | #define MAVLINK_MSG_ID_AUTH_KEY_CRC 119
|
---|
16 | #define MAVLINK_MSG_ID_7_CRC 119
|
---|
17 |
|
---|
18 | #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
|
---|
19 |
|
---|
20 | #if MAVLINK_COMMAND_24BIT
|
---|
21 | #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
|
---|
22 | 7, \
|
---|
23 | "AUTH_KEY", \
|
---|
24 | 1, \
|
---|
25 | { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
|
---|
26 | } \
|
---|
27 | }
|
---|
28 | #else
|
---|
29 | #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
|
---|
30 | "AUTH_KEY", \
|
---|
31 | 1, \
|
---|
32 | { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
|
---|
33 | } \
|
---|
34 | }
|
---|
35 | #endif
|
---|
36 |
|
---|
37 | /**
|
---|
38 | * @brief Pack a auth_key message
|
---|
39 | * @param system_id ID of this system
|
---|
40 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
41 | * @param msg The MAVLink message to compress the data into
|
---|
42 | *
|
---|
43 | * @param key key
|
---|
44 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
45 | */
|
---|
46 | static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
|
---|
47 | const char *key)
|
---|
48 | {
|
---|
49 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
50 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
|
---|
51 |
|
---|
52 | _mav_put_char_array(buf, 0, key, 32);
|
---|
53 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
---|
54 | #else
|
---|
55 | mavlink_auth_key_t packet;
|
---|
56 |
|
---|
57 | mav_array_memcpy(packet.key, key, sizeof(char)*32);
|
---|
58 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
---|
59 | #endif
|
---|
60 |
|
---|
61 | msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
|
---|
62 | return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
63 | }
|
---|
64 |
|
---|
65 | /**
|
---|
66 | * @brief Pack a auth_key message on a channel
|
---|
67 | * @param system_id ID of this system
|
---|
68 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
69 | * @param chan The MAVLink channel this message will be sent over
|
---|
70 | * @param msg The MAVLink message to compress the data into
|
---|
71 | * @param key key
|
---|
72 | * @return length of the message in bytes (excluding serial stream start sign)
|
---|
73 | */
|
---|
74 | static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
|
---|
75 | mavlink_message_t* msg,
|
---|
76 | const char *key)
|
---|
77 | {
|
---|
78 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
79 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
|
---|
80 |
|
---|
81 | _mav_put_char_array(buf, 0, key, 32);
|
---|
82 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
---|
83 | #else
|
---|
84 | mavlink_auth_key_t packet;
|
---|
85 |
|
---|
86 | mav_array_memcpy(packet.key, key, sizeof(char)*32);
|
---|
87 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
---|
88 | #endif
|
---|
89 |
|
---|
90 | msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
|
---|
91 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
92 | }
|
---|
93 |
|
---|
94 | /**
|
---|
95 | * @brief Encode a auth_key struct
|
---|
96 | *
|
---|
97 | * @param system_id ID of this system
|
---|
98 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
99 | * @param msg The MAVLink message to compress the data into
|
---|
100 | * @param auth_key C-struct to read the message contents from
|
---|
101 | */
|
---|
102 | static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
|
---|
103 | {
|
---|
104 | return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
|
---|
105 | }
|
---|
106 |
|
---|
107 | /**
|
---|
108 | * @brief Encode a auth_key struct on a channel
|
---|
109 | *
|
---|
110 | * @param system_id ID of this system
|
---|
111 | * @param component_id ID of this component (e.g. 200 for IMU)
|
---|
112 | * @param chan The MAVLink channel this message will be sent over
|
---|
113 | * @param msg The MAVLink message to compress the data into
|
---|
114 | * @param auth_key C-struct to read the message contents from
|
---|
115 | */
|
---|
116 | static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
|
---|
117 | {
|
---|
118 | return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
|
---|
119 | }
|
---|
120 |
|
---|
121 | /**
|
---|
122 | * @brief Send a auth_key message
|
---|
123 | * @param chan MAVLink channel to send the message
|
---|
124 | *
|
---|
125 | * @param key key
|
---|
126 | */
|
---|
127 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
|
---|
128 |
|
---|
129 | static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
|
---|
130 | {
|
---|
131 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
132 | char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
|
---|
133 |
|
---|
134 | _mav_put_char_array(buf, 0, key, 32);
|
---|
135 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
136 | #else
|
---|
137 | mavlink_auth_key_t packet;
|
---|
138 |
|
---|
139 | mav_array_memcpy(packet.key, key, sizeof(char)*32);
|
---|
140 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
141 | #endif
|
---|
142 | }
|
---|
143 |
|
---|
144 | /**
|
---|
145 | * @brief Send a auth_key message
|
---|
146 | * @param chan MAVLink channel to send the message
|
---|
147 | * @param struct The MAVLink struct to serialize
|
---|
148 | */
|
---|
149 | static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan, const mavlink_auth_key_t* auth_key)
|
---|
150 | {
|
---|
151 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
152 | mavlink_msg_auth_key_send(chan, auth_key->key);
|
---|
153 | #else
|
---|
154 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)auth_key, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
155 | #endif
|
---|
156 | }
|
---|
157 |
|
---|
158 | #if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
|
---|
159 | /*
|
---|
160 | This varient of _send() can be used to save stack space by re-using
|
---|
161 | memory from the receive buffer. The caller provides a
|
---|
162 | mavlink_message_t which is the size of a full mavlink message. This
|
---|
163 | is usually the receive buffer for the channel, and allows a reply to an
|
---|
164 | incoming message with minimum stack space usage.
|
---|
165 | */
|
---|
166 | static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key)
|
---|
167 | {
|
---|
168 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
169 | char *buf = (char *)msgbuf;
|
---|
170 |
|
---|
171 | _mav_put_char_array(buf, 0, key, 32);
|
---|
172 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
173 | #else
|
---|
174 | mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
|
---|
175 |
|
---|
176 | mav_array_memcpy(packet->key, key, sizeof(char)*32);
|
---|
177 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
|
---|
178 | #endif
|
---|
179 | }
|
---|
180 | #endif
|
---|
181 |
|
---|
182 | #endif
|
---|
183 |
|
---|
184 | // MESSAGE AUTH_KEY UNPACKING
|
---|
185 |
|
---|
186 |
|
---|
187 | /**
|
---|
188 | * @brief Get field key from auth_key message
|
---|
189 | *
|
---|
190 | * @return key
|
---|
191 | */
|
---|
192 | static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
|
---|
193 | {
|
---|
194 | return _MAV_RETURN_char_array(msg, key, 32, 0);
|
---|
195 | }
|
---|
196 |
|
---|
197 | /**
|
---|
198 | * @brief Decode a auth_key message into a struct
|
---|
199 | *
|
---|
200 | * @param msg The message to decode
|
---|
201 | * @param auth_key C-struct to decode the message contents into
|
---|
202 | */
|
---|
203 | static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
|
---|
204 | {
|
---|
205 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
|
---|
206 | mavlink_msg_auth_key_get_key(msg, auth_key->key);
|
---|
207 | #else
|
---|
208 | uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN;
|
---|
209 | memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN);
|
---|
210 | memcpy(auth_key, _MAV_PAYLOAD(msg), len);
|
---|
211 | #endif
|
---|
212 | }
|
---|