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) }, \ 50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 92 mavlink_message_t* msg,
95 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 116 #if MAVLINK_CRC_EXTRA 160 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 164 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 172 #if MAVLINK_CRC_EXTRA 185 #if MAVLINK_CRC_EXTRA 193 #if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN 203 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 204 char *buf = (
char *)msgbuf;
211 #if MAVLINK_CRC_EXTRA 224 #if MAVLINK_CRC_EXTRA 275 return _MAV_RETURN_uint16_t(msg, 0);
296 #if MAVLINK_NEED_BYTE_SWAP #define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC
static 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)
Pack a request_data_stream message on a channel.
static uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t *msg)
Send a request_data_stream message.
static 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)
Encode a request_data_stream struct on a channel.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static void mavlink_msg_request_data_stream_decode(const mavlink_message_t *msg, mavlink_request_data_stream_t *request_data_stream)
Decode a request_data_stream message into a struct.
static uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t *msg)
Get field req_message_rate from request_data_stream message.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
struct __mavlink_request_data_stream_t mavlink_request_data_stream_t
static uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t *msg)
Get field req_stream_id from request_data_stream message.
#define _MAV_PAYLOAD(msg)
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN
static 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)
Encode a request_data_stream struct.
uint16_t req_message_rate
static uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t *msg)
Get field start_stop from request_data_stream message.
static uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t *msg)
Get field target_component from request_data_stream message.
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM
#define _mav_put_uint16_t(buf, wire_offset, b)
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.
static 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)
Pack a request_data_stream message.