3 #define MAVLINK_MSG_ID_LOG_ENTRY 118 14 #define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 15 #define MAVLINK_MSG_ID_118_LEN 14 17 #define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 18 #define MAVLINK_MSG_ID_118_CRC 56 22 #define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ 25 { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ 26 { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ 27 { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ 28 { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ 29 { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ 50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 92 mavlink_message_t* msg,
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 116 #if MAVLINK_CRC_EXTRA 160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 172 #if MAVLINK_CRC_EXTRA 185 #if MAVLINK_CRC_EXTRA 193 #if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN 203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 204 char *buf = (
char *)msgbuf;
211 #if MAVLINK_CRC_EXTRA 224 #if MAVLINK_CRC_EXTRA 245 return _MAV_RETURN_uint16_t(msg, 8);
255 return _MAV_RETURN_uint16_t(msg, 10);
265 return _MAV_RETURN_uint16_t(msg, 12);
275 return _MAV_RETURN_uint32_t(msg, 0);
285 return _MAV_RETURN_uint32_t(msg, 4);
296 #if MAVLINK_NEED_BYTE_SWAP
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.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _MAV_PAYLOAD_NON_CONST(msg)
#define _MAV_PAYLOAD(msg)
struct __mavlink_log_entry_t mavlink_log_entry_t
static uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t *msg)
Get field time_utc from log_entry message.
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_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_get_num_logs(const mavlink_message_t *msg)
Get field num_logs from log_entry message.
#define MAVLINK_MSG_ID_LOG_ENTRY
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.
#define MAVLINK_MSG_ID_LOG_ENTRY_LEN
#define _mav_put_uint16_t(buf, wire_offset, b)
#define MAVLINK_MSG_ID_LOG_ENTRY_CRC
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.
static uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t *msg)
Get field size from log_entry message.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t *msg)
Send a log_entry message.
#define _mav_put_uint32_t(buf, wire_offset, b)