3 #define MAVLINK_MSG_ID_DATA_STREAM 67
12 #define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
13 #define MAVLINK_MSG_ID_67_LEN 4
15 #define MAVLINK_MSG_ID_DATA_STREAM_CRC 21
16 #define MAVLINK_MSG_ID_67_CRC 21
20 #define MAVLINK_MESSAGE_INFO_DATA_STREAM { \
23 { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
24 { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
25 { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \
41 static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42 uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
44 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
80 mavlink_message_t* msg,
81 uint8_t stream_id,uint16_t message_rate,uint8_t on_off)
83 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 #if MAVLINK_CRC_EXTRA
115 static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_data_stream_t* data_stream)
117 return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->
stream_id, data_stream->
message_rate, data_stream->
on_off);
129 static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_data_stream_t* data_stream)
131 return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->
stream_id, data_stream->
message_rate, data_stream->
on_off);
142 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
144 static inline void mavlink_msg_data_stream_send(
mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
146 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
152 #if MAVLINK_CRC_EXTRA
163 #if MAVLINK_CRC_EXTRA
171 #if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
179 static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
181 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 char *buf = (
char *)msgbuf;
187 #if MAVLINK_CRC_EXTRA
198 #if MAVLINK_CRC_EXTRA
217 static inline uint8_t mavlink_msg_data_stream_get_stream_id(
const mavlink_message_t* msg)
227 static inline uint16_t mavlink_msg_data_stream_get_message_rate(
const mavlink_message_t* msg)
229 return _MAV_RETURN_uint16_t(msg, 0);
237 static inline uint8_t mavlink_msg_data_stream_get_on_off(
const mavlink_message_t* msg)
248 static inline void mavlink_msg_data_stream_decode(
const mavlink_message_t* msg,
mavlink_data_stream_t* data_stream)
250 #if MAVLINK_NEED_BYTE_SWAP
251 data_stream->
message_rate = mavlink_msg_data_stream_get_message_rate(msg);
252 data_stream->
stream_id = mavlink_msg_data_stream_get_stream_id(msg);
253 data_stream->
on_off = mavlink_msg_data_stream_get_on_off(msg);
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
#define MAVLINK_MSG_ID_DATA_STREAM_LEN
Definition: mavlink_msg_data_stream.h:12
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 MAVLINK_MSG_ID_DATA_STREAM
Definition: mavlink_msg_data_stream.h:3
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
uint8_t on_off
1 stream is enabled, 0 stream is stopped.
Definition: mavlink_msg_data_stream.h:9
mavlink_channel_t
Definition: mavlink_types.h:178
uint16_t message_rate
The requested interval between two messages of this type.
Definition: mavlink_msg_data_stream.h:7
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
#define MAVLINK_MSG_ID_DATA_STREAM_CRC
Definition: mavlink_msg_data_stream.h:15
struct __mavlink_data_stream_t mavlink_data_stream_t
Definition: mavlink_msg_data_stream.h:5
#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
uint8_t stream_id
The ID of the requested data stream.
Definition: mavlink_msg_data_stream.h:8