Classes | Macros | Typedefs | Functions
mavlink_msg_attitude_quaternion_cov.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_attitude_quaternion_cov_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV
 
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN   9
 
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN   4
 
#define MAVLINK_MSG_ID_61_CRC   153
 
#define MAVLINK_MSG_ID_61_LEN   68
 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV   61
 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC   153
 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN   68
 

Typedefs

typedef struct __mavlink_attitude_quaternion_cov_t mavlink_attitude_quaternion_cov_t
 

Functions

static void mavlink_msg_attitude_quaternion_cov_decode (const mavlink_message_t *msg, mavlink_attitude_quaternion_cov_t *attitude_quaternion_cov)
 Decode a attitude_quaternion_cov message into a struct. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_attitude_quaternion_cov_t *attitude_quaternion_cov)
 Encode a attitude_quaternion_cov struct. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_attitude_quaternion_cov_t *attitude_quaternion_cov)
 Encode a attitude_quaternion_cov struct on a channel. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance (const mavlink_message_t *msg, float *covariance)
 Get field covariance from attitude_quaternion_cov message. More...
 
static float mavlink_msg_attitude_quaternion_cov_get_pitchspeed (const mavlink_message_t *msg)
 Get field pitchspeed from attitude_quaternion_cov message. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_get_q (const mavlink_message_t *msg, float *q)
 Get field q from attitude_quaternion_cov message. More...
 
static float mavlink_msg_attitude_quaternion_cov_get_rollspeed (const mavlink_message_t *msg)
 Get field rollspeed from attitude_quaternion_cov message. More...
 
static uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms (const mavlink_message_t *msg)
 Send a attitude_quaternion_cov message. More...
 
static float mavlink_msg_attitude_quaternion_cov_get_yawspeed (const mavlink_message_t *msg)
 Get field yawspeed from attitude_quaternion_cov message. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
 Pack a attitude_quaternion_cov message. More...
 
static uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
 Pack a attitude_quaternion_cov message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV
Value:
{ \
"ATTITUDE_QUATERNION_COV", \
6, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
} \
}

Definition at line 24 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN   9

Definition at line 22 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN   4

Definition at line 21 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ID_61_CRC   153

Definition at line 19 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ID_61_LEN   68

Definition at line 16 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV   61

Definition at line 3 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC   153

Definition at line 18 of file mavlink_msg_attitude_quaternion_cov.h.

#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN   68

Definition at line 15 of file mavlink_msg_attitude_quaternion_cov.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_attitude_quaternion_cov_decode ( const mavlink_message_t *  msg,
mavlink_attitude_quaternion_cov_t attitude_quaternion_cov 
)
inlinestatic

Decode a attitude_quaternion_cov message into a struct.

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

Definition at line 310 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_attitude_quaternion_cov_t attitude_quaternion_cov 
)
inlinestatic

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

Definition at line 136 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_attitude_quaternion_cov_t attitude_quaternion_cov 
)
inlinestatic

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

Definition at line 150 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance ( const mavlink_message_t *  msg,
float *  covariance 
)
inlinestatic

Get field covariance from attitude_quaternion_cov message.

Returns
Attitude covariance

Definition at line 299 of file mavlink_msg_attitude_quaternion_cov.h.

static float mavlink_msg_attitude_quaternion_cov_get_pitchspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field pitchspeed from attitude_quaternion_cov message.

Returns
Pitch angular speed (rad/s)

Definition at line 279 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_get_q ( const mavlink_message_t *  msg,
float *  q 
)
inlinestatic

Get field q from attitude_quaternion_cov message.

Returns
Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)

Definition at line 259 of file mavlink_msg_attitude_quaternion_cov.h.

static float mavlink_msg_attitude_quaternion_cov_get_rollspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field rollspeed from attitude_quaternion_cov message.

Returns
Roll angular speed (rad/s)

Definition at line 269 of file mavlink_msg_attitude_quaternion_cov.h.

static uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a attitude_quaternion_cov message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
qQuaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
rollspeedRoll angular speed (rad/s)
pitchspeedPitch angular speed (rad/s)
yawspeedYaw angular speed (rad/s)
covarianceAttitude covariance Get field time_boot_ms from attitude_quaternion_cov message
Returns
Timestamp (milliseconds since system boot)

Definition at line 249 of file mavlink_msg_attitude_quaternion_cov.h.

static float mavlink_msg_attitude_quaternion_cov_get_yawspeed ( const mavlink_message_t *  msg)
inlinestatic

Get field yawspeed from attitude_quaternion_cov message.

Returns
Yaw angular speed (rad/s)

Definition at line 289 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
const float *  q,
float  rollspeed,
float  pitchspeed,
float  yawspeed,
const float *  covariance 
)
inlinestatic

Pack a attitude_quaternion_cov 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 (milliseconds since system boot)
qQuaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
rollspeedRoll angular speed (rad/s)
pitchspeedPitch angular speed (rad/s)
yawspeedYaw angular speed (rad/s)
covarianceAttitude covariance
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 51 of file mavlink_msg_attitude_quaternion_cov.h.

static uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
const float *  q,
float  rollspeed,
float  pitchspeed,
float  yawspeed,
const float *  covariance 
)
inlinestatic

Pack a attitude_quaternion_cov 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 (milliseconds since system boot)
qQuaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
rollspeedRoll angular speed (rad/s)
pitchspeedPitch angular speed (rad/s)
yawspeedYaw angular speed (rad/s)
covarianceAttitude covariance
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 96 of file mavlink_msg_attitude_quaternion_cov.h.



rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13