mavlink_msg_request_data_stream.h
Go to the documentation of this file.
1 // MESSAGE REQUEST_DATA_STREAM PACKING
2 
3 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
4 
6 {
7  uint16_t req_message_rate; /*< The requested message rate*/
8  uint8_t target_system; /*< The target requested to send the message stream.*/
9  uint8_t target_component; /*< The target requested to send the message stream.*/
10  uint8_t req_stream_id; /*< The ID of the requested data stream*/
11  uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/
13 
14 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
15 #define MAVLINK_MSG_ID_66_LEN 6
16 
17 #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148
18 #define MAVLINK_MSG_ID_66_CRC 148
19 
20 
21 
22 #define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
23  "REQUEST_DATA_STREAM", \
24  5, \
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) }, \
30  } \
31 }
32 
33 
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)
49 {
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
57 
59 #else
65  packet.start_stop = start_stop;
66 
68 #endif
69 
71 #if MAVLINK_CRC_EXTRA
73 #else
74  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
75 #endif
76 }
77 
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)
94 {
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
102 
104 #else
107  packet.target_system = target_system;
109  packet.req_stream_id = req_stream_id;
110  packet.start_stop = start_stop;
111 
113 #endif
114 
116 #if MAVLINK_CRC_EXTRA
118 #else
119  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
120 #endif
121 }
122 
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)
132 {
133  return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
134 }
135 
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)
146 {
147  return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
148 }
149 
160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
161 
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)
163 {
164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
170  _mav_put_uint8_t(buf, 5, start_stop);
171 
172 #if MAVLINK_CRC_EXTRA
174 #else
175  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
176 #endif
177 #else
180  packet.target_system = target_system;
182  packet.req_stream_id = req_stream_id;
183  packet.start_stop = start_stop;
184 
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);
187 #else
188  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
189 #endif
190 #endif
191 }
192 
193 #if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
194 /*
195  This varient of _send() can be used to save stack space by re-using
196  memory from the receive buffer. The caller provides a
197  mavlink_message_t which is the size of a full mavlink message. This
198  is usually the receive buffer for the channel, and allows a reply to an
199  incoming message with minimum stack space usage.
200  */
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)
202 {
203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
204  char *buf = (char *)msgbuf;
209  _mav_put_uint8_t(buf, 5, start_stop);
210 
211 #if MAVLINK_CRC_EXTRA
213 #else
214  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
215 #endif
216 #else
219  packet->target_system = target_system;
221  packet->req_stream_id = req_stream_id;
222  packet->start_stop = start_stop;
223 
224 #if MAVLINK_CRC_EXTRA
226 #else
227  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
228 #endif
229 #endif
230 }
231 #endif
232 
233 #endif
234 
235 // MESSAGE REQUEST_DATA_STREAM UNPACKING
236 
237 
243 static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
244 {
245  return _MAV_RETURN_uint8_t(msg, 2);
246 }
247 
253 static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
254 {
255  return _MAV_RETURN_uint8_t(msg, 3);
256 }
257 
263 static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
264 {
265  return _MAV_RETURN_uint8_t(msg, 4);
266 }
267 
273 static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
274 {
275  return _MAV_RETURN_uint16_t(msg, 0);
276 }
277 
283 static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
284 {
285  return _MAV_RETURN_uint8_t(msg, 5);
286 }
287 
294 static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
295 {
296 #if MAVLINK_NEED_BYTE_SWAP
302 #else
303  memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
304 #endif
305 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13