Classes | Macros | Typedefs | Functions
mavlink_msg_serial_control.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_serial_control_t
 

Macros

#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL
 
#define MAVLINK_MSG_ID_126_CRC   220
 
#define MAVLINK_MSG_ID_126_LEN   79
 
#define MAVLINK_MSG_ID_SERIAL_CONTROL   126
 
#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC   220
 
#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN   79
 
#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN   70
 

Typedefs

typedef struct __mavlink_serial_control_t mavlink_serial_control_t
 

Functions

static void mavlink_msg_serial_control_decode (const mavlink_message_t *msg, mavlink_serial_control_t *serial_control)
 Decode a serial_control message into a struct. More...
 
static uint16_t mavlink_msg_serial_control_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_serial_control_t *serial_control)
 Encode a serial_control struct. More...
 
static uint16_t mavlink_msg_serial_control_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_serial_control_t *serial_control)
 Encode a serial_control struct on a channel. More...
 
static uint32_t mavlink_msg_serial_control_get_baudrate (const mavlink_message_t *msg)
 Get field baudrate from serial_control message. More...
 
static uint8_t mavlink_msg_serial_control_get_count (const mavlink_message_t *msg)
 Get field count from serial_control message. More...
 
static uint16_t mavlink_msg_serial_control_get_data (const mavlink_message_t *msg, uint8_t *data)
 Get field data from serial_control message. More...
 
static uint8_t mavlink_msg_serial_control_get_device (const mavlink_message_t *msg)
 Send a serial_control message. More...
 
static uint8_t mavlink_msg_serial_control_get_flags (const mavlink_message_t *msg)
 Get field flags from serial_control message. More...
 
static uint16_t mavlink_msg_serial_control_get_timeout (const mavlink_message_t *msg)
 Get field timeout from serial_control message. More...
 
static uint16_t mavlink_msg_serial_control_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
 Pack a serial_control message. More...
 
static uint16_t mavlink_msg_serial_control_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
 Pack a serial_control message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL
Value:
{ \
"SERIAL_CONTROL", \
6, \
{ { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \
{ "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \
{ "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 23 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_ID_126_CRC   220

Definition at line 19 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_ID_126_LEN   79

Definition at line 16 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_ID_SERIAL_CONTROL   126

Definition at line 3 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC   220

Definition at line 18 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN   79

Definition at line 15 of file mavlink_msg_serial_control.h.

#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN   70

Definition at line 21 of file mavlink_msg_serial_control.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_serial_control_decode ( const mavlink_message_t *  msg,
mavlink_serial_control_t serial_control 
)
inlinestatic

Decode a serial_control message into a struct.

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

Definition at line 309 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_serial_control_t serial_control 
)
inlinestatic

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

Definition at line 135 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_serial_control_t serial_control 
)
inlinestatic

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

Definition at line 149 of file mavlink_msg_serial_control.h.

static uint32_t mavlink_msg_serial_control_get_baudrate ( const mavlink_message_t *  msg)
inlinestatic

Get field baudrate from serial_control message.

Returns
Baudrate of transfer. Zero means no change.

Definition at line 278 of file mavlink_msg_serial_control.h.

static uint8_t mavlink_msg_serial_control_get_count ( const mavlink_message_t *  msg)
inlinestatic

Get field count from serial_control message.

Returns
how many bytes in this transfer

Definition at line 288 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_get_data ( const mavlink_message_t *  msg,
uint8_t *  data 
)
inlinestatic

Get field data from serial_control message.

Returns
serial data

Definition at line 298 of file mavlink_msg_serial_control.h.

static uint8_t mavlink_msg_serial_control_get_device ( const mavlink_message_t *  msg)
inlinestatic

Send a serial_control message.

Parameters
chanMAVLink channel to send the message
deviceSee SERIAL_CONTROL_DEV enum
flagsSee SERIAL_CONTROL_FLAG enum
timeoutTimeout for reply data in milliseconds
baudrateBaudrate of transfer. Zero means no change.
counthow many bytes in this transfer
dataserial data Get field device from serial_control message
Returns
See SERIAL_CONTROL_DEV enum

Definition at line 248 of file mavlink_msg_serial_control.h.

static uint8_t mavlink_msg_serial_control_get_flags ( const mavlink_message_t *  msg)
inlinestatic

Get field flags from serial_control message.

Returns
See SERIAL_CONTROL_FLAG enum

Definition at line 258 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_get_timeout ( const mavlink_message_t *  msg)
inlinestatic

Get field timeout from serial_control message.

Returns
Timeout for reply data in milliseconds

Definition at line 268 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  flags,
uint16_t  timeout,
uint32_t  baudrate,
uint8_t  count,
const uint8_t *  data 
)
inlinestatic

Pack a serial_control 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
deviceSee SERIAL_CONTROL_DEV enum
flagsSee SERIAL_CONTROL_FLAG enum
timeoutTimeout for reply data in milliseconds
baudrateBaudrate of transfer. Zero means no change.
counthow many bytes in this transfer
dataserial data
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 50 of file mavlink_msg_serial_control.h.

static uint16_t mavlink_msg_serial_control_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  device,
uint8_t  flags,
uint16_t  timeout,
uint32_t  baudrate,
uint8_t  count,
const uint8_t *  data 
)
inlinestatic

Pack a serial_control 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
deviceSee SERIAL_CONTROL_DEV enum
flagsSee SERIAL_CONTROL_FLAG enum
timeoutTimeout for reply data in milliseconds
baudrateBaudrate of transfer. Zero means no change.
counthow many bytes in this transfer
dataserial data
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 95 of file mavlink_msg_serial_control.h.



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