Classes | Macros | Typedefs | Functions
mavlink_msg_data_transmission_handshake.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_data_transmission_handshake_t
 

Macros

#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE
 
#define MAVLINK_MSG_ID_130_CRC   29
 
#define MAVLINK_MSG_ID_130_LEN   13
 
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE   130
 
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC   29
 
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN   13
 

Typedefs

typedef struct __mavlink_data_transmission_handshake_t mavlink_data_transmission_handshake_t
 

Functions

static void mavlink_msg_data_transmission_handshake_decode (const mavlink_message_t *msg, mavlink_data_transmission_handshake_t *data_transmission_handshake)
 Decode a data_transmission_handshake message into a struct. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_data_transmission_handshake_t *data_transmission_handshake)
 Encode a data_transmission_handshake struct. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_data_transmission_handshake_t *data_transmission_handshake)
 Encode a data_transmission_handshake struct on a channel. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_get_height (const mavlink_message_t *msg)
 Get field height from data_transmission_handshake message. More...
 
static uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality (const mavlink_message_t *msg)
 Get field jpg_quality from data_transmission_handshake message. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_get_packets (const mavlink_message_t *msg)
 Get field packets from data_transmission_handshake message. More...
 
static uint8_t mavlink_msg_data_transmission_handshake_get_payload (const mavlink_message_t *msg)
 Get field payload from data_transmission_handshake message. More...
 
static uint32_t mavlink_msg_data_transmission_handshake_get_size (const mavlink_message_t *msg)
 Get field size from data_transmission_handshake message. More...
 
static uint8_t mavlink_msg_data_transmission_handshake_get_type (const mavlink_message_t *msg)
 Send a data_transmission_handshake message. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_get_width (const mavlink_message_t *msg)
 Get field width from data_transmission_handshake message. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
 Pack a data_transmission_handshake message. More...
 
static uint16_t mavlink_msg_data_transmission_handshake_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
 Pack a data_transmission_handshake message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE
Value:
{ \
"DATA_TRANSMISSION_HANDSHAKE", \
7, \
{ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
{ "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
{ "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_data_transmission_handshake.h.

#define MAVLINK_MSG_ID_130_CRC   29

Definition at line 20 of file mavlink_msg_data_transmission_handshake.h.

#define MAVLINK_MSG_ID_130_LEN   13

Definition at line 17 of file mavlink_msg_data_transmission_handshake.h.

#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE   130

Definition at line 3 of file mavlink_msg_data_transmission_handshake.h.

#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC   29

Definition at line 19 of file mavlink_msg_data_transmission_handshake.h.

#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN   13

Definition at line 16 of file mavlink_msg_data_transmission_handshake.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_data_transmission_handshake_decode ( const mavlink_message_t *  msg,
mavlink_data_transmission_handshake_t data_transmission_handshake 
)
inlinestatic

Decode a data_transmission_handshake message into a struct.

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

Definition at line 340 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_data_transmission_handshake_t data_transmission_handshake 
)
inlinestatic

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

Definition at line 147 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_data_transmission_handshake_t data_transmission_handshake 
)
inlinestatic

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

Definition at line 161 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_get_height ( const mavlink_message_t *  msg)
inlinestatic

Get field height from data_transmission_handshake message.

Returns
Height of a matrix or image

Definition at line 299 of file mavlink_msg_data_transmission_handshake.h.

static uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality ( const mavlink_message_t *  msg)
inlinestatic

Get field jpg_quality from data_transmission_handshake message.

Returns
JPEG quality out of [1,100]

Definition at line 329 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_get_packets ( const mavlink_message_t *  msg)
inlinestatic

Get field packets from data_transmission_handshake message.

Returns
number of packets beeing sent (set on ACK only)

Definition at line 309 of file mavlink_msg_data_transmission_handshake.h.

static uint8_t mavlink_msg_data_transmission_handshake_get_payload ( const mavlink_message_t *  msg)
inlinestatic

Get field payload from data_transmission_handshake message.

Returns
payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)

Definition at line 319 of file mavlink_msg_data_transmission_handshake.h.

static uint32_t mavlink_msg_data_transmission_handshake_get_size ( const mavlink_message_t *  msg)
inlinestatic

Get field size from data_transmission_handshake message.

Returns
total data size in bytes (set on ACK only)

Definition at line 279 of file mavlink_msg_data_transmission_handshake.h.

static uint8_t mavlink_msg_data_transmission_handshake_get_type ( const mavlink_message_t *  msg)
inlinestatic

Send a data_transmission_handshake message.

Parameters
chanMAVLink channel to send the message
typetype of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
sizetotal data size in bytes (set on ACK only)
widthWidth of a matrix or image
heightHeight of a matrix or image
packetsnumber of packets beeing sent (set on ACK only)
payloadpayload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
jpg_qualityJPEG quality out of [1,100] Get field type from data_transmission_handshake message
Returns
type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)

Definition at line 269 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_get_width ( const mavlink_message_t *  msg)
inlinestatic

Get field width from data_transmission_handshake message.

Returns
Width of a matrix or image

Definition at line 289 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  type,
uint32_t  size,
uint16_t  width,
uint16_t  height,
uint16_t  packets,
uint8_t  payload,
uint8_t  jpg_quality 
)
inlinestatic

Pack a data_transmission_handshake 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
typetype of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
sizetotal data size in bytes (set on ACK only)
widthWidth of a matrix or image
heightHeight of a matrix or image
packetsnumber of packets beeing sent (set on ACK only)
payloadpayload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
jpg_qualityJPEG quality out of [1,100]
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_data_transmission_handshake.h.

static uint16_t mavlink_msg_data_transmission_handshake_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  type,
uint32_t  size,
uint16_t  width,
uint16_t  height,
uint16_t  packets,
uint8_t  payload,
uint8_t  jpg_quality 
)
inlinestatic

Pack a data_transmission_handshake 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
typetype of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
sizetotal data size in bytes (set on ACK only)
widthWidth of a matrix or image
heightHeight of a matrix or image
packetsnumber of packets beeing sent (set on ACK only)
payloadpayload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
jpg_qualityJPEG quality out of [1,100]
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_data_transmission_handshake.h.



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