Classes | Macros | Typedefs | Functions
mavlink_msg_file_transfer_protocol.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_file_transfer_protocol_t
 

Macros

#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL
 
#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN   251
 
#define MAVLINK_MSG_ID_110_CRC   84
 
#define MAVLINK_MSG_ID_110_LEN   254
 
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL   110
 
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC   84
 
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN   254
 

Typedefs

typedef struct __mavlink_file_transfer_protocol_t mavlink_file_transfer_protocol_t
 

Functions

static void mavlink_msg_file_transfer_protocol_decode (const mavlink_message_t *msg, mavlink_file_transfer_protocol_t *file_transfer_protocol)
 Decode a file_transfer_protocol message into a struct. More...
 
static uint16_t mavlink_msg_file_transfer_protocol_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_file_transfer_protocol_t *file_transfer_protocol)
 Encode a file_transfer_protocol struct. More...
 
static uint16_t mavlink_msg_file_transfer_protocol_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_file_transfer_protocol_t *file_transfer_protocol)
 Encode a file_transfer_protocol struct on a channel. More...
 
static uint16_t mavlink_msg_file_transfer_protocol_get_payload (const mavlink_message_t *msg, uint8_t *payload)
 Get field payload from file_transfer_protocol message. More...
 
static uint8_t mavlink_msg_file_transfer_protocol_get_target_component (const mavlink_message_t *msg)
 Get field target_component from file_transfer_protocol message. More...
 
static uint8_t mavlink_msg_file_transfer_protocol_get_target_network (const mavlink_message_t *msg)
 Send a file_transfer_protocol message. More...
 
static uint8_t mavlink_msg_file_transfer_protocol_get_target_system (const mavlink_message_t *msg)
 Get field target_system from file_transfer_protocol message. More...
 
static uint16_t mavlink_msg_file_transfer_protocol_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
 Pack a file_transfer_protocol message. More...
 
static uint16_t mavlink_msg_file_transfer_protocol_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
 Pack a file_transfer_protocol message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL
Value:
{ \
"FILE_TRANSFER_PROTOCOL", \
4, \
{ { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN   251

Definition at line 19 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_ID_110_CRC   84

Definition at line 17 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_ID_110_LEN   254

Definition at line 14 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL   110

Definition at line 3 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC   84

Definition at line 16 of file mavlink_msg_file_transfer_protocol.h.

#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN   254

Definition at line 13 of file mavlink_msg_file_transfer_protocol.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_file_transfer_protocol_decode ( const mavlink_message_t *  msg,
mavlink_file_transfer_protocol_t file_transfer_protocol 
)
inlinestatic

Decode a file_transfer_protocol message into a struct.

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

Definition at line 263 of file mavlink_msg_file_transfer_protocol.h.

static uint16_t mavlink_msg_file_transfer_protocol_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_file_transfer_protocol_t file_transfer_protocol 
)
inlinestatic

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

Definition at line 119 of file mavlink_msg_file_transfer_protocol.h.

static uint16_t mavlink_msg_file_transfer_protocol_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_file_transfer_protocol_t file_transfer_protocol 
)
inlinestatic

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

Definition at line 133 of file mavlink_msg_file_transfer_protocol.h.

static uint16_t mavlink_msg_file_transfer_protocol_get_payload ( const mavlink_message_t *  msg,
uint8_t *  payload 
)
inlinestatic

Get field payload from file_transfer_protocol message.

Returns
Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.

Definition at line 252 of file mavlink_msg_file_transfer_protocol.h.

static uint8_t mavlink_msg_file_transfer_protocol_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from file_transfer_protocol message.

Returns
Component ID (0 for broadcast)

Definition at line 242 of file mavlink_msg_file_transfer_protocol.h.

static uint8_t mavlink_msg_file_transfer_protocol_get_target_network ( const mavlink_message_t *  msg)
inlinestatic

Send a file_transfer_protocol message.

Parameters
chanMAVLink channel to send the message
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification. Get field target_network from file_transfer_protocol message
Returns
Network ID (0 for broadcast)

Definition at line 222 of file mavlink_msg_file_transfer_protocol.h.

static uint8_t mavlink_msg_file_transfer_protocol_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Get field target_system from file_transfer_protocol message.

Returns
System ID (0 for broadcast)

Definition at line 232 of file mavlink_msg_file_transfer_protocol.h.

static uint16_t mavlink_msg_file_transfer_protocol_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target_network,
uint8_t  target_system,
uint8_t  target_component,
const uint8_t *  payload 
)
inlinestatic

Pack a file_transfer_protocol 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
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_file_transfer_protocol.h.

static uint16_t mavlink_msg_file_transfer_protocol_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target_network,
uint8_t  target_system,
uint8_t  target_component,
const uint8_t *  payload 
)
inlinestatic

Pack a file_transfer_protocol 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
target_networkNetwork ID (0 for broadcast)
target_systemSystem ID (0 for broadcast)
target_componentComponent ID (0 for broadcast)
payloadVariable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 83 of file mavlink_msg_file_transfer_protocol.h.



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