3 #define MAVLINK_MSG_ID_AUTH_KEY 7 10 #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 11 #define MAVLINK_MSG_ID_7_LEN 32 13 #define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 14 #define MAVLINK_MSG_ID_7_CRC 119 16 #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 18 #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ 21 { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ 38 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 68 mavlink_message_t* msg,
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 132 #if MAVLINK_CRC_EXTRA 141 #if MAVLINK_CRC_EXTRA 149 #if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN 157 static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan,
const char *
key)
159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 160 char *buf = (
char *)msgbuf;
163 #if MAVLINK_CRC_EXTRA 172 #if MAVLINK_CRC_EXTRA 204 #if MAVLINK_NEED_BYTE_SWAP static void mavlink_msg_auth_key_decode(const mavlink_message_t *msg, mavlink_auth_key_t *auth_key)
Decode a auth_key message into a struct.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
static 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)
Encode a auth_key struct on a channel.
static uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const char *key)
Pack a auth_key message.
#define _MAV_PAYLOAD_NON_CONST(msg)
#define MAVLINK_MSG_ID_AUTH_KEY_CRC
#define _MAV_PAYLOAD(msg)
static 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)
Encode a auth_key struct.
struct __mavlink_auth_key_t mavlink_auth_key_t
#define MAVLINK_MSG_ID_AUTH_KEY
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
static uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t *msg, char *key)
Send a auth_key message.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
#define MAVLINK_MSG_ID_AUTH_KEY_LEN
static uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const char *key)
Pack a auth_key message on a channel.