Go to the source code of this file.
Classes | |
struct | __mavlink_log_entry_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_LOG_ENTRY |
#define | MAVLINK_MSG_ID_118_CRC 56 |
#define | MAVLINK_MSG_ID_118_LEN 14 |
#define | MAVLINK_MSG_ID_LOG_ENTRY 118 |
#define | MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 |
#define | MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 |
Typedefs | |
typedef struct __mavlink_log_entry_t | mavlink_log_entry_t |
Functions | |
static void | mavlink_msg_log_entry_decode (const mavlink_message_t *msg, mavlink_log_entry_t *log_entry) |
Decode a log_entry message into a struct. | |
static uint16_t | mavlink_msg_log_entry_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_log_entry_t *log_entry) |
Encode a log_entry struct. | |
static uint16_t | mavlink_msg_log_entry_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_log_entry_t *log_entry) |
Encode a log_entry struct on a channel. | |
static uint16_t | mavlink_msg_log_entry_get_id (const mavlink_message_t *msg) |
Send a log_entry message. | |
static uint16_t | mavlink_msg_log_entry_get_last_log_num (const mavlink_message_t *msg) |
Get field last_log_num from log_entry message. | |
static uint16_t | mavlink_msg_log_entry_get_num_logs (const mavlink_message_t *msg) |
Get field num_logs from log_entry message. | |
static uint32_t | mavlink_msg_log_entry_get_size (const mavlink_message_t *msg) |
Get field size from log_entry message. | |
static uint32_t | mavlink_msg_log_entry_get_time_utc (const mavlink_message_t *msg) |
Get field time_utc from log_entry message. | |
static uint16_t | mavlink_msg_log_entry_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) |
Pack a log_entry message. | |
static uint16_t | mavlink_msg_log_entry_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) |
Pack a log_entry message on a channel. |
#define MAVLINK_MESSAGE_INFO_LOG_ENTRY |
{ \ "LOG_ENTRY", \ 5, \ { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ } \ }
Definition at line 22 of file mavlink_msg_log_entry.h.
#define MAVLINK_MSG_ID_118_CRC 56 |
Definition at line 18 of file mavlink_msg_log_entry.h.
#define MAVLINK_MSG_ID_118_LEN 14 |
Definition at line 15 of file mavlink_msg_log_entry.h.
#define MAVLINK_MSG_ID_LOG_ENTRY 118 |
Definition at line 3 of file mavlink_msg_log_entry.h.
#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 |
Definition at line 17 of file mavlink_msg_log_entry.h.
#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 |
Definition at line 14 of file mavlink_msg_log_entry.h.
typedef struct __mavlink_log_entry_t mavlink_log_entry_t |
static void mavlink_msg_log_entry_decode | ( | const mavlink_message_t * | msg, |
mavlink_log_entry_t * | log_entry | ||
) | [inline, static] |
Decode a log_entry message into a struct.
msg | The message to decode |
log_entry | C-struct to decode the message contents into |
Definition at line 294 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_log_entry_t * | log_entry | ||
) | [inline, static] |
Encode a log_entry 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 |
log_entry | C-struct to read the message contents from |
Definition at line 131 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_log_entry_t * | log_entry | ||
) | [inline, static] |
Encode a log_entry 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 |
log_entry | C-struct to read the message contents from |
Definition at line 145 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_get_id | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a log_entry message.
chan | MAVLink channel to send the message |
id | Log id |
num_logs | Total number of logs |
last_log_num | High log number |
time_utc | UTC timestamp of log in seconds since 1970, or 0 if not available |
size | Size of the log (may be approximate) in bytes Get field id from log_entry message |
Definition at line 243 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_get_last_log_num | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field last_log_num from log_entry message.
Definition at line 263 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_get_num_logs | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field num_logs from log_entry message.
Definition at line 253 of file mavlink_msg_log_entry.h.
static uint32_t mavlink_msg_log_entry_get_size | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field size from log_entry message.
Definition at line 283 of file mavlink_msg_log_entry.h.
static uint32_t mavlink_msg_log_entry_get_time_utc | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field time_utc from log_entry message.
Definition at line 273 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint16_t | id, | ||
uint16_t | num_logs, | ||
uint16_t | last_log_num, | ||
uint32_t | time_utc, | ||
uint32_t | size | ||
) | [inline, static] |
Pack a log_entry 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 |
id | Log id |
num_logs | Total number of logs |
last_log_num | High log number |
time_utc | UTC timestamp of log in seconds since 1970, or 0 if not available |
size | Size of the log (may be approximate) in bytes |
Definition at line 47 of file mavlink_msg_log_entry.h.
static uint16_t mavlink_msg_log_entry_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint16_t | id, | ||
uint16_t | num_logs, | ||
uint16_t | last_log_num, | ||
uint32_t | time_utc, | ||
uint32_t | size | ||
) | [inline, static] |
Pack a log_entry 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 |
id | Log id |
num_logs | Total number of logs |
last_log_num | High log number |
time_utc | UTC timestamp of log in seconds since 1970, or 0 if not available |
size | Size of the log (may be approximate) in bytes |
Definition at line 91 of file mavlink_msg_log_entry.h.