Classes | Macros | Typedefs | Functions
mavlink_msg_manual_control.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_manual_control_t
 

Macros

#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL
 
#define MAVLINK_MSG_ID_69_CRC   243
 
#define MAVLINK_MSG_ID_69_LEN   11
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL   69
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC   243
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN   11
 

Typedefs

typedef struct __mavlink_manual_control_t mavlink_manual_control_t
 

Functions

static void mavlink_msg_manual_control_decode (const mavlink_message_t *msg, mavlink_manual_control_t *manual_control)
 Decode a manual_control message into a struct. More...
 
static uint16_t mavlink_msg_manual_control_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_manual_control_t *manual_control)
 Encode a manual_control struct. More...
 
static uint16_t mavlink_msg_manual_control_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_manual_control_t *manual_control)
 Encode a manual_control struct on a channel. More...
 
static uint16_t mavlink_msg_manual_control_get_buttons (const mavlink_message_t *msg)
 Get field buttons from manual_control message. More...
 
static int16_t mavlink_msg_manual_control_get_r (const mavlink_message_t *msg)
 Get field r from manual_control message. More...
 
static uint8_t mavlink_msg_manual_control_get_target (const mavlink_message_t *msg)
 Send a manual_control message. More...
 
static int16_t mavlink_msg_manual_control_get_x (const mavlink_message_t *msg)
 Get field x from manual_control message. More...
 
static int16_t mavlink_msg_manual_control_get_y (const mavlink_message_t *msg)
 Get field y from manual_control message. More...
 
static int16_t mavlink_msg_manual_control_get_z (const mavlink_message_t *msg)
 Get field z from manual_control message. More...
 
static uint16_t mavlink_msg_manual_control_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
 Pack a manual_control message. More...
 
static uint16_t mavlink_msg_manual_control_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
 Pack a manual_control message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL
Value:
{ \
"MANUAL_CONTROL", \
6, \
{ { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \
{ "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \
{ "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 23 of file mavlink_msg_manual_control.h.

#define MAVLINK_MSG_ID_69_CRC   243

Definition at line 19 of file mavlink_msg_manual_control.h.

#define MAVLINK_MSG_ID_69_LEN   11

Definition at line 16 of file mavlink_msg_manual_control.h.

#define MAVLINK_MSG_ID_MANUAL_CONTROL   69

Definition at line 3 of file mavlink_msg_manual_control.h.

#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC   243

Definition at line 18 of file mavlink_msg_manual_control.h.

#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN   11

Definition at line 15 of file mavlink_msg_manual_control.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_manual_control_decode ( const mavlink_message_t *  msg,
mavlink_manual_control_t manual_control 
)
inlinestatic

Decode a manual_control message into a struct.

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

Definition at line 317 of file mavlink_msg_manual_control.h.

static uint16_t mavlink_msg_manual_control_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_manual_control_t manual_control 
)
inlinestatic

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

Definition at line 139 of file mavlink_msg_manual_control.h.

static uint16_t mavlink_msg_manual_control_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_manual_control_t manual_control 
)
inlinestatic

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

Definition at line 153 of file mavlink_msg_manual_control.h.

static uint16_t mavlink_msg_manual_control_get_buttons ( const mavlink_message_t *  msg)
inlinestatic

Get field buttons from manual_control message.

Returns
A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.

Definition at line 306 of file mavlink_msg_manual_control.h.

static int16_t mavlink_msg_manual_control_get_r ( const mavlink_message_t *  msg)
inlinestatic

Get field r from manual_control message.

Returns
R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.

Definition at line 296 of file mavlink_msg_manual_control.h.

static uint8_t mavlink_msg_manual_control_get_target ( const mavlink_message_t *  msg)
inlinestatic

Send a manual_control message.

Parameters
chanMAVLink channel to send the message
targetThe system to be controlled.
xX-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
yY-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
zZ-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
rR-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
buttonsA bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. Get field target from manual_control message
Returns
The system to be controlled.

Definition at line 256 of file mavlink_msg_manual_control.h.

static int16_t mavlink_msg_manual_control_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from manual_control message.

Returns
X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.

Definition at line 266 of file mavlink_msg_manual_control.h.

static int16_t mavlink_msg_manual_control_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from manual_control message.

Returns
Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.

Definition at line 276 of file mavlink_msg_manual_control.h.

static int16_t mavlink_msg_manual_control_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from manual_control message.

Returns
Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.

Definition at line 286 of file mavlink_msg_manual_control.h.

static uint16_t mavlink_msg_manual_control_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint8_t  target,
int16_t  x,
int16_t  y,
int16_t  z,
int16_t  r,
uint16_t  buttons 
)
inlinestatic

Pack a manual_control 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
targetThe system to be controlled.
xX-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
yY-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
zZ-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
rR-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
buttonsA bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 50 of file mavlink_msg_manual_control.h.

static uint16_t mavlink_msg_manual_control_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint8_t  target,
int16_t  x,
int16_t  y,
int16_t  z,
int16_t  r,
uint16_t  buttons 
)
inlinestatic

Pack a manual_control 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
targetThe system to be controlled.
xX-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
yY-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
zZ-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
rR-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
buttonsA bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 97 of file mavlink_msg_manual_control.h.



rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:51