Go to the source code of this file.
Classes | |
struct | __mavlink_attitude_target_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET |
#define | MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 |
#define | MAVLINK_MSG_ID_83_CRC 22 |
#define | MAVLINK_MSG_ID_83_LEN 37 |
#define | MAVLINK_MSG_ID_ATTITUDE_TARGET 83 |
#define | MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 |
#define | MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 |
Typedefs | |
typedef struct __mavlink_attitude_target_t | mavlink_attitude_target_t |
Functions | |
static void | mavlink_msg_attitude_target_decode (const mavlink_message_t *msg, mavlink_attitude_target_t *attitude_target) |
Decode a attitude_target message into a struct. More... | |
static uint16_t | mavlink_msg_attitude_target_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_attitude_target_t *attitude_target) |
Encode a attitude_target struct. More... | |
static uint16_t | mavlink_msg_attitude_target_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_attitude_target_t *attitude_target) |
Encode a attitude_target struct on a channel. More... | |
static float | mavlink_msg_attitude_target_get_body_pitch_rate (const mavlink_message_t *msg) |
Get field body_pitch_rate from attitude_target message. More... | |
static float | mavlink_msg_attitude_target_get_body_roll_rate (const mavlink_message_t *msg) |
Get field body_roll_rate from attitude_target message. More... | |
static float | mavlink_msg_attitude_target_get_body_yaw_rate (const mavlink_message_t *msg) |
Get field body_yaw_rate from attitude_target message. More... | |
static uint16_t | mavlink_msg_attitude_target_get_q (const mavlink_message_t *msg, float *q) |
Get field q from attitude_target message. More... | |
static float | mavlink_msg_attitude_target_get_thrust (const mavlink_message_t *msg) |
Get field thrust from attitude_target message. More... | |
static uint32_t | mavlink_msg_attitude_target_get_time_boot_ms (const mavlink_message_t *msg) |
Send a attitude_target message. More... | |
static uint8_t | mavlink_msg_attitude_target_get_type_mask (const mavlink_message_t *msg) |
Get field type_mask from attitude_target message. More... | |
static uint16_t | mavlink_msg_attitude_target_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) |
Pack a attitude_target message. More... | |
static uint16_t | mavlink_msg_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 type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) |
Pack a attitude_target message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET |
Definition at line 24 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4 |
Definition at line 22 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ID_83_CRC 22 |
Definition at line 20 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ID_83_LEN 37 |
Definition at line 17 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83 |
Definition at line 3 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22 |
Definition at line 19 of file mavlink_msg_attitude_target.h.
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37 |
Definition at line 16 of file mavlink_msg_attitude_target.h.
typedef struct __mavlink_attitude_target_t mavlink_attitude_target_t |
|
inlinestatic |
Decode a attitude_target message into a struct.
msg | The message to decode |
attitude_target | C-struct to decode the message contents into |
Definition at line 332 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Encode a 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 |
attitude_target | C-struct to read the message contents from |
Definition at line 143 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Encode a 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 |
attitude_target | C-struct to read the message contents from |
Definition at line 157 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field body_pitch_rate from attitude_target message.
Definition at line 301 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field body_roll_rate from attitude_target message.
Definition at line 291 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field body_yaw_rate from attitude_target message.
Definition at line 311 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field q from attitude_target message.
Definition at line 281 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field thrust from attitude_target message.
Definition at line 321 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Send a attitude_target message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp in milliseconds since system boot |
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 7: reserved, 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 attitude_target message |
Definition at line 261 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Get field type_mask from attitude_target message.
Definition at line 271 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Pack a 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 |
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 7: reserved, 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 53 of file mavlink_msg_attitude_target.h.
|
inlinestatic |
Pack a 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 |
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 7: reserved, 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 101 of file mavlink_msg_attitude_target.h.