Classes | Macros | Typedefs | Functions
mavlink_msg_auth_key.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_auth_key_t
 

Macros

#define MAVLINK_MESSAGE_INFO_AUTH_KEY
 
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN   32
 
#define MAVLINK_MSG_ID_7_CRC   119
 
#define MAVLINK_MSG_ID_7_LEN   32
 
#define MAVLINK_MSG_ID_AUTH_KEY   7
 
#define MAVLINK_MSG_ID_AUTH_KEY_CRC   119
 
#define MAVLINK_MSG_ID_AUTH_KEY_LEN   32
 

Typedefs

typedef struct __mavlink_auth_key_t mavlink_auth_key_t
 

Functions

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. More...
 
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. More...
 
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. More...
 
static uint16_t mavlink_msg_auth_key_get_key (const mavlink_message_t *msg, char *key)
 Send a auth_key message. More...
 
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. More...
 
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. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_AUTH_KEY
Value:
{ \
"AUTH_KEY", \
1, \
{ { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 18 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN   32

Definition at line 16 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_ID_7_CRC   119

Definition at line 14 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_ID_7_LEN   32

Definition at line 11 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_ID_AUTH_KEY   7

Definition at line 3 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_ID_AUTH_KEY_CRC   119

Definition at line 13 of file mavlink_msg_auth_key.h.

#define MAVLINK_MSG_ID_AUTH_KEY_LEN   32

Definition at line 10 of file mavlink_msg_auth_key.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_auth_key_decode ( const mavlink_message_t *  msg,
mavlink_auth_key_t auth_key 
)
inlinestatic

Decode a auth_key message into a struct.

Parameters
msgThe message to decode
auth_keyC-struct to decode the message contents into

Definition at line 202 of file mavlink_msg_auth_key.h.

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 
)
inlinestatic

Encode a auth_key struct.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
auth_keyC-struct to read the message contents from

Definition at line 99 of file mavlink_msg_auth_key.h.

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 
)
inlinestatic

Encode a auth_key struct on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
auth_keyC-struct to read the message contents from

Definition at line 113 of file mavlink_msg_auth_key.h.

static uint16_t mavlink_msg_auth_key_get_key ( const mavlink_message_t *  msg,
char *  key 
)
inlinestatic

Send a auth_key message.

Parameters
chanMAVLink channel to send the message
keykey Get field key from auth_key message
Returns
key

Definition at line 191 of file mavlink_msg_auth_key.h.

static uint16_t mavlink_msg_auth_key_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const char *  key 
)
inlinestatic

Pack a auth_key message.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
keykey
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 35 of file mavlink_msg_auth_key.h.

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 
)
inlinestatic

Pack a auth_key message on a channel.

Parameters
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
keykey
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 67 of file mavlink_msg_auth_key.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:50