Classes | Defines | Typedefs | Functions
mavlink_msg_rc_channels.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_rc_channels_t

Defines

#define MAVLINK_MESSAGE_INFO_RC_CHANNELS
#define MAVLINK_MSG_ID_65_CRC   118
#define MAVLINK_MSG_ID_65_LEN   42
#define MAVLINK_MSG_ID_RC_CHANNELS   65
#define MAVLINK_MSG_ID_RC_CHANNELS_CRC   118
#define MAVLINK_MSG_ID_RC_CHANNELS_LEN   42

Typedefs

typedef struct
__mavlink_rc_channels_t 
mavlink_rc_channels_t

Functions

static void mavlink_msg_rc_channels_decode (const mavlink_message_t *msg, mavlink_rc_channels_t *rc_channels)
 Decode a rc_channels message into a struct.
static uint16_t mavlink_msg_rc_channels_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rc_channels_t *rc_channels)
 Encode a rc_channels struct.
static uint16_t mavlink_msg_rc_channels_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rc_channels_t *rc_channels)
 Encode a rc_channels struct on a channel.
static uint16_t mavlink_msg_rc_channels_get_chan10_raw (const mavlink_message_t *msg)
 Get field chan10_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan11_raw (const mavlink_message_t *msg)
 Get field chan11_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan12_raw (const mavlink_message_t *msg)
 Get field chan12_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan13_raw (const mavlink_message_t *msg)
 Get field chan13_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan14_raw (const mavlink_message_t *msg)
 Get field chan14_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan15_raw (const mavlink_message_t *msg)
 Get field chan15_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan16_raw (const mavlink_message_t *msg)
 Get field chan16_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan17_raw (const mavlink_message_t *msg)
 Get field chan17_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan18_raw (const mavlink_message_t *msg)
 Get field chan18_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan1_raw (const mavlink_message_t *msg)
 Get field chan1_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan2_raw (const mavlink_message_t *msg)
 Get field chan2_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan3_raw (const mavlink_message_t *msg)
 Get field chan3_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan4_raw (const mavlink_message_t *msg)
 Get field chan4_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan5_raw (const mavlink_message_t *msg)
 Get field chan5_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan6_raw (const mavlink_message_t *msg)
 Get field chan6_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan7_raw (const mavlink_message_t *msg)
 Get field chan7_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan8_raw (const mavlink_message_t *msg)
 Get field chan8_raw from rc_channels message.
static uint16_t mavlink_msg_rc_channels_get_chan9_raw (const mavlink_message_t *msg)
 Get field chan9_raw from rc_channels message.
static uint8_t mavlink_msg_rc_channels_get_chancount (const mavlink_message_t *msg)
 Get field chancount from rc_channels message.
static uint8_t mavlink_msg_rc_channels_get_rssi (const mavlink_message_t *msg)
 Get field rssi from rc_channels message.
static uint32_t mavlink_msg_rc_channels_get_time_boot_ms (const mavlink_message_t *msg)
 Send a rc_channels message.
static uint16_t mavlink_msg_rc_channels_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
 Pack a rc_channels message.
static uint16_t mavlink_msg_rc_channels_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
 Pack a rc_channels message on a channel.

Define Documentation

Value:
{ \
        "RC_CHANNELS", \
        21, \
        {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
         { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
         { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
         { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
         { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
         { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
         { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
         { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
         { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
         { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
         { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
         { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
         { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
         { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
         { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
         { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
         { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
         { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
         { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
         { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
         { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
         } \
}

Definition at line 38 of file mavlink_msg_rc_channels.h.

#define MAVLINK_MSG_ID_65_CRC   118

Definition at line 34 of file mavlink_msg_rc_channels.h.

#define MAVLINK_MSG_ID_65_LEN   42

Definition at line 31 of file mavlink_msg_rc_channels.h.

#define MAVLINK_MSG_ID_RC_CHANNELS   65

Definition at line 3 of file mavlink_msg_rc_channels.h.

Definition at line 33 of file mavlink_msg_rc_channels.h.

Definition at line 30 of file mavlink_msg_rc_channels.h.


Typedef Documentation


Function Documentation

static void mavlink_msg_rc_channels_decode ( const mavlink_message_t msg,
mavlink_rc_channels_t rc_channels 
) [inline, static]

Decode a rc_channels message into a struct.

Parameters:
msgThe message to decode
rc_channelsC-struct to decode the message contents into

Definition at line 662 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
const mavlink_rc_channels_t rc_channels 
) [inline, static]

Encode a rc_channels struct.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
rc_channelsC-struct to read the message contents from

Definition at line 259 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
const mavlink_rc_channels_t rc_channels 
) [inline, static]

Encode a rc_channels struct on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
rc_channelsC-struct to read the message contents from

Definition at line 273 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan10_raw ( const mavlink_message_t msg) [inline, static]

Get field chan10_raw from rc_channels message.

Returns:
RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 561 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan11_raw ( const mavlink_message_t msg) [inline, static]

Get field chan11_raw from rc_channels message.

Returns:
RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 571 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan12_raw ( const mavlink_message_t msg) [inline, static]

Get field chan12_raw from rc_channels message.

Returns:
RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 581 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan13_raw ( const mavlink_message_t msg) [inline, static]

Get field chan13_raw from rc_channels message.

Returns:
RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 591 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan14_raw ( const mavlink_message_t msg) [inline, static]

Get field chan14_raw from rc_channels message.

Returns:
RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 601 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan15_raw ( const mavlink_message_t msg) [inline, static]

Get field chan15_raw from rc_channels message.

Returns:
RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 611 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan16_raw ( const mavlink_message_t msg) [inline, static]

Get field chan16_raw from rc_channels message.

Returns:
RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 621 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan17_raw ( const mavlink_message_t msg) [inline, static]

Get field chan17_raw from rc_channels message.

Returns:
RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 631 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan18_raw ( const mavlink_message_t msg) [inline, static]

Get field chan18_raw from rc_channels message.

Returns:
RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 641 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan1_raw ( const mavlink_message_t msg) [inline, static]

Get field chan1_raw from rc_channels message.

Returns:
RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 471 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan2_raw ( const mavlink_message_t msg) [inline, static]

Get field chan2_raw from rc_channels message.

Returns:
RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 481 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan3_raw ( const mavlink_message_t msg) [inline, static]

Get field chan3_raw from rc_channels message.

Returns:
RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 491 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan4_raw ( const mavlink_message_t msg) [inline, static]

Get field chan4_raw from rc_channels message.

Returns:
RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 501 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan5_raw ( const mavlink_message_t msg) [inline, static]

Get field chan5_raw from rc_channels message.

Returns:
RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 511 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan6_raw ( const mavlink_message_t msg) [inline, static]

Get field chan6_raw from rc_channels message.

Returns:
RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 521 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan7_raw ( const mavlink_message_t msg) [inline, static]

Get field chan7_raw from rc_channels message.

Returns:
RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 531 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan8_raw ( const mavlink_message_t msg) [inline, static]

Get field chan8_raw from rc_channels message.

Returns:
RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 541 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_get_chan9_raw ( const mavlink_message_t msg) [inline, static]

Get field chan9_raw from rc_channels message.

Returns:
RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.

Definition at line 551 of file mavlink_msg_rc_channels.h.

static uint8_t mavlink_msg_rc_channels_get_chancount ( const mavlink_message_t msg) [inline, static]

Get field chancount from rc_channels message.

Returns:
Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.

Definition at line 461 of file mavlink_msg_rc_channels.h.

static uint8_t mavlink_msg_rc_channels_get_rssi ( const mavlink_message_t msg) [inline, static]

Get field rssi from rc_channels message.

Returns:
Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.

Definition at line 651 of file mavlink_msg_rc_channels.h.

static uint32_t mavlink_msg_rc_channels_get_time_boot_ms ( const mavlink_message_t msg) [inline, static]

Send a rc_channels message.

Parameters:
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
chancountTotal number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
chan1_rawRC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan2_rawRC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan3_rawRC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan4_rawRC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan5_rawRC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan6_rawRC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan7_rawRC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan8_rawRC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan9_rawRC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan10_rawRC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan11_rawRC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan12_rawRC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan13_rawRC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan14_rawRC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan15_rawRC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan16_rawRC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan17_rawRC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan18_rawRC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
rssiReceive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. Get field time_boot_ms from rc_channels message
Returns:
Timestamp (milliseconds since system boot)

Definition at line 451 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t msg,
uint32_t  time_boot_ms,
uint8_t  chancount,
uint16_t  chan1_raw,
uint16_t  chan2_raw,
uint16_t  chan3_raw,
uint16_t  chan4_raw,
uint16_t  chan5_raw,
uint16_t  chan6_raw,
uint16_t  chan7_raw,
uint16_t  chan8_raw,
uint16_t  chan9_raw,
uint16_t  chan10_raw,
uint16_t  chan11_raw,
uint16_t  chan12_raw,
uint16_t  chan13_raw,
uint16_t  chan14_raw,
uint16_t  chan15_raw,
uint16_t  chan16_raw,
uint16_t  chan17_raw,
uint16_t  chan18_raw,
uint8_t  rssi 
) [inline, static]

Pack a rc_channels message.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
time_boot_msTimestamp (milliseconds since system boot)
chancountTotal number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
chan1_rawRC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan2_rawRC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan3_rawRC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan4_rawRC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan5_rawRC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan6_rawRC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan7_rawRC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan8_rawRC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan9_rawRC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan10_rawRC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan11_rawRC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan12_rawRC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan13_rawRC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan14_rawRC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan15_rawRC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan16_rawRC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan17_rawRC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan18_rawRC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
rssiReceive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 95 of file mavlink_msg_rc_channels.h.

static uint16_t mavlink_msg_rc_channels_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t msg,
uint32_t  time_boot_ms,
uint8_t  chancount,
uint16_t  chan1_raw,
uint16_t  chan2_raw,
uint16_t  chan3_raw,
uint16_t  chan4_raw,
uint16_t  chan5_raw,
uint16_t  chan6_raw,
uint16_t  chan7_raw,
uint16_t  chan8_raw,
uint16_t  chan9_raw,
uint16_t  chan10_raw,
uint16_t  chan11_raw,
uint16_t  chan12_raw,
uint16_t  chan13_raw,
uint16_t  chan14_raw,
uint16_t  chan15_raw,
uint16_t  chan16_raw,
uint16_t  chan17_raw,
uint16_t  chan18_raw,
uint8_t  rssi 
) [inline, static]

Pack a rc_channels message on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
time_boot_msTimestamp (milliseconds since system boot)
chancountTotal number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
chan1_rawRC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan2_rawRC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan3_rawRC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan4_rawRC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan5_rawRC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan6_rawRC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan7_rawRC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan8_rawRC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan9_rawRC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan10_rawRC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan11_rawRC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan12_rawRC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan13_rawRC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan14_rawRC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan15_rawRC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan16_rawRC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan17_rawRC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
chan18_rawRC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
rssiReceive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
Returns:
length of the message in bytes (excluding serial stream start sign)

Definition at line 187 of file mavlink_msg_rc_channels.h.



dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:36