4#define MAVLINK_MSG_ID_AUTH_KEY 7
7typedef struct __mavlink_auth_key_t {
11#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
12#define MAVLINK_MSG_ID_AUTH_KEY_MIN_LEN 32
13#define MAVLINK_MSG_ID_7_LEN 32
14#define MAVLINK_MSG_ID_7_MIN_LEN 32
16#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119
17#define MAVLINK_MSG_ID_7_CRC 119
19#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
21#if MAVLINK_COMMAND_24BIT
22#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
26 { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
30#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
33 { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
47static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
50#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
53 _mav_put_char_array(buf, 0, key, 32);
54 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
56 mavlink_auth_key_t packet;
58 mav_array_memcpy(packet.key, key,
sizeof(
char)*32);
59 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
62 msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
63 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);
75static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
76 mavlink_message_t* msg,
79#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
80 char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
82 _mav_put_char_array(buf, 0, key, 32);
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
85 mavlink_auth_key_t packet;
87 mav_array_memcpy(packet.key, key,
sizeof(
char)*32);
88 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
91 msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
92 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);
103static 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)
105 return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
117static 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)
119 return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
128#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
130static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan,
const char *key)
132#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
133 char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
135 _mav_put_char_array(buf, 0, key, 32);
136 _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);
138 mavlink_auth_key_t packet;
140 mav_array_memcpy(packet.key, key,
sizeof(
char)*32);
141 _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);
150static inline void mavlink_msg_auth_key_send_struct(mavlink_channel_t chan,
const mavlink_auth_key_t* auth_key)
152#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
153 mavlink_msg_auth_key_send(chan, auth_key->key);
155 _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);
159#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
167static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,
const char *key)
169#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
170 char *buf = (
char *)msgbuf;
172 _mav_put_char_array(buf, 0, key, 32);
173 _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);
175 mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
177 mav_array_memcpy(packet->key, key,
sizeof(
char)*32);
178 _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);
193static inline uint16_t mavlink_msg_auth_key_get_key(
const mavlink_message_t* msg,
char *key)
195 return _MAV_RETURN_char_array(msg, key, 32, 0);
204static inline void mavlink_msg_auth_key_decode(
const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
206#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
207 mavlink_msg_auth_key_get_key(msg, auth_key->key);
209 uint8_t len = msg->len < MAVLINK_MSG_ID_AUTH_KEY_LEN? msg->len : MAVLINK_MSG_ID_AUTH_KEY_LEN;
210 memset(auth_key, 0, MAVLINK_MSG_ID_AUTH_KEY_LEN);
211 memcpy(auth_key, _MAV_PAYLOAD(msg), len);