Classes | Macros | Typedefs | Functions
mavlink_msg_log_request_list.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_log_request_list_t
 

Macros

#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST
 
#define MAVLINK_MSG_ID_117_CRC   128
 
#define MAVLINK_MSG_ID_117_LEN   6
 
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST   117
 
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC   128
 
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN   6
 

Typedefs

typedef struct __mavlink_log_request_list_t mavlink_log_request_list_t
 

Functions

static void mavlink_msg_log_request_list_decode (const mavlink_message_t *msg, mavlink_log_request_list_t *log_request_list)
 Decode a log_request_list message into a struct. More...
 
static uint16_t mavlink_msg_log_request_list_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_log_request_list_t *log_request_list)
 Encode a log_request_list struct. More...
 
static uint16_t mavlink_msg_log_request_list_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_log_request_list_t *log_request_list)
 Encode a log_request_list struct on a channel. More...
 
static uint16_t mavlink_msg_log_request_list_get_end (const mavlink_message_t *msg)
 Get field end from log_request_list message. More...
 
static uint16_t mavlink_msg_log_request_list_get_start (const mavlink_message_t *msg)
 Get field start from log_request_list message. More...
 
static uint8_t mavlink_msg_log_request_list_get_target_component (const mavlink_message_t *msg)
 Get field target_component from log_request_list message. More...
 
static uint8_t mavlink_msg_log_request_list_get_target_system (const mavlink_message_t *msg)
 Send a log_request_list message. More...
 
static uint16_t mavlink_msg_log_request_list_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
 Pack a log_request_list message. More...
 
static uint16_t mavlink_msg_log_request_list_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
 Pack a log_request_list message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST
Value:
{ \
"LOG_REQUEST_LIST", \
4, \
{ { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_log_request_list.h.

#define MAVLINK_MSG_ID_117_CRC   128

Definition at line 17 of file mavlink_msg_log_request_list.h.

#define MAVLINK_MSG_ID_117_LEN   6

Definition at line 14 of file mavlink_msg_log_request_list.h.

#define MAVLINK_MSG_ID_LOG_REQUEST_LIST   117

Definition at line 3 of file mavlink_msg_log_request_list.h.

#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC   128

Definition at line 16 of file mavlink_msg_log_request_list.h.

#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN   6

Definition at line 13 of file mavlink_msg_log_request_list.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_log_request_list_decode ( const mavlink_message_t *  msg,
mavlink_log_request_list_t log_request_list 
)
inlinestatic

Decode a log_request_list message into a struct.

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

Definition at line 271 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_log_request_list_t log_request_list 
)
inlinestatic

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

Definition at line 123 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_log_request_list_t log_request_list 
)
inlinestatic

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

Definition at line 137 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_get_end ( const mavlink_message_t *  msg)
inlinestatic

Get field end from log_request_list message.

Returns
Last log id (0xffff for last available)

Definition at line 260 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_get_start ( const mavlink_message_t *  msg)
inlinestatic

Get field start from log_request_list message.

Returns
First log id (0 for first available)

Definition at line 250 of file mavlink_msg_log_request_list.h.

static uint8_t mavlink_msg_log_request_list_get_target_component ( const mavlink_message_t *  msg)
inlinestatic

Get field target_component from log_request_list message.

Returns
Component ID

Definition at line 240 of file mavlink_msg_log_request_list.h.

static uint8_t mavlink_msg_log_request_list_get_target_system ( const mavlink_message_t *  msg)
inlinestatic

Send a log_request_list message.

Parameters
chanMAVLink channel to send the message
target_systemSystem ID
target_componentComponent ID
startFirst log id (0 for first available)
endLast log id (0xffff for last available) Get field target_system from log_request_list message
Returns
System ID

Definition at line 230 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  start,
uint16_t  end 
)
inlinestatic

Pack a log_request_list 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_systemSystem ID
target_componentComponent ID
startFirst log id (0 for first available)
endLast log id (0xffff for last available)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_log_request_list.h.

static uint16_t mavlink_msg_log_request_list_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target_system,
uint8_t  target_component,
uint16_t  start,
uint16_t  end 
)
inlinestatic

Pack a log_request_list 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_systemSystem ID
target_componentComponent ID
startFirst log id (0 for first available)
endLast log id (0xffff for last available)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 85 of file mavlink_msg_log_request_list.h.



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