Classes | Macros | Typedefs | Functions
mavlink_msg_rc_channels_scaled.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_scaled_t
 

Macros

#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED
 
#define MAVLINK_MSG_ID_34_CRC   237
 
#define MAVLINK_MSG_ID_34_LEN   22
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED   34
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC   237
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN   22
 

Typedefs

typedef struct __mavlink_rc_channels_scaled_t mavlink_rc_channels_scaled_t
 

Functions

static void mavlink_msg_rc_channels_scaled_decode (const mavlink_message_t *msg, mavlink_rc_channels_scaled_t *rc_channels_scaled)
 Decode a rc_channels_scaled message into a struct. More...
 
static uint16_t mavlink_msg_rc_channels_scaled_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_rc_channels_scaled_t *rc_channels_scaled)
 Encode a rc_channels_scaled struct. More...
 
static uint16_t mavlink_msg_rc_channels_scaled_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_rc_channels_scaled_t *rc_channels_scaled)
 Encode a rc_channels_scaled struct on a channel. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled (const mavlink_message_t *msg)
 Get field chan1_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled (const mavlink_message_t *msg)
 Get field chan2_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled (const mavlink_message_t *msg)
 Get field chan3_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled (const mavlink_message_t *msg)
 Get field chan4_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled (const mavlink_message_t *msg)
 Get field chan5_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled (const mavlink_message_t *msg)
 Get field chan6_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled (const mavlink_message_t *msg)
 Get field chan7_scaled from rc_channels_scaled message. More...
 
static int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled (const mavlink_message_t *msg)
 Get field chan8_scaled from rc_channels_scaled message. More...
 
static uint8_t mavlink_msg_rc_channels_scaled_get_port (const mavlink_message_t *msg)
 Get field port from rc_channels_scaled message. More...
 
static uint8_t mavlink_msg_rc_channels_scaled_get_rssi (const mavlink_message_t *msg)
 Get field rssi from rc_channels_scaled message. More...
 
static uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms (const mavlink_message_t *msg)
 Send a rc_channels_scaled message. More...
 
static uint16_t mavlink_msg_rc_channels_scaled_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
 Pack a rc_channels_scaled message. More...
 
static uint16_t mavlink_msg_rc_channels_scaled_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
 Pack a rc_channels_scaled message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED
Value:
{ \
"RC_CHANNELS_SCALED", \
11, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \
{ "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \
{ "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \
{ "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \
{ "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \
{ "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \
{ "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \
{ "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \
{ "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \
{ "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 28 of file mavlink_msg_rc_channels_scaled.h.

#define MAVLINK_MSG_ID_34_CRC   237

Definition at line 24 of file mavlink_msg_rc_channels_scaled.h.

#define MAVLINK_MSG_ID_34_LEN   22

Definition at line 21 of file mavlink_msg_rc_channels_scaled.h.

#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED   34

Definition at line 3 of file mavlink_msg_rc_channels_scaled.h.

#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC   237

Definition at line 23 of file mavlink_msg_rc_channels_scaled.h.

#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN   22

Definition at line 20 of file mavlink_msg_rc_channels_scaled.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_rc_channels_scaled_decode ( const mavlink_message_t *  msg,
mavlink_rc_channels_scaled_t rc_channels_scaled 
)
inlinestatic

Decode a rc_channels_scaled message into a struct.

Parameters
msgThe message to decode
rc_channels_scaledC-struct to decode the message contents into

Definition at line 432 of file mavlink_msg_rc_channels_scaled.h.

static uint16_t mavlink_msg_rc_channels_scaled_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_rc_channels_scaled_t rc_channels_scaled 
)
inlinestatic

Encode a rc_channels_scaled 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_channels_scaledC-struct to read the message contents from

Definition at line 179 of file mavlink_msg_rc_channels_scaled.h.

static uint16_t mavlink_msg_rc_channels_scaled_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_rc_channels_scaled_t rc_channels_scaled 
)
inlinestatic

Encode a rc_channels_scaled 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_channels_scaledC-struct to read the message contents from

Definition at line 193 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan1_scaled from rc_channels_scaled message.

Returns
RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 341 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan2_scaled from rc_channels_scaled message.

Returns
RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 351 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan3_scaled from rc_channels_scaled message.

Returns
RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 361 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan4_scaled from rc_channels_scaled message.

Returns
RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 371 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan5_scaled from rc_channels_scaled message.

Returns
RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 381 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan6_scaled from rc_channels_scaled message.

Returns
RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 391 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan7_scaled from rc_channels_scaled message.

Returns
RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 401 of file mavlink_msg_rc_channels_scaled.h.

static int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled ( const mavlink_message_t *  msg)
inlinestatic

Get field chan8_scaled from rc_channels_scaled message.

Returns
RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.

Definition at line 411 of file mavlink_msg_rc_channels_scaled.h.

static uint8_t mavlink_msg_rc_channels_scaled_get_port ( const mavlink_message_t *  msg)
inlinestatic

Get field port from rc_channels_scaled message.

Returns
Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.

Definition at line 331 of file mavlink_msg_rc_channels_scaled.h.

static uint8_t mavlink_msg_rc_channels_scaled_get_rssi ( const mavlink_message_t *  msg)
inlinestatic

Get field rssi from rc_channels_scaled message.

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

Definition at line 421 of file mavlink_msg_rc_channels_scaled.h.

static uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a rc_channels_scaled message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
portServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
chan1_scaledRC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan2_scaledRC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan3_scaledRC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan4_scaledRC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan5_scaledRC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan6_scaledRC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan7_scaledRC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan8_scaledRC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
rssiReceive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. Get field time_boot_ms from rc_channels_scaled message
Returns
Timestamp (milliseconds since system boot)

Definition at line 321 of file mavlink_msg_rc_channels_scaled.h.

static uint16_t mavlink_msg_rc_channels_scaled_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  port,
int16_t  chan1_scaled,
int16_t  chan2_scaled,
int16_t  chan3_scaled,
int16_t  chan4_scaled,
int16_t  chan5_scaled,
int16_t  chan6_scaled,
int16_t  chan7_scaled,
int16_t  chan8_scaled,
uint8_t  rssi 
)
inlinestatic

Pack a rc_channels_scaled 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)
portServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
chan1_scaledRC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan2_scaledRC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan3_scaledRC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan4_scaledRC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan5_scaledRC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan6_scaledRC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan7_scaledRC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan8_scaledRC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
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 65 of file mavlink_msg_rc_channels_scaled.h.

static uint16_t mavlink_msg_rc_channels_scaled_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint8_t  port,
int16_t  chan1_scaled,
int16_t  chan2_scaled,
int16_t  chan3_scaled,
int16_t  chan4_scaled,
int16_t  chan5_scaled,
int16_t  chan6_scaled,
int16_t  chan7_scaled,
int16_t  chan8_scaled,
uint8_t  rssi 
)
inlinestatic

Pack a rc_channels_scaled 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)
portServo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
chan1_scaledRC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan2_scaledRC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan3_scaledRC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan4_scaledRC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan5_scaledRC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan6_scaledRC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan7_scaledRC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
chan8_scaledRC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
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 127 of file mavlink_msg_rc_channels_scaled.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:27