4#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119
7typedef struct __mavlink_log_request_data_t {
11 uint8_t target_system;
12 uint8_t target_component;
13}) mavlink_log_request_data_t;
15#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12
16#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN 12
17#define MAVLINK_MSG_ID_119_LEN 12
18#define MAVLINK_MSG_ID_119_MIN_LEN 12
20#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116
21#define MAVLINK_MSG_ID_119_CRC 116
25#if MAVLINK_COMMAND_24BIT
26#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \
30 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
31 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
32 { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
33 { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
34 { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
38#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \
41 { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
42 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
43 { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
44 { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
45 { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
63static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
64 uint8_t target_system, uint8_t target_component, uint16_t
id, uint32_t ofs, uint32_t count)
66#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
68 _mav_put_uint32_t(buf, 0, ofs);
69 _mav_put_uint32_t(buf, 4, count);
70 _mav_put_uint16_t(buf, 8,
id);
71 _mav_put_uint8_t(buf, 10, target_system);
72 _mav_put_uint8_t(buf, 11, target_component);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
76 mavlink_log_request_data_t packet;
80 packet.target_system = target_system;
81 packet.target_component = target_component;
83 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
86 msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
87 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
103static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
104 mavlink_message_t* msg,
105 uint8_t target_system,uint8_t target_component,uint16_t
id,uint32_t ofs,uint32_t count)
107#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
109 _mav_put_uint32_t(buf, 0, ofs);
110 _mav_put_uint32_t(buf, 4, count);
111 _mav_put_uint16_t(buf, 8,
id);
112 _mav_put_uint8_t(buf, 10, target_system);
113 _mav_put_uint8_t(buf, 11, target_component);
115 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
117 mavlink_log_request_data_t packet;
119 packet.count = count;
121 packet.target_system = target_system;
122 packet.target_component = target_component;
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
127 msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
128 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
139static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_log_request_data_t* log_request_data)
141 return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
153static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_log_request_data_t* log_request_data)
155 return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
168#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t
id, uint32_t ofs, uint32_t count)
172#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173 char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
174 _mav_put_uint32_t(buf, 0, ofs);
175 _mav_put_uint32_t(buf, 4, count);
176 _mav_put_uint16_t(buf, 8,
id);
177 _mav_put_uint8_t(buf, 10, target_system);
178 _mav_put_uint8_t(buf, 11, target_component);
180 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
182 mavlink_log_request_data_t packet;
184 packet.count = count;
186 packet.target_system = target_system;
187 packet.target_component = target_component;
189 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (
const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
198static inline void mavlink_msg_log_request_data_send_struct(mavlink_channel_t chan,
const mavlink_log_request_data_t* log_request_data)
200#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
201 mavlink_msg_log_request_data_send(chan, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
203 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (
const char *)log_request_data, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
207#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
215static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t
id, uint32_t ofs, uint32_t count)
217#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
218 char *buf = (
char *)msgbuf;
219 _mav_put_uint32_t(buf, 0, ofs);
220 _mav_put_uint32_t(buf, 4, count);
221 _mav_put_uint16_t(buf, 8,
id);
222 _mav_put_uint8_t(buf, 10, target_system);
223 _mav_put_uint8_t(buf, 11, target_component);
225 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
227 mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf;
229 packet->count = count;
231 packet->target_system = target_system;
232 packet->target_component = target_component;
234 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (
const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_MIN_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
249static inline uint8_t mavlink_msg_log_request_data_get_target_system(
const mavlink_message_t* msg)
251 return _MAV_RETURN_uint8_t(msg, 10);
259static inline uint8_t mavlink_msg_log_request_data_get_target_component(
const mavlink_message_t* msg)
261 return _MAV_RETURN_uint8_t(msg, 11);
269static inline uint16_t mavlink_msg_log_request_data_get_id(
const mavlink_message_t* msg)
271 return _MAV_RETURN_uint16_t(msg, 8);
279static inline uint32_t mavlink_msg_log_request_data_get_ofs(
const mavlink_message_t* msg)
281 return _MAV_RETURN_uint32_t(msg, 0);
289static inline uint32_t mavlink_msg_log_request_data_get_count(
const mavlink_message_t* msg)
291 return _MAV_RETURN_uint32_t(msg, 4);
300static inline void mavlink_msg_log_request_data_decode(
const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data)
302#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
303 log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg);
304 log_request_data->count = mavlink_msg_log_request_data_get_count(msg);
305 log_request_data->id = mavlink_msg_log_request_data_get_id(msg);
306 log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg);
307 log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg);
309 uint8_t len = msg->len < MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN;
310 memset(log_request_data, 0, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
311 memcpy(log_request_data, _MAV_PAYLOAD(msg), len);