Classes | Macros | Typedefs | Functions
mavlink_msg_rosflight_config_info.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_rosflight_config_info_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG_INFO
 
#define MAVLINK_MSG_ID_203_CRC   123
 
#define MAVLINK_MSG_ID_203_LEN   22
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO   203
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_CRC   123
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_LEN   22
 
#define MAVLINK_MSG_ROSFLIGHT_CONFIG_INFO_FIELD_NAME_LEN   20
 

Typedefs

typedef struct __mavlink_rosflight_config_info_t mavlink_rosflight_config_info_t
 

Functions

static void mavlink_msg_rosflight_config_info_decode (const mavlink_message_t *msg, mavlink_rosflight_config_info_t *rosflight_config_info)
 Decode a rosflight_config_info message into a struct. More...
 
static uint16_t mavlink_msg_rosflight_config_info_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_config_info_t *rosflight_config_info)
 Encode a rosflight_config_info struct. More...
 
static uint16_t mavlink_msg_rosflight_config_info_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_config_info_t *rosflight_config_info)
 Encode a rosflight_config_info struct on a channel. More...
 
static uint8_t mavlink_msg_rosflight_config_info_get_config (const mavlink_message_t *msg)
 Get field config from rosflight_config_info message. More...
 
static uint8_t mavlink_msg_rosflight_config_info_get_device (const mavlink_message_t *msg)
 Send a rosflight_config_info message. More...
 
static uint16_t mavlink_msg_rosflight_config_info_get_name (const mavlink_message_t *msg, uint8_t *name)
 Get field name from rosflight_config_info message. More...
 
static uint16_t mavlink_msg_rosflight_config_info_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t config, const uint8_t *name)
 Pack a rosflight_config_info message. More...
 
static uint16_t mavlink_msg_rosflight_config_info_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t config, const uint8_t *name)
 Pack a rosflight_config_info message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG_INFO
Value:
{ \
"ROSFLIGHT_CONFIG_INFO", \
3, \
{ { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_config_info_t, device) }, \
{ "config", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_config_info_t, config) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 20 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ID_203_CRC   123

Definition at line 16 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ID_203_LEN   22

Definition at line 13 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO   203

Definition at line 3 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_CRC   123

Definition at line 15 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_INFO_LEN   22

Definition at line 12 of file mavlink_msg_rosflight_config_info.h.

#define MAVLINK_MSG_ROSFLIGHT_CONFIG_INFO_FIELD_NAME_LEN   20

Definition at line 18 of file mavlink_msg_rosflight_config_info.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_rosflight_config_info_decode ( const mavlink_message_t *  msg,
mavlink_rosflight_config_info_t rosflight_config_info 
)
inlinestatic

Decode a rosflight_config_info message into a struct.

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

Definition at line 240 of file mavlink_msg_rosflight_config_info.h.

static uint16_t mavlink_msg_rosflight_config_info_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_rosflight_config_info_t rosflight_config_info 
)
inlinestatic

Encode a rosflight_config_info 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
rosflight_config_infoC-struct to read the message contents from

Definition at line 111 of file mavlink_msg_rosflight_config_info.h.

static uint16_t mavlink_msg_rosflight_config_info_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_rosflight_config_info_t rosflight_config_info 
)
inlinestatic

Encode a rosflight_config_info 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
rosflight_config_infoC-struct to read the message contents from

Definition at line 125 of file mavlink_msg_rosflight_config_info.h.

static uint8_t mavlink_msg_rosflight_config_info_get_config ( const mavlink_message_t *  msg)
inlinestatic

Get field config from rosflight_config_info message.

Returns

Definition at line 219 of file mavlink_msg_rosflight_config_info.h.

static uint8_t mavlink_msg_rosflight_config_info_get_device ( const mavlink_message_t *  msg)
inlinestatic

Send a rosflight_config_info message.

Parameters
chanMAVLink channel to send the message
device
config
nameGet field device from rosflight_config_info message
Returns

Definition at line 209 of file mavlink_msg_rosflight_config_info.h.

static uint16_t mavlink_msg_rosflight_config_info_get_name ( const mavlink_message_t *  msg,
uint8_t *  name 
)
inlinestatic

Get field name from rosflight_config_info message.

Returns

Definition at line 229 of file mavlink_msg_rosflight_config_info.h.

static uint16_t mavlink_msg_rosflight_config_info_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  config,
const uint8_t *  name 
)
inlinestatic

Pack a rosflight_config_info 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
device
config
name
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 41 of file mavlink_msg_rosflight_config_info.h.

static uint16_t mavlink_msg_rosflight_config_info_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  config,
const uint8_t *  name 
)
inlinestatic

Pack a rosflight_config_info 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
device
config
name
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 77 of file mavlink_msg_rosflight_config_info.h.



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