Classes | Macros | Typedefs | Functions
mavlink_msg_att_pos_mocap.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_att_pos_mocap_t
 

Macros

#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP
 
#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN   4
 
#define MAVLINK_MSG_ID_138_CRC   109
 
#define MAVLINK_MSG_ID_138_LEN   36
 
#define MAVLINK_MSG_ID_ATT_POS_MOCAP   138
 
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC   109
 
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN   36
 

Typedefs

typedef struct __mavlink_att_pos_mocap_t mavlink_att_pos_mocap_t
 

Functions

static void mavlink_msg_att_pos_mocap_decode (const mavlink_message_t *msg, mavlink_att_pos_mocap_t *att_pos_mocap)
 Decode a att_pos_mocap message into a struct. More...
 
static uint16_t mavlink_msg_att_pos_mocap_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_att_pos_mocap_t *att_pos_mocap)
 Encode a att_pos_mocap struct. More...
 
static uint16_t mavlink_msg_att_pos_mocap_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_att_pos_mocap_t *att_pos_mocap)
 Encode a att_pos_mocap struct on a channel. More...
 
static uint16_t mavlink_msg_att_pos_mocap_get_q (const mavlink_message_t *msg, float *q)
 Get field q from att_pos_mocap message. More...
 
static uint64_t mavlink_msg_att_pos_mocap_get_time_usec (const mavlink_message_t *msg)
 Send a att_pos_mocap message. More...
 
static float mavlink_msg_att_pos_mocap_get_x (const mavlink_message_t *msg)
 Get field x from att_pos_mocap message. More...
 
static float mavlink_msg_att_pos_mocap_get_y (const mavlink_message_t *msg)
 Get field y from att_pos_mocap message. More...
 
static float mavlink_msg_att_pos_mocap_get_z (const mavlink_message_t *msg)
 Get field z from att_pos_mocap message. More...
 
static uint16_t mavlink_msg_att_pos_mocap_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t time_usec, const float *q, float x, float y, float z)
 Pack a att_pos_mocap message. More...
 
static uint16_t mavlink_msg_att_pos_mocap_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t time_usec, const float *q, float x, float y, float z)
 Pack a att_pos_mocap message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP
Value:
{ \
"ATT_POS_MOCAP", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 22 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN   4

Definition at line 20 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ID_138_CRC   109

Definition at line 18 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ID_138_LEN   36

Definition at line 15 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ID_ATT_POS_MOCAP   138

Definition at line 3 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC   109

Definition at line 17 of file mavlink_msg_att_pos_mocap.h.

#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN   36

Definition at line 14 of file mavlink_msg_att_pos_mocap.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_att_pos_mocap_decode ( const mavlink_message_t *  msg,
mavlink_att_pos_mocap_t att_pos_mocap 
)
inlinestatic

Decode a att_pos_mocap message into a struct.

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

Definition at line 286 of file mavlink_msg_att_pos_mocap.h.

static uint16_t mavlink_msg_att_pos_mocap_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_att_pos_mocap_t att_pos_mocap 
)
inlinestatic

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

Definition at line 127 of file mavlink_msg_att_pos_mocap.h.

static uint16_t mavlink_msg_att_pos_mocap_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_att_pos_mocap_t att_pos_mocap 
)
inlinestatic

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

Definition at line 141 of file mavlink_msg_att_pos_mocap.h.

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

Get field q from att_pos_mocap message.

Returns
Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)

Definition at line 245 of file mavlink_msg_att_pos_mocap.h.

static uint64_t mavlink_msg_att_pos_mocap_get_time_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a att_pos_mocap message.

Parameters
chanMAVLink channel to send the message
time_usecTimestamp (micros since boot or Unix epoch)
qAttitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
xX position in meters (NED)
yY position in meters (NED)
zZ position in meters (NED) Get field time_usec from att_pos_mocap message
Returns
Timestamp (micros since boot or Unix epoch)

Definition at line 235 of file mavlink_msg_att_pos_mocap.h.

static float mavlink_msg_att_pos_mocap_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from att_pos_mocap message.

Returns
X position in meters (NED)

Definition at line 255 of file mavlink_msg_att_pos_mocap.h.

static float mavlink_msg_att_pos_mocap_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from att_pos_mocap message.

Returns
Y position in meters (NED)

Definition at line 265 of file mavlink_msg_att_pos_mocap.h.

static float mavlink_msg_att_pos_mocap_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from att_pos_mocap message.

Returns
Z position in meters (NED)

Definition at line 275 of file mavlink_msg_att_pos_mocap.h.

static uint16_t mavlink_msg_att_pos_mocap_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  time_usec,
const float *  q,
float  x,
float  y,
float  z 
)
inlinestatic

Pack a att_pos_mocap 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_usecTimestamp (micros since boot or Unix epoch)
qAttitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
xX position in meters (NED)
yY position in meters (NED)
zZ position in meters (NED)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 47 of file mavlink_msg_att_pos_mocap.h.

static uint16_t mavlink_msg_att_pos_mocap_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  time_usec,
const float *  q,
float  x,
float  y,
float  z 
)
inlinestatic

Pack a att_pos_mocap 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_usecTimestamp (micros since boot or Unix epoch)
qAttitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
xX position in meters (NED)
yY position in meters (NED)
zZ position in meters (NED)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 89 of file mavlink_msg_att_pos_mocap.h.



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