mavlink_msg_auth_key.h
Go to the documentation of this file.
1 // MESSAGE AUTH_KEY PACKING
2 
3 #define MAVLINK_MSG_ID_AUTH_KEY 7
4 
5 typedef struct __mavlink_auth_key_t
6 {
7  char key[32]; /*< key*/
9 
10 #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
11 #define MAVLINK_MSG_ID_7_LEN 32
12 
13 #define MAVLINK_MSG_ID_AUTH_KEY_CRC 119
14 #define MAVLINK_MSG_ID_7_CRC 119
15 
16 #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
17 
18 #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
19  "AUTH_KEY", \
20  1, \
21  { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
22  } \
23 }
24 
25 
35 static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
36  const char *key)
37 {
38 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
40 
41  _mav_put_char_array(buf, 0, key, 32);
43 #else
44  mavlink_auth_key_t packet;
45 
46  mav_array_memcpy(packet.key, key, sizeof(char)*32);
48 #endif
49 
50  msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
51 #if MAVLINK_CRC_EXTRA
53 #else
54  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
55 #endif
56 }
57 
67 static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
68  mavlink_message_t* msg,
69  const char *key)
70 {
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
73 
74  _mav_put_char_array(buf, 0, key, 32);
76 #else
77  mavlink_auth_key_t packet;
78 
79  mav_array_memcpy(packet.key, key, sizeof(char)*32);
81 #endif
82 
83  msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
84 #if MAVLINK_CRC_EXTRA
86 #else
87  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
88 #endif
89 }
90 
99 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)
100 {
101  return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
102 }
103 
113 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)
114 {
115  return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
116 }
117 
124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
125 
126 static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
127 {
128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
129  char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
130 
131  _mav_put_char_array(buf, 0, key, 32);
132 #if MAVLINK_CRC_EXTRA
133  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
134 #else
135  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
136 #endif
137 #else
138  mavlink_auth_key_t packet;
139 
140  mav_array_memcpy(packet.key, key, sizeof(char)*32);
141 #if MAVLINK_CRC_EXTRA
142  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
143 #else
144  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
145 #endif
146 #endif
147 }
148 
149 #if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
150 /*
151  This varient of _send() can be used to save stack space by re-using
152  memory from the receive buffer. The caller provides a
153  mavlink_message_t which is the size of a full mavlink message. This
154  is usually the receive buffer for the channel, and allows a reply to an
155  incoming message with minimum stack space usage.
156  */
157 static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key)
158 {
159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
160  char *buf = (char *)msgbuf;
161 
162  _mav_put_char_array(buf, 0, key, 32);
163 #if MAVLINK_CRC_EXTRA
164  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
165 #else
166  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
167 #endif
168 #else
169  mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
170 
171  mav_array_memcpy(packet->key, key, sizeof(char)*32);
172 #if MAVLINK_CRC_EXTRA
173  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
174 #else
175  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
176 #endif
177 #endif
178 }
179 #endif
180 
181 #endif
182 
183 // MESSAGE AUTH_KEY UNPACKING
184 
185 
191 static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
192 {
193  return _MAV_RETURN_char_array(msg, key, 32, 0);
194 }
195 
202 static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
203 {
204 #if MAVLINK_NEED_BYTE_SWAP
205  mavlink_msg_auth_key_get_key(msg, auth_key->key);
206 #else
207  memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN);
208 #endif
209 }
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:288
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
Definition: protocol.h:188


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:12