
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... | |
| #define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL | 
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.
| 
 | inlinestatic | 
Decode a file_transfer_protocol message into a struct.
| msg | The message to decode | 
| file_transfer_protocol | C-struct to decode the message contents into | 
Definition at line 263 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Encode a file_transfer_protocol struct.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| msg | The MAVLink message to compress the data into | 
| file_transfer_protocol | C-struct to read the message contents from | 
Definition at line 119 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Encode a file_transfer_protocol struct on a channel.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| chan | The MAVLink channel this message will be sent over | 
| msg | The MAVLink message to compress the data into | 
| file_transfer_protocol | C-struct to read the message contents from | 
Definition at line 133 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Get field payload from file_transfer_protocol message.
Definition at line 252 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Get field target_component from file_transfer_protocol message.
Definition at line 242 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Send a file_transfer_protocol message.
| chan | MAVLink channel to send the message | 
| target_network | Network ID (0 for broadcast) | 
| target_system | System ID (0 for broadcast) | 
| target_component | Component ID (0 for broadcast) | 
| payload | 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. Get field target_network from file_transfer_protocol message | 
Definition at line 222 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Get field target_system from file_transfer_protocol message.
Definition at line 232 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Pack a file_transfer_protocol message.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| msg | The MAVLink message to compress the data into | 
| target_network | Network ID (0 for broadcast) | 
| target_system | System ID (0 for broadcast) | 
| target_component | Component ID (0 for broadcast) | 
| payload | 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 44 of file mavlink_msg_file_transfer_protocol.h.
| 
 | inlinestatic | 
Pack a file_transfer_protocol message on a channel.
| system_id | ID of this system | 
| component_id | ID of this component (e.g. 200 for IMU) | 
| chan | The MAVLink channel this message will be sent over | 
| msg | The MAVLink message to compress the data into | 
| target_network | Network ID (0 for broadcast) | 
| target_system | System ID (0 for broadcast) | 
| target_component | Component ID (0 for broadcast) | 
| payload | 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 83 of file mavlink_msg_file_transfer_protocol.h.