mavlink_msg_request_data_stream.h 9.15 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 17 18 19 20 21
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
#define MAVLINK_MSG_ID_66_LEN 6



#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
	"REQUEST_DATA_STREAM", \
	5, \
lm's avatar
lm committed
22 23 24 25 26
	{  { "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
27 28 29 30
         } \
}


James Goppert's avatar
James Goppert committed
31 32 33 34 35 36 37 38
/**
 * @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.
39
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
40 41 42 43
 * @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
44 45
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
46
{
LM's avatar
LM committed
47 48 49 50 51 52 53 54
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_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);

55
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
LM's avatar
LM committed
56 57 58 59 60 61 62 63
#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;

64
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
LM's avatar
LM committed
65
#endif
James Goppert's avatar
James Goppert committed
66

LM's avatar
LM committed
67
	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
lm's avatar
lm committed
68
	return mavlink_finalize_message(msg, system_id, component_id, 6, 148);
James Goppert's avatar
James Goppert committed
69 70 71
}

/**
lm's avatar
lm committed
72
 * @brief Pack a request_data_stream message on a channel
James Goppert's avatar
James Goppert committed
73 74 75 76 77 78
 * @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 was sent over
 * @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.
79
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
80 81 82 83
 * @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
84 85 86
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
87
{
LM's avatar
LM committed
88 89 90 91 92 93 94 95
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_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);

96
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
LM's avatar
LM committed
97 98 99 100 101 102 103 104
#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;

105
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
LM's avatar
LM committed
106
#endif
James Goppert's avatar
James Goppert committed
107

LM's avatar
LM committed
108
	msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
lm's avatar
lm committed
109
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 148);
James Goppert's avatar
James Goppert committed
110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130
}

/**
 * @brief Encode a request_data_stream struct into a 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 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);
}

/**
 * @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.
131
 * @param req_stream_id The ID of the requested data stream
James Goppert's avatar
James Goppert committed
132 133 134
 * @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
135 136
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
137 138
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
139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[6];
	_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);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6, 148);
#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;

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6, 148);
#endif
James Goppert's avatar
James Goppert committed
158 159 160
}

#endif
lm's avatar
lm committed
161

James Goppert's avatar
James Goppert committed
162 163
// MESSAGE REQUEST_DATA_STREAM UNPACKING

lm's avatar
lm committed
164

James Goppert's avatar
James Goppert committed
165 166 167 168 169 170 171
/**
 * @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
172
	return _MAV_RETURN_uint8_t(msg,  2);
James Goppert's avatar
James Goppert committed
173 174 175 176 177 178 179 180 181
}

/**
 * @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
182
	return _MAV_RETURN_uint8_t(msg,  3);
James Goppert's avatar
James Goppert committed
183 184 185 186 187
}

/**
 * @brief Get field req_stream_id from request_data_stream message
 *
188
 * @return The ID of the requested data stream
James Goppert's avatar
James Goppert committed
189 190 191
 */
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
LM's avatar
LM committed
192
	return _MAV_RETURN_uint8_t(msg,  4);
James Goppert's avatar
James Goppert committed
193 194 195 196 197 198 199 200 201
}

/**
 * @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
202
	return _MAV_RETURN_uint16_t(msg,  0);
James Goppert's avatar
James Goppert committed
203 204 205 206 207 208 209 210 211
}

/**
 * @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
212
	return _MAV_RETURN_uint8_t(msg,  5);
James Goppert's avatar
James Goppert committed
213 214 215 216 217 218 219 220 221 222
}

/**
 * @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
223 224 225 226 227 228 229
#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
LM's avatar
LM committed
230
	memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6);
lm's avatar
lm committed
231
#endif
James Goppert's avatar
James Goppert committed
232
}