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
51 char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
52 _mav_put_uint16_t(buf, 0, req_message_rate);
53 _mav_put_uint8_t(buf, 2, target_system);
54 _mav_put_uint8_t(buf, 3, target_component);
55 _mav_put_uint8_t(buf, 4, req_stream_id);
56 _mav_put_uint8_t(buf, 5, start_stop);
58 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
67 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
70 msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
72 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
74 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
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
96 char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
97 _mav_put_uint16_t(buf, 0, req_message_rate);
98 _mav_put_uint8_t(buf, 2, target_system);
99 _mav_put_uint8_t(buf, 3, target_component);
100 _mav_put_uint8_t(buf, 4, req_stream_id);
101 _mav_put_uint8_t(buf, 5, start_stop);
103 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
112 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
115 msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
116 #if MAVLINK_CRC_EXTRA
117 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
119 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
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
165 char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
166 _mav_put_uint16_t(buf, 0, req_message_rate);
167 _mav_put_uint8_t(buf, 2, target_system);
168 _mav_put_uint8_t(buf, 3, target_component);
169 _mav_put_uint8_t(buf, 4, req_stream_id);
170 _mav_put_uint8_t(buf, 5, start_stop);
172 #if MAVLINK_CRC_EXTRA
173 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
175 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
185 #if MAVLINK_CRC_EXTRA
186 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (
const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
188 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (
const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
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;
205 _mav_put_uint16_t(buf, 0, req_message_rate);
206 _mav_put_uint8_t(buf, 2, target_system);
207 _mav_put_uint8_t(buf, 3, target_component);
208 _mav_put_uint8_t(buf, 4, req_stream_id);
209 _mav_put_uint8_t(buf, 5, start_stop);
211 #if MAVLINK_CRC_EXTRA
212 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
214 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
224 #if MAVLINK_CRC_EXTRA
225 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (
const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
227 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (
const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
243 static inline uint8_t mavlink_msg_request_data_stream_get_target_system(
const mavlink_message_t* msg)
245 return _MAV_RETURN_uint8_t(msg, 2);
253 static inline uint8_t mavlink_msg_request_data_stream_get_target_component(
const mavlink_message_t* msg)
255 return _MAV_RETURN_uint8_t(msg, 3);
263 static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(
const mavlink_message_t* msg)
265 return _MAV_RETURN_uint8_t(msg, 4);
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)
285 return _MAV_RETURN_uint8_t(msg, 5);
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);
303 memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
uint8_t target_component
The target requested to send the message stream.
Definition: mavlink_msg_request_data_stream.h:9
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