Go to the source code of this file.
Classes | |
struct | __mavlink_data_stream_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_DATA_STREAM |
#define | MAVLINK_MSG_ID_67_CRC 21 |
#define | MAVLINK_MSG_ID_67_LEN 4 |
#define | MAVLINK_MSG_ID_DATA_STREAM 67 |
#define | MAVLINK_MSG_ID_DATA_STREAM_CRC 21 |
#define | MAVLINK_MSG_ID_DATA_STREAM_LEN 4 |
Typedefs | |
typedef struct __mavlink_data_stream_t | mavlink_data_stream_t |
Functions | |
static void | mavlink_msg_data_stream_decode (const mavlink_message_t *msg, mavlink_data_stream_t *data_stream) |
Decode a data_stream message into a struct. | |
static 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) |
Encode a data_stream struct. | |
static 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) |
Encode a data_stream struct on a channel. | |
static uint16_t | mavlink_msg_data_stream_get_message_rate (const mavlink_message_t *msg) |
Get field message_rate from data_stream message. | |
static uint8_t | mavlink_msg_data_stream_get_on_off (const mavlink_message_t *msg) |
Get field on_off from data_stream message. | |
static uint8_t | mavlink_msg_data_stream_get_stream_id (const mavlink_message_t *msg) |
Send a data_stream message. | |
static uint16_t | mavlink_msg_data_stream_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) |
Pack a data_stream message. | |
static uint16_t | mavlink_msg_data_stream_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) |
Pack a data_stream message on a channel. |
#define MAVLINK_MESSAGE_INFO_DATA_STREAM |
{ \ "DATA_STREAM", \ 3, \ { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ } \ }
Definition at line 20 of file mavlink_msg_data_stream.h.
#define MAVLINK_MSG_ID_67_CRC 21 |
Definition at line 16 of file mavlink_msg_data_stream.h.
#define MAVLINK_MSG_ID_67_LEN 4 |
Definition at line 13 of file mavlink_msg_data_stream.h.
#define MAVLINK_MSG_ID_DATA_STREAM 67 |
Definition at line 3 of file mavlink_msg_data_stream.h.
#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 |
Definition at line 15 of file mavlink_msg_data_stream.h.
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 |
Definition at line 12 of file mavlink_msg_data_stream.h.
typedef struct __mavlink_data_stream_t mavlink_data_stream_t |
static void mavlink_msg_data_stream_decode | ( | const mavlink_message_t * | msg, |
mavlink_data_stream_t * | data_stream | ||
) | [inline, static] |
Decode a data_stream message into a struct.
msg | The message to decode |
data_stream | C-struct to decode the message contents into |
Definition at line 248 of file mavlink_msg_data_stream.h.
static 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 | ||
) | [inline, static] |
Encode a data_stream struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
data_stream | C-struct to read the message contents from |
Definition at line 115 of file mavlink_msg_data_stream.h.
static 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 | ||
) | [inline, static] |
Encode a data_stream struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
data_stream | C-struct to read the message contents from |
Definition at line 129 of file mavlink_msg_data_stream.h.
static uint16_t mavlink_msg_data_stream_get_message_rate | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field message_rate from data_stream message.
Definition at line 227 of file mavlink_msg_data_stream.h.
static uint8_t mavlink_msg_data_stream_get_on_off | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field on_off from data_stream message.
Definition at line 237 of file mavlink_msg_data_stream.h.
static uint8_t mavlink_msg_data_stream_get_stream_id | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a data_stream message.
chan | MAVLink channel to send the message |
stream_id | The ID of the requested data stream |
message_rate | The message rate |
on_off | 1 stream is enabled, 0 stream is stopped. Get field stream_id from data_stream message |
Definition at line 217 of file mavlink_msg_data_stream.h.
static uint16_t mavlink_msg_data_stream_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint8_t | stream_id, | ||
uint16_t | message_rate, | ||
uint8_t | on_off | ||
) | [inline, static] |
Pack a data_stream message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
stream_id | The ID of the requested data stream |
message_rate | The message rate |
on_off | 1 stream is enabled, 0 stream is stopped. |
Definition at line 41 of file mavlink_msg_data_stream.h.
static uint16_t mavlink_msg_data_stream_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint8_t | stream_id, | ||
uint16_t | message_rate, | ||
uint8_t | on_off | ||
) | [inline, static] |
Pack a data_stream message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
stream_id | The ID of the requested data stream |
message_rate | The message rate |
on_off | 1 stream is enabled, 0 stream is stopped. |
Definition at line 79 of file mavlink_msg_data_stream.h.