Go to the source code of this file.
Classes | |
struct | __mavlink_attitude_quaternion_t |
Defines | |
#define | MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION |
#define | MAVLINK_MSG_ID_31_CRC 246 |
#define | MAVLINK_MSG_ID_31_LEN 32 |
#define | MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 |
#define | MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 |
#define | MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 |
Typedefs | |
typedef struct __mavlink_attitude_quaternion_t | mavlink_attitude_quaternion_t |
Functions | |
static void | mavlink_msg_attitude_quaternion_decode (const mavlink_message_t *msg, mavlink_attitude_quaternion_t *attitude_quaternion) |
Decode a attitude_quaternion message into a struct. | |
static uint16_t | mavlink_msg_attitude_quaternion_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_attitude_quaternion_t *attitude_quaternion) |
Encode a attitude_quaternion struct. | |
static uint16_t | mavlink_msg_attitude_quaternion_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_attitude_quaternion_t *attitude_quaternion) |
Encode a attitude_quaternion struct on a channel. | |
static float | mavlink_msg_attitude_quaternion_get_pitchspeed (const mavlink_message_t *msg) |
Get field pitchspeed from attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_q1 (const mavlink_message_t *msg) |
Get field q1 from attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_q2 (const mavlink_message_t *msg) |
Get field q2 from attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_q3 (const mavlink_message_t *msg) |
Get field q3 from attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_q4 (const mavlink_message_t *msg) |
Get field q4 from attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_rollspeed (const mavlink_message_t *msg) |
Get field rollspeed from attitude_quaternion message. | |
static uint32_t | mavlink_msg_attitude_quaternion_get_time_boot_ms (const mavlink_message_t *msg) |
Send a attitude_quaternion message. | |
static float | mavlink_msg_attitude_quaternion_get_yawspeed (const mavlink_message_t *msg) |
Get field yawspeed from attitude_quaternion message. | |
static uint16_t | mavlink_msg_attitude_quaternion_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) |
Pack a attitude_quaternion message. | |
static uint16_t | mavlink_msg_attitude_quaternion_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) |
Pack a attitude_quaternion message on a channel. |
{ \ "ATTITUDE_QUATERNION", \ 8, \ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ } \ }
Definition at line 25 of file mavlink_msg_attitude_quaternion.h.
#define MAVLINK_MSG_ID_31_CRC 246 |
Definition at line 21 of file mavlink_msg_attitude_quaternion.h.
#define MAVLINK_MSG_ID_31_LEN 32 |
Definition at line 18 of file mavlink_msg_attitude_quaternion.h.
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 |
Definition at line 3 of file mavlink_msg_attitude_quaternion.h.
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 |
Definition at line 20 of file mavlink_msg_attitude_quaternion.h.
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 |
Definition at line 17 of file mavlink_msg_attitude_quaternion.h.
typedef struct __mavlink_attitude_quaternion_t mavlink_attitude_quaternion_t |
static void mavlink_msg_attitude_quaternion_decode | ( | const mavlink_message_t * | msg, |
mavlink_attitude_quaternion_t * | attitude_quaternion | ||
) | [inline, static] |
Decode a attitude_quaternion message into a struct.
msg | The message to decode |
attitude_quaternion | C-struct to decode the message contents into |
Definition at line 363 of file mavlink_msg_attitude_quaternion.h.
static uint16_t mavlink_msg_attitude_quaternion_encode | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
const mavlink_attitude_quaternion_t * | attitude_quaternion | ||
) | [inline, static] |
Encode a attitude_quaternion 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_quaternion | C-struct to read the message contents from |
Definition at line 155 of file mavlink_msg_attitude_quaternion.h.
static uint16_t mavlink_msg_attitude_quaternion_encode_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
const mavlink_attitude_quaternion_t * | attitude_quaternion | ||
) | [inline, static] |
Encode a attitude_quaternion 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_quaternion | C-struct to read the message contents from |
Definition at line 169 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_pitchspeed | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field pitchspeed from attitude_quaternion message.
Definition at line 342 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_q1 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field q1 from attitude_quaternion message.
Definition at line 292 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_q2 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field q2 from attitude_quaternion message.
Definition at line 302 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_q3 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field q3 from attitude_quaternion message.
Definition at line 312 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_q4 | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field q4 from attitude_quaternion message.
Definition at line 322 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_rollspeed | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field rollspeed from attitude_quaternion message.
Definition at line 332 of file mavlink_msg_attitude_quaternion.h.
static uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Send a attitude_quaternion message.
chan | MAVLink channel to send the message |
time_boot_ms | Timestamp (milliseconds since system boot) |
q1 | Quaternion component 1, w (1 in null-rotation) |
q2 | Quaternion component 2, x (0 in null-rotation) |
q3 | Quaternion component 3, y (0 in null-rotation) |
q4 | Quaternion component 4, z (0 in null-rotation) |
rollspeed | Roll angular speed (rad/s) |
pitchspeed | Pitch angular speed (rad/s) |
yawspeed | Yaw angular speed (rad/s) Get field time_boot_ms from attitude_quaternion message |
Definition at line 282 of file mavlink_msg_attitude_quaternion.h.
static float mavlink_msg_attitude_quaternion_get_yawspeed | ( | const mavlink_message_t * | msg | ) | [inline, static] |
Get field yawspeed from attitude_quaternion message.
Definition at line 352 of file mavlink_msg_attitude_quaternion.h.
static uint16_t mavlink_msg_attitude_quaternion_pack | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
float | q1, | ||
float | q2, | ||
float | q3, | ||
float | q4, | ||
float | rollspeed, | ||
float | pitchspeed, | ||
float | yawspeed | ||
) | [inline, static] |
Pack a attitude_quaternion 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 (milliseconds since system boot) |
q1 | Quaternion component 1, w (1 in null-rotation) |
q2 | Quaternion component 2, x (0 in null-rotation) |
q3 | Quaternion component 3, y (0 in null-rotation) |
q4 | Quaternion component 4, z (0 in null-rotation) |
rollspeed | Roll angular speed (rad/s) |
pitchspeed | Pitch angular speed (rad/s) |
yawspeed | Yaw angular speed (rad/s) |
Definition at line 56 of file mavlink_msg_attitude_quaternion.h.
static uint16_t mavlink_msg_attitude_quaternion_pack_chan | ( | uint8_t | system_id, |
uint8_t | component_id, | ||
uint8_t | chan, | ||
mavlink_message_t * | msg, | ||
uint32_t | time_boot_ms, | ||
float | q1, | ||
float | q2, | ||
float | q3, | ||
float | q4, | ||
float | rollspeed, | ||
float | pitchspeed, | ||
float | yawspeed | ||
) | [inline, static] |
Pack a attitude_quaternion 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 (milliseconds since system boot) |
q1 | Quaternion component 1, w (1 in null-rotation) |
q2 | Quaternion component 2, x (0 in null-rotation) |
q3 | Quaternion component 3, y (0 in null-rotation) |
q4 | Quaternion component 4, z (0 in null-rotation) |
rollspeed | Roll angular speed (rad/s) |
pitchspeed | Pitch angular speed (rad/s) |
yawspeed | Yaw angular speed (rad/s) |
Definition at line 109 of file mavlink_msg_attitude_quaternion.h.