Classes | Macros | Typedefs | Functions
mavlink_msg_log_data.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_data_t
 

Macros

#define MAVLINK_MESSAGE_INFO_LOG_DATA
 
#define MAVLINK_MSG_ID_120_CRC   134
 
#define MAVLINK_MSG_ID_120_LEN   97
 
#define MAVLINK_MSG_ID_LOG_DATA   120
 
#define MAVLINK_MSG_ID_LOG_DATA_CRC   134
 
#define MAVLINK_MSG_ID_LOG_DATA_LEN   97
 
#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN   90
 

Typedefs

typedef struct __mavlink_log_data_t mavlink_log_data_t
 

Functions

static void mavlink_msg_log_data_decode (const mavlink_message_t *msg, mavlink_log_data_t *log_data)
 Decode a log_data message into a struct. More...
 
static uint16_t mavlink_msg_log_data_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_log_data_t *log_data)
 Encode a log_data struct. More...
 
static uint16_t mavlink_msg_log_data_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_log_data_t *log_data)
 Encode a log_data struct on a channel. More...
 
static uint8_t mavlink_msg_log_data_get_count (const mavlink_message_t *msg)
 Get field count from log_data message. More...
 
static uint16_t mavlink_msg_log_data_get_data (const mavlink_message_t *msg, uint8_t *data)
 Get field data from log_data message. More...
 
static uint16_t mavlink_msg_log_data_get_id (const mavlink_message_t *msg)
 Send a log_data message. More...
 
static uint32_t mavlink_msg_log_data_get_ofs (const mavlink_message_t *msg)
 Get field ofs from log_data message. More...
 
static uint16_t mavlink_msg_log_data_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
 Pack a log_data message. More...
 
static uint16_t mavlink_msg_log_data_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
 Pack a log_data message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_LOG_DATA
Value:
{ \
"LOG_DATA", \
4, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 21 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_ID_120_CRC   134

Definition at line 17 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_ID_120_LEN   97

Definition at line 14 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_ID_LOG_DATA   120

Definition at line 3 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_ID_LOG_DATA_CRC   134

Definition at line 16 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_ID_LOG_DATA_LEN   97

Definition at line 13 of file mavlink_msg_log_data.h.

#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN   90

Definition at line 19 of file mavlink_msg_log_data.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_log_data_decode ( const mavlink_message_t *  msg,
mavlink_log_data_t log_data 
)
inlinestatic

Decode a log_data message into a struct.

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

Definition at line 263 of file mavlink_msg_log_data.h.

static uint16_t mavlink_msg_log_data_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_log_data_t log_data 
)
inlinestatic

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

Definition at line 119 of file mavlink_msg_log_data.h.

static uint16_t mavlink_msg_log_data_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_log_data_t log_data 
)
inlinestatic

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

Definition at line 133 of file mavlink_msg_log_data.h.

static uint8_t mavlink_msg_log_data_get_count ( const mavlink_message_t *  msg)
inlinestatic

Get field count from log_data message.

Returns
Number of bytes (zero for end of log)

Definition at line 242 of file mavlink_msg_log_data.h.

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

Get field data from log_data message.

Returns
log data

Definition at line 252 of file mavlink_msg_log_data.h.

static uint16_t mavlink_msg_log_data_get_id ( const mavlink_message_t *  msg)
inlinestatic

Send a log_data message.

Parameters
chanMAVLink channel to send the message
idLog id (from LOG_ENTRY reply)
ofsOffset into the log
countNumber of bytes (zero for end of log)
datalog data Get field id from log_data message
Returns
Log id (from LOG_ENTRY reply)

Definition at line 222 of file mavlink_msg_log_data.h.

static uint32_t mavlink_msg_log_data_get_ofs ( const mavlink_message_t *  msg)
inlinestatic

Get field ofs from log_data message.

Returns
Offset into the log

Definition at line 232 of file mavlink_msg_log_data.h.

static uint16_t mavlink_msg_log_data_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint16_t  id,
uint32_t  ofs,
uint8_t  count,
const uint8_t *  data 
)
inlinestatic

Pack a log_data 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
idLog id (from LOG_ENTRY reply)
ofsOffset into the log
countNumber of bytes (zero for end of log)
datalog data
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 44 of file mavlink_msg_log_data.h.

static uint16_t mavlink_msg_log_data_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint16_t  id,
uint32_t  ofs,
uint8_t  count,
const uint8_t *  data 
)
inlinestatic

Pack a log_data 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
idLog id (from LOG_ENTRY reply)
ofsOffset into the log
countNumber of bytes (zero for end of log)
datalog data
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 83 of file mavlink_msg_log_data.h.



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