Classes | Macros | Typedefs | Functions
mavlink_msg_rosflight_config.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_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG
 
#define MAVLINK_MSG_ID_201_CRC   248
 
#define MAVLINK_MSG_ID_201_LEN   2
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG   201
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_CRC   248
 
#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_LEN   2
 

Typedefs

typedef struct __mavlink_rosflight_config_t mavlink_rosflight_config_t
 

Functions

static void mavlink_msg_rosflight_config_decode (const mavlink_message_t *msg, mavlink_rosflight_config_t *rosflight_config)
 Decode a rosflight_config message into a struct. More...
 
static uint16_t mavlink_msg_rosflight_config_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rosflight_config_t *rosflight_config)
 Encode a rosflight_config struct. More...
 
static uint16_t mavlink_msg_rosflight_config_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rosflight_config_t *rosflight_config)
 Encode a rosflight_config struct on a channel. More...
 
static uint8_t mavlink_msg_rosflight_config_get_config (const mavlink_message_t *msg)
 Get field config from rosflight_config message. More...
 
static uint8_t mavlink_msg_rosflight_config_get_device (const mavlink_message_t *msg)
 Send a rosflight_config message. More...
 
static uint16_t mavlink_msg_rosflight_config_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t config)
 Pack a rosflight_config message. More...
 
static uint16_t mavlink_msg_rosflight_config_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t config)
 Pack a rosflight_config message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ROSFLIGHT_CONFIG
Value:
{ \
"ROSFLIGHT_CONFIG", \
2, \
{ { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rosflight_config_t, device) }, \
{ "config", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rosflight_config_t, config) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 19 of file mavlink_msg_rosflight_config.h.

#define MAVLINK_MSG_ID_201_CRC   248

Definition at line 15 of file mavlink_msg_rosflight_config.h.

#define MAVLINK_MSG_ID_201_LEN   2

Definition at line 12 of file mavlink_msg_rosflight_config.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG   201

Definition at line 3 of file mavlink_msg_rosflight_config.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_CRC   248

Definition at line 14 of file mavlink_msg_rosflight_config.h.

#define MAVLINK_MSG_ID_ROSFLIGHT_CONFIG_LEN   2

Definition at line 11 of file mavlink_msg_rosflight_config.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_rosflight_config_decode ( const mavlink_message_t *  msg,
mavlink_rosflight_config_t rosflight_config 
)
inlinestatic

Decode a rosflight_config message into a struct.

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

Definition at line 225 of file mavlink_msg_rosflight_config.h.

static uint16_t mavlink_msg_rosflight_config_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_rosflight_config_t rosflight_config 
)
inlinestatic

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

Definition at line 107 of file mavlink_msg_rosflight_config.h.

static uint16_t mavlink_msg_rosflight_config_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_rosflight_config_t rosflight_config 
)
inlinestatic

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

Definition at line 121 of file mavlink_msg_rosflight_config.h.

static uint8_t mavlink_msg_rosflight_config_get_config ( const mavlink_message_t *  msg)
inlinestatic

Get field config from rosflight_config message.

Returns

Definition at line 214 of file mavlink_msg_rosflight_config.h.

static uint8_t mavlink_msg_rosflight_config_get_device ( const mavlink_message_t *  msg)
inlinestatic

Send a rosflight_config message.

Parameters
chanMAVLink channel to send the message
device
configGet field device from rosflight_config message
Returns

Definition at line 204 of file mavlink_msg_rosflight_config.h.

static uint16_t mavlink_msg_rosflight_config_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  config 
)
inlinestatic

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

Definition at line 38 of file mavlink_msg_rosflight_config.h.

static uint16_t mavlink_msg_rosflight_config_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  config 
)
inlinestatic

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

Definition at line 73 of file mavlink_msg_rosflight_config.h.



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