3 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
14 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
15 #define MAVLINK_MSG_ID_66_LEN 6
17 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148
18 #define MAVLINK_MSG_ID_66_CRC 148
22 #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
23 "REQUEST_DATA_STREAM", \
25 { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \
26 { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \
27 { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \
28 { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \
29 { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \
47 static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48 uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
91 static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
92 mavlink_message_t* msg,
93 uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop)
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
116 #if MAVLINK_CRC_EXTRA
131 static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_request_data_stream_t* request_data_stream)
145 static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_request_data_stream_t* request_data_stream)
160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
162 static inline void mavlink_msg_request_data_stream_send(
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
172 #if MAVLINK_CRC_EXTRA
185 #if MAVLINK_CRC_EXTRA
193 #if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
201 static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
204 char *buf = (
char *)msgbuf;
211 #if MAVLINK_CRC_EXTRA
224 #if MAVLINK_CRC_EXTRA
243 static inline uint8_t mavlink_msg_request_data_stream_get_target_system(
const mavlink_message_t* msg)
253 static inline uint8_t mavlink_msg_request_data_stream_get_target_component(
const mavlink_message_t* msg)
263 static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(
const mavlink_message_t* msg)
273 static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(
const mavlink_message_t* msg)
275 return _MAV_RETURN_uint16_t(msg, 0);
283 static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(
const mavlink_message_t* msg)
296 #if MAVLINK_NEED_BYTE_SWAP
297 request_data_stream->
req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
298 request_data_stream->
target_system = mavlink_msg_request_data_stream_get_target_system(msg);
299 request_data_stream->
target_component = mavlink_msg_request_data_stream_get_target_component(msg);
300 request_data_stream->
req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
301 request_data_stream->
start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC
Definition: mavlink_msg_request_data_stream.h:17
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
uint8_t target_component
The target requested to send the message stream.
Definition: mavlink_msg_request_data_stream.h:9
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.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct __mavlink_request_data_stream_t mavlink_request_data_stream_t
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN
Definition: mavlink_msg_request_data_stream.h:14
uint8_t req_stream_id
The ID of the requested data stream.
Definition: mavlink_msg_request_data_stream.h:10
uint8_t start_stop
1 to start sending, 0 to stop sending.
Definition: mavlink_msg_request_data_stream.h:11
Definition: mavlink_msg_request_data_stream.h:5
uint8_t target_system
The target requested to send the message stream.
Definition: mavlink_msg_request_data_stream.h:8
uint16_t req_message_rate
The requested interval between two messages of this type.
Definition: mavlink_msg_request_data_stream.h:7
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM
Definition: mavlink_msg_request_data_stream.h:3
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
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.
Definition: mavlink_helpers.h:71