Classes | Macros | Typedefs | Functions
mavlink_msg_manual_setpoint.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_setpoint_t
 

Macros

#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT
 
#define MAVLINK_MSG_ID_81_CRC   106
 
#define MAVLINK_MSG_ID_81_LEN   22
 
#define MAVLINK_MSG_ID_MANUAL_SETPOINT   81
 
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC   106
 
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN   22
 

Typedefs

typedef struct __mavlink_manual_setpoint_t mavlink_manual_setpoint_t
 

Functions

static void mavlink_msg_manual_setpoint_decode (const mavlink_message_t *msg, mavlink_manual_setpoint_t *manual_setpoint)
 Decode a manual_setpoint message into a struct. More...
 
static uint16_t mavlink_msg_manual_setpoint_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_manual_setpoint_t *manual_setpoint)
 Encode a manual_setpoint struct. More...
 
static uint16_t mavlink_msg_manual_setpoint_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_manual_setpoint_t *manual_setpoint)
 Encode a manual_setpoint struct on a channel. More...
 
static uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch (const mavlink_message_t *msg)
 Get field manual_override_switch from manual_setpoint message. More...
 
static uint8_t mavlink_msg_manual_setpoint_get_mode_switch (const mavlink_message_t *msg)
 Get field mode_switch from manual_setpoint message. More...
 
static float mavlink_msg_manual_setpoint_get_pitch (const mavlink_message_t *msg)
 Get field pitch from manual_setpoint message. More...
 
static float mavlink_msg_manual_setpoint_get_roll (const mavlink_message_t *msg)
 Get field roll from manual_setpoint message. More...
 
static float mavlink_msg_manual_setpoint_get_thrust (const mavlink_message_t *msg)
 Get field thrust from manual_setpoint message. More...
 
static uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms (const mavlink_message_t *msg)
 Send a manual_setpoint message. More...
 
static float mavlink_msg_manual_setpoint_get_yaw (const mavlink_message_t *msg)
 Get field yaw from manual_setpoint message. More...
 
static uint16_t mavlink_msg_manual_setpoint_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
 Pack a manual_setpoint message. More...
 
static uint16_t mavlink_msg_manual_setpoint_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
 Pack a manual_setpoint message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT
Value:
{ \
"MANUAL_SETPOINT", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \
{ "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \
{ "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_manual_setpoint.h.

#define MAVLINK_MSG_ID_81_CRC   106

Definition at line 20 of file mavlink_msg_manual_setpoint.h.

#define MAVLINK_MSG_ID_81_LEN   22

Definition at line 17 of file mavlink_msg_manual_setpoint.h.

#define MAVLINK_MSG_ID_MANUAL_SETPOINT   81

Definition at line 3 of file mavlink_msg_manual_setpoint.h.

#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC   106

Definition at line 19 of file mavlink_msg_manual_setpoint.h.

#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN   22

Definition at line 16 of file mavlink_msg_manual_setpoint.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_manual_setpoint_decode ( const mavlink_message_t *  msg,
mavlink_manual_setpoint_t manual_setpoint 
)
inlinestatic

Decode a manual_setpoint message into a struct.

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

Definition at line 340 of file mavlink_msg_manual_setpoint.h.

static uint16_t mavlink_msg_manual_setpoint_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_manual_setpoint_t manual_setpoint 
)
inlinestatic

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

Definition at line 147 of file mavlink_msg_manual_setpoint.h.

static uint16_t mavlink_msg_manual_setpoint_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_manual_setpoint_t manual_setpoint 
)
inlinestatic

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

Definition at line 161 of file mavlink_msg_manual_setpoint.h.

static uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch ( const mavlink_message_t *  msg)
inlinestatic

Get field manual_override_switch from manual_setpoint message.

Returns
Override mode switch position, 0.. 255

Definition at line 329 of file mavlink_msg_manual_setpoint.h.

static uint8_t mavlink_msg_manual_setpoint_get_mode_switch ( const mavlink_message_t *  msg)
inlinestatic

Get field mode_switch from manual_setpoint message.

Returns
Flight mode switch position, 0.. 255

Definition at line 319 of file mavlink_msg_manual_setpoint.h.

static float mavlink_msg_manual_setpoint_get_pitch ( const mavlink_message_t *  msg)
inlinestatic

Get field pitch from manual_setpoint message.

Returns
Desired pitch rate in radians per second

Definition at line 289 of file mavlink_msg_manual_setpoint.h.

static float mavlink_msg_manual_setpoint_get_roll ( const mavlink_message_t *  msg)
inlinestatic

Get field roll from manual_setpoint message.

Returns
Desired roll rate in radians per second

Definition at line 279 of file mavlink_msg_manual_setpoint.h.

static float mavlink_msg_manual_setpoint_get_thrust ( const mavlink_message_t *  msg)
inlinestatic

Get field thrust from manual_setpoint message.

Returns
Collective thrust, normalized to 0 .. 1

Definition at line 309 of file mavlink_msg_manual_setpoint.h.

static uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a manual_setpoint message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp in milliseconds since system boot
rollDesired roll rate in radians per second
pitchDesired pitch rate in radians per second
yawDesired yaw rate in radians per second
thrustCollective thrust, normalized to 0 .. 1
mode_switchFlight mode switch position, 0.. 255
manual_override_switchOverride mode switch position, 0.. 255 Get field time_boot_ms from manual_setpoint message
Returns
Timestamp in milliseconds since system boot

Definition at line 269 of file mavlink_msg_manual_setpoint.h.

static float mavlink_msg_manual_setpoint_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from manual_setpoint message.

Returns
Desired yaw rate in radians per second

Definition at line 299 of file mavlink_msg_manual_setpoint.h.

static uint16_t mavlink_msg_manual_setpoint_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
float  roll,
float  pitch,
float  yaw,
float  thrust,
uint8_t  mode_switch,
uint8_t  manual_override_switch 
)
inlinestatic

Pack a manual_setpoint 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 in milliseconds since system boot
rollDesired roll rate in radians per second
pitchDesired pitch rate in radians per second
yawDesired yaw rate in radians per second
thrustCollective thrust, normalized to 0 .. 1
mode_switchFlight mode switch position, 0.. 255
manual_override_switchOverride mode switch position, 0.. 255
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_manual_setpoint.h.

static uint16_t mavlink_msg_manual_setpoint_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
float  roll,
float  pitch,
float  yaw,
float  thrust,
uint8_t  mode_switch,
uint8_t  manual_override_switch 
)
inlinestatic

Pack a manual_setpoint 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 in milliseconds since system boot
rollDesired roll rate in radians per second
pitchDesired pitch rate in radians per second
yawDesired yaw rate in radians per second
thrustCollective thrust, normalized to 0 .. 1
mode_switchFlight mode switch position, 0.. 255
manual_override_switchOverride mode switch position, 0.. 255
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_manual_setpoint.h.



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