Go to the source code of this file.
Classes | |
struct | __mavlink_set_attitude_target_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET |
#define | MAVLINK_MSG_ID_82_CRC 49 |
#define | MAVLINK_MSG_ID_82_LEN 39 |
#define | MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 |
#define | MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 |
#define | MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 |
#define | MAVLINK_MSG_SET_ATTITUDE_TARGET_FIELD_Q_LEN 4 |
Typedefs | |
typedef struct __mavlink_set_attitude_target_t | mavlink_set_attitude_target_t |
Functions | |
static void | mavlink_msg_set_attitude_target_decode (const mavlink_message_t *msg, mavlink_set_attitude_target_t *set_attitude_target) |
Decode a set_attitude_target message into a struct. | |
static uint16_t | mavlink_msg_set_attitude_target_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_set_attitude_target_t *set_attitude_target) |
Encode a set_attitude_target struct. | |
static uint16_t | mavlink_msg_set_attitude_target_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_set_attitude_target_t *set_attitude_target) |
Encode a set_attitude_target struct on a channel. | |
static float | mavlink_msg_set_attitude_target_get_body_pitch_rate (const mavlink_message_t *msg) |
Get field body_pitch_rate from set_attitude_target message. | |
static float | mavlink_msg_set_attitude_target_get_body_roll_rate (const mavlink_message_t *msg) |
Get field body_roll_rate from set_attitude_target message. | |
static float | mavlink_msg_set_attitude_target_get_body_yaw_rate (const mavlink_message_t *msg) |
Get field body_yaw_rate from set_attitude_target message. | |
static uint16_t | mavlink_msg_set_attitude_target_get_q (const mavlink_message_t *msg, float *q) |
Get field q from set_attitude_target message. | |
static uint8_t | mavlink_msg_set_attitude_target_get_target_component (const mavlink_message_t *msg) |
Get field target_component from set_attitude_target message. | |
static uint8_t | mavlink_msg_set_attitude_target_get_target_system (const mavlink_message_t *msg) |
Get field target_system from set_attitude_target message. | |
static float | mavlink_msg_set_attitude_target_get_thrust (const mavlink_message_t *msg) |
Get field thrust from set_attitude_target message. | |
static uint32_t | mavlink_msg_set_attitude_target_get_time_boot_ms (const mavlink_message_t *msg) |
Send a set_attitude_target message. | |
static uint8_t | mavlink_msg_set_attitude_target_get_type_mask (const mavlink_message_t *msg) |
Get field type_mask from set_attitude_target message. | |
static uint16_t | mavlink_msg_set_attitude_target_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) |
Pack a set_attitude_target message. | |
static uint16_t | mavlink_msg_set_attitude_target_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) |
Pack a set_attitude_target message on a channel. |
{ \ "SET_ATTITUDE_TARGET", \ 9, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_attitude_target_t, time_boot_ms) }, \ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_set_attitude_target_t, q) }, \ { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_set_attitude_target_t, body_roll_rate) }, \ { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_set_attitude_target_t, body_pitch_rate) }, \ { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_set_attitude_target_t, body_yaw_rate) }, \ { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_set_attitude_target_t, thrust) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_set_attitude_target_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_set_attitude_target_t, target_component) }, \ { "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_set_attitude_target_t, type_mask) }, \ } \ }
Definition at line 26 of file mavlink_msg_set_attitude_target.h.
#define MAVLINK_MSG_ID_82_CRC 49 |
Definition at line 22 of file mavlink_msg_set_attitude_target.h.
#define MAVLINK_MSG_ID_82_LEN 39 |
Definition at line 19 of file mavlink_msg_set_attitude_target.h.
#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET 82 |
Definition at line 3 of file mavlink_msg_set_attitude_target.h.
#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_CRC 49 |
Definition at line 21 of file mavlink_msg_set_attitude_target.h.
#define MAVLINK_MSG_ID_SET_ATTITUDE_TARGET_LEN 39 |
Definition at line 18 of file mavlink_msg_set_attitude_target.h.
Definition at line 24 of file mavlink_msg_set_attitude_target.h.
typedef struct __mavlink_set_attitude_target_t mavlink_set_attitude_target_t |
static void mavlink_msg_set_attitude_target_decode | ( | const mavlink_message_t * | msg, |
mavlink_set_attitude_target_t * | set_attitude_target | ||
) | [inline, static] |
Decode a set_attitude_target message into a struct.
msg | The message to decode |
set_attitude_target | C-struct to decode the message contents into |
Definition at line 378 of file mavlink_msg_set_attitude_target.h.
static uint16_t mavlink_msg_set_attitude_target_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_set_attitude_target_t * | set_attitude_target | ||
) | [inline, static] |
Encode a set_attitude_target 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 |
set_attitude_target | C-struct to read the message contents from |
Definition at line 159 of file mavlink_msg_set_attitude_target.h.
static uint16_t mavlink_msg_set_attitude_target_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_set_attitude_target_t * | set_attitude_target | ||
) | [inline, static] |
Encode a set_attitude_target 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 |
set_attitude_target | C-struct to read the message contents from |
Definition at line 173 of file mavlink_msg_set_attitude_target.h.
static float mavlink_msg_set_attitude_target_get_body_pitch_rate | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field body_pitch_rate from set_attitude_target message.
Definition at line 347 of file mavlink_msg_set_attitude_target.h.
static float mavlink_msg_set_attitude_target_get_body_roll_rate | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field body_roll_rate from set_attitude_target message.
Definition at line 337 of file mavlink_msg_set_attitude_target.h.
static float mavlink_msg_set_attitude_target_get_body_yaw_rate | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field body_yaw_rate from set_attitude_target message.
Definition at line 357 of file mavlink_msg_set_attitude_target.h.
static uint16_t mavlink_msg_set_attitude_target_get_q | ( | const mavlink_message_t * | msg, |
float * | q | ||
) | [inline, static] |
Get field q from set_attitude_target message.
Definition at line 327 of file mavlink_msg_set_attitude_target.h.
static uint8_t mavlink_msg_set_attitude_target_get_target_component | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field target_component from set_attitude_target message.
Definition at line 307 of file mavlink_msg_set_attitude_target.h.
static uint8_t mavlink_msg_set_attitude_target_get_target_system | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field target_system from set_attitude_target message.
Definition at line 297 of file mavlink_msg_set_attitude_target.h.
static float mavlink_msg_set_attitude_target_get_thrust | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field thrust from set_attitude_target message.
Definition at line 367 of file mavlink_msg_set_attitude_target.h.
static uint32_t mavlink_msg_set_attitude_target_get_time_boot_ms | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a set_attitude_target message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp in milliseconds since system boot |
target_system | System ID |
target_component | Component ID |
type_mask | Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude |
q | Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) |
body_roll_rate | Body roll rate in radians per second |
body_pitch_rate | Body roll rate in radians per second |
body_yaw_rate | Body roll rate in radians per second |
thrust | Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) Get field time_boot_ms from set_attitude_target message |
Definition at line 287 of file mavlink_msg_set_attitude_target.h.
static uint8_t mavlink_msg_set_attitude_target_get_type_mask | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field type_mask from set_attitude_target message.
Definition at line 317 of file mavlink_msg_set_attitude_target.h.
static uint16_t mavlink_msg_set_attitude_target_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
uint8_t | target_system, | ||
uint8_t | target_component, | ||
uint8_t | type_mask, | ||
const float * | q, | ||
float | body_roll_rate, | ||
float | body_pitch_rate, | ||
float | body_yaw_rate, | ||
float | thrust | ||
) | [inline, static] |
Pack a set_attitude_target 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 |
time_boot_ms | Timestamp in milliseconds since system boot |
target_system | System ID |
target_component | Component ID |
type_mask | Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude |
q | Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) |
body_roll_rate | Body roll rate in radians per second |
body_pitch_rate | Body roll rate in radians per second |
body_yaw_rate | Body roll rate in radians per second |
thrust | Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) |
Definition at line 59 of file mavlink_msg_set_attitude_target.h.
static uint16_t mavlink_msg_set_attitude_target_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
uint8_t | target_system, | ||
uint8_t | target_component, | ||
uint8_t | type_mask, | ||
const float * | q, | ||
float | body_roll_rate, | ||
float | body_pitch_rate, | ||
float | body_yaw_rate, | ||
float | thrust | ||
) | [inline, static] |
Pack a set_attitude_target 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 |
time_boot_ms | Timestamp in milliseconds since system boot |
target_system | System ID |
target_component | Component ID |
type_mask | Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 6: reserved, bit 7: throttle, bit 8: attitude |
q | Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) |
body_roll_rate | Body roll rate in radians per second |
body_pitch_rate | Body roll rate in radians per second |
body_yaw_rate | Body roll rate in radians per second |
thrust | Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) |
Definition at line 113 of file mavlink_msg_set_attitude_target.h.