mavlink_msg_request_data_stream.h 13.1 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3 4
// MESSAGE REQUEST_DATA_STREAM PACKING

#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66

lm's avatar
lm committed
5
typedef struct __mavlink_request_data_stream_t
James Goppert's avatar
James Goppert committed
6
{
lm's avatar
lm committed
7 8 9 10 11
 uint16_t req_message_rate; ///< The requested interval between two messages of this type
 uint8_t target_system; ///< The target requested to send the message stream.
 uint8_t target_component; ///< The target requested to send the message stream.
 uint8_t req_stream_id; ///< The ID of the requested data stream
 uint8_t start_stop; ///< 1 to start sending, 0 to stop sending.
James Goppert's avatar
James Goppert committed
12 13
} mavlink_request_data_stream_t;

lm's avatar
lm committed
14 15 16
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
#define MAVLINK_MSG_ID_66_LEN 6

Lorenz Meier's avatar
Lorenz Meier committed
17 18 19
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148
#define MAVLINK_MSG_ID_66_CRC 148

lm's avatar
lm committed
20 21 22 23 24


#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
	"REQUEST_DATA_STREAM", \
	5, \
lm's avatar
lm committed
25 26 27 28 29
	{  { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \
         { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \
         { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \
         { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \
         { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \
lm's avatar
lm committed
30 31 32 33
         } \
}


James Goppert's avatar
James Goppert committed
34 35 36 37 38 39 40 41
/**
 * @brief Pack a request_data_stream message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param target_system The target requested to send the message stream.
 * @param target_component The target requested to send the message stream.
42
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
43 44 45 46
 * @param req_message_rate The requested interval between two messages of this type
 * @param start_stop 1 to start sending, 0 to stop sending.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
47 48
static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
James Goppert's avatar
James Goppert committed
49
{
LM's avatar
LM committed
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
51
	char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
LM's avatar
LM committed
52 53 54 55 56 57
	_mav_put_uint16_t(buf, 0, req_message_rate);
	_mav_put_uint8_t(buf, 2, target_system);
	_mav_put_uint8_t(buf, 3, target_component);
	_mav_put_uint8_t(buf, 4, req_stream_id);
	_mav_put_uint8_t(buf, 5, start_stop);

Lorenz Meier's avatar
Lorenz Meier committed
58
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
LM's avatar
LM committed
59 60 61 62 63 64 65 66
#else
	mavlink_request_data_stream_t packet;
	packet.req_message_rate = req_message_rate;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.req_stream_id = req_stream_id;
	packet.start_stop = start_stop;

Lorenz Meier's avatar
Lorenz Meier committed
67
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
LM's avatar
LM committed
68
#endif
James Goppert's avatar
James Goppert committed
69

LM's avatar
LM committed
70
	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
Lorenz Meier's avatar
Lorenz Meier committed
71 72 73 74 75
#if MAVLINK_CRC_EXTRA
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
James Goppert's avatar
James Goppert committed
76 77 78
}

/**
lm's avatar
lm committed
79
 * @brief Pack a request_data_stream message on a channel
James Goppert's avatar
James Goppert committed
80 81
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
Lorenz Meier's avatar
Lorenz Meier committed
82
 * @param chan The MAVLink channel this message will be sent over
James Goppert's avatar
James Goppert committed
83 84 85
 * @param msg The MAVLink message to compress the data into
 * @param target_system The target requested to send the message stream.
 * @param target_component The target requested to send the message stream.
86
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
87 88 89 90
 * @param req_message_rate The requested interval between two messages of this type
 * @param start_stop 1 to start sending, 0 to stop sending.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
91 92 93
static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop)
James Goppert's avatar
James Goppert committed
94
{
LM's avatar
LM committed
95
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
96
	char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
LM's avatar
LM committed
97 98 99 100 101 102
	_mav_put_uint16_t(buf, 0, req_message_rate);
	_mav_put_uint8_t(buf, 2, target_system);
	_mav_put_uint8_t(buf, 3, target_component);
	_mav_put_uint8_t(buf, 4, req_stream_id);
	_mav_put_uint8_t(buf, 5, start_stop);

Lorenz Meier's avatar
Lorenz Meier committed
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
LM's avatar
LM committed
104 105 106 107 108 109 110 111
#else
	mavlink_request_data_stream_t packet;
	packet.req_message_rate = req_message_rate;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.req_stream_id = req_stream_id;
	packet.start_stop = start_stop;

Lorenz Meier's avatar
Lorenz Meier committed
112
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
LM's avatar
LM committed
113
#endif
James Goppert's avatar
James Goppert committed
114

LM's avatar
LM committed
115
	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
Lorenz Meier's avatar
Lorenz Meier committed
116 117 118 119 120
#if MAVLINK_CRC_EXTRA
    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);
#else
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
James Goppert's avatar
James Goppert committed
121 122 123
}

/**
Lorenz Meier's avatar
Lorenz Meier committed
124
 * @brief Encode a request_data_stream struct
James Goppert's avatar
James Goppert committed
125 126 127 128 129 130 131 132 133 134 135
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param request_data_stream C-struct to read the message contents from
 */
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)
{
	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);
}

Lorenz Meier's avatar
Lorenz Meier committed
136 137 138 139 140 141 142 143 144 145 146 147 148 149
/**
 * @brief Encode a request_data_stream struct on a channel
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param request_data_stream C-struct to read the message contents from
 */
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)
{
	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);
}

James Goppert's avatar
James Goppert committed
150 151 152 153 154 155
/**
 * @brief Send a request_data_stream message
 * @param chan MAVLink channel to send the message
 *
 * @param target_system The target requested to send the message stream.
 * @param target_component The target requested to send the message stream.
156
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
157 158 159
 * @param req_message_rate The requested interval between two messages of this type
 * @param start_stop 1 to start sending, 0 to stop sending.
 */
lm's avatar
lm committed
160 161
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
162 163
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)
{
LM's avatar
LM committed
164
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
Lorenz Meier's avatar
Lorenz Meier committed
165
	char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
LM's avatar
LM committed
166 167 168 169 170 171
	_mav_put_uint16_t(buf, 0, req_message_rate);
	_mav_put_uint8_t(buf, 2, target_system);
	_mav_put_uint8_t(buf, 3, target_component);
	_mav_put_uint8_t(buf, 4, req_stream_id);
	_mav_put_uint8_t(buf, 5, start_stop);

Lorenz Meier's avatar
Lorenz Meier committed
172 173 174 175 176
#if MAVLINK_CRC_EXTRA
    _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);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
LM's avatar
LM committed
177 178 179 180 181 182 183 184
#else
	mavlink_request_data_stream_t packet;
	packet.req_message_rate = req_message_rate;
	packet.target_system = target_system;
	packet.target_component = target_component;
	packet.req_stream_id = req_stream_id;
	packet.start_stop = start_stop;

Lorenz Meier's avatar
Lorenz Meier committed
185 186 187 188 189
#if MAVLINK_CRC_EXTRA
    _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);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
LM's avatar
LM committed
190
#endif
James Goppert's avatar
James Goppert committed
191 192
}

193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232
#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This varient of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char *buf = (char *)msgbuf;
	_mav_put_uint16_t(buf, 0, req_message_rate);
	_mav_put_uint8_t(buf, 2, target_system);
	_mav_put_uint8_t(buf, 3, target_component);
	_mav_put_uint8_t(buf, 4, req_stream_id);
	_mav_put_uint8_t(buf, 5, start_stop);

#if MAVLINK_CRC_EXTRA
    _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);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#else
	mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf;
	packet->req_message_rate = req_message_rate;
	packet->target_system = target_system;
	packet->target_component = target_component;
	packet->req_stream_id = req_stream_id;
	packet->start_stop = start_stop;

#if MAVLINK_CRC_EXTRA
    _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);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#endif
}
#endif

James Goppert's avatar
James Goppert committed
233
#endif
lm's avatar
lm committed
234

James Goppert's avatar
James Goppert committed
235 236
// MESSAGE REQUEST_DATA_STREAM UNPACKING

lm's avatar
lm committed
237

James Goppert's avatar
James Goppert committed
238 239 240 241 242 243 244
/**
 * @brief Get field target_system from request_data_stream message
 *
 * @return The target requested to send the message stream.
 */
static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
{
LM's avatar
LM committed
245
	return _MAV_RETURN_uint8_t(msg,  2);
James Goppert's avatar
James Goppert committed
246 247 248 249 250 251 252 253 254
}

/**
 * @brief Get field target_component from request_data_stream message
 *
 * @return The target requested to send the message stream.
 */
static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
{
LM's avatar
LM committed
255
	return _MAV_RETURN_uint8_t(msg,  3);
James Goppert's avatar
James Goppert committed
256 257 258 259 260
}

/**
 * @brief Get field req_stream_id from request_data_stream message
 *
261
 * @return The ID of the requested data stream
James Goppert's avatar
James Goppert committed
262 263 264
 */
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
265
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
266 267 268 269 270 271 272 273 274
}

/**
 * @brief Get field req_message_rate from request_data_stream message
 *
 * @return The requested interval between two messages of this type
 */
static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
{
LM's avatar
LM committed
275
	return _MAV_RETURN_uint16_t(msg,  0);
James Goppert's avatar
James Goppert committed
276 277 278 279 280 281 282 283 284
}

/**
 * @brief Get field start_stop from request_data_stream message
 *
 * @return 1 to start sending, 0 to stop sending.
 */
static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
{
LM's avatar
LM committed
285
	return _MAV_RETURN_uint8_t(msg,  5);
James Goppert's avatar
James Goppert committed
286 287 288 289 290 291 292 293 294 295
}

/**
 * @brief Decode a request_data_stream message into a struct
 *
 * @param msg The message to decode
 * @param request_data_stream C-struct to decode the message contents into
 */
static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
{
lm's avatar
lm committed
296 297 298 299 300 301 302
#if MAVLINK_NEED_BYTE_SWAP
	request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
	request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
	request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
	request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
	request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
#else
Lorenz Meier's avatar
Lorenz Meier committed
303
	memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
lm's avatar
lm committed
304
#endif
James Goppert's avatar
James Goppert committed
305
}