Classes | Macros | Typedefs | Functions
mavlink_msg_vision_position_estimate.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_vision_position_estimate_t
 

Macros

#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE
 
#define MAVLINK_MSG_ID_102_CRC   158
 
#define MAVLINK_MSG_ID_102_LEN   32
 
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE   102
 
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC   158
 
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN   32
 

Typedefs

typedef struct __mavlink_vision_position_estimate_t mavlink_vision_position_estimate_t
 

Functions

static void mavlink_msg_vision_position_estimate_decode (const mavlink_message_t *msg, mavlink_vision_position_estimate_t *vision_position_estimate)
 Decode a vision_position_estimate message into a struct. More...
 
static uint16_t mavlink_msg_vision_position_estimate_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_vision_position_estimate_t *vision_position_estimate)
 Encode a vision_position_estimate struct. More...
 
static uint16_t mavlink_msg_vision_position_estimate_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_vision_position_estimate_t *vision_position_estimate)
 Encode a vision_position_estimate struct on a channel. More...
 
static float mavlink_msg_vision_position_estimate_get_pitch (const mavlink_message_t *msg)
 Get field pitch from vision_position_estimate message. More...
 
static float mavlink_msg_vision_position_estimate_get_roll (const mavlink_message_t *msg)
 Get field roll from vision_position_estimate message. More...
 
static uint64_t mavlink_msg_vision_position_estimate_get_usec (const mavlink_message_t *msg)
 Send a vision_position_estimate message. More...
 
static float mavlink_msg_vision_position_estimate_get_x (const mavlink_message_t *msg)
 Get field x from vision_position_estimate message. More...
 
static float mavlink_msg_vision_position_estimate_get_y (const mavlink_message_t *msg)
 Get field y from vision_position_estimate message. More...
 
static float mavlink_msg_vision_position_estimate_get_yaw (const mavlink_message_t *msg)
 Get field yaw from vision_position_estimate message. More...
 
static float mavlink_msg_vision_position_estimate_get_z (const mavlink_message_t *msg)
 Get field z from vision_position_estimate message. More...
 
static uint16_t mavlink_msg_vision_position_estimate_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
 Pack a vision_position_estimate message. More...
 
static uint16_t mavlink_msg_vision_position_estimate_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
 Pack a vision_position_estimate message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE
Value:
{ \
"VISION_POSITION_ESTIMATE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 24 of file mavlink_msg_vision_position_estimate.h.

#define MAVLINK_MSG_ID_102_CRC   158

Definition at line 20 of file mavlink_msg_vision_position_estimate.h.

#define MAVLINK_MSG_ID_102_LEN   32

Definition at line 17 of file mavlink_msg_vision_position_estimate.h.

#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE   102

Definition at line 3 of file mavlink_msg_vision_position_estimate.h.

#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC   158

Definition at line 19 of file mavlink_msg_vision_position_estimate.h.

#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN   32

Definition at line 16 of file mavlink_msg_vision_position_estimate.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_vision_position_estimate_decode ( const mavlink_message_t *  msg,
mavlink_vision_position_estimate_t vision_position_estimate 
)
inlinestatic

Decode a vision_position_estimate message into a struct.

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

Definition at line 340 of file mavlink_msg_vision_position_estimate.h.

static uint16_t mavlink_msg_vision_position_estimate_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_vision_position_estimate_t vision_position_estimate 
)
inlinestatic

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

Definition at line 147 of file mavlink_msg_vision_position_estimate.h.

static uint16_t mavlink_msg_vision_position_estimate_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_vision_position_estimate_t vision_position_estimate 
)
inlinestatic

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

Definition at line 161 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_pitch ( const mavlink_message_t *  msg)
inlinestatic

Get field pitch from vision_position_estimate message.

Returns
Pitch angle in rad

Definition at line 319 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_roll ( const mavlink_message_t *  msg)
inlinestatic

Get field roll from vision_position_estimate message.

Returns
Roll angle in rad

Definition at line 309 of file mavlink_msg_vision_position_estimate.h.

static uint64_t mavlink_msg_vision_position_estimate_get_usec ( const mavlink_message_t *  msg)
inlinestatic

Send a vision_position_estimate message.

Parameters
chanMAVLink channel to send the message
usecTimestamp (microseconds, synced to UNIX time or since system boot)
xGlobal X position
yGlobal Y position
zGlobal Z position
rollRoll angle in rad
pitchPitch angle in rad
yawYaw angle in rad Get field usec from vision_position_estimate message
Returns
Timestamp (microseconds, synced to UNIX time or since system boot)

Definition at line 269 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from vision_position_estimate message.

Returns
Global X position

Definition at line 279 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from vision_position_estimate message.

Returns
Global Y position

Definition at line 289 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_yaw ( const mavlink_message_t *  msg)
inlinestatic

Get field yaw from vision_position_estimate message.

Returns
Yaw angle in rad

Definition at line 329 of file mavlink_msg_vision_position_estimate.h.

static float mavlink_msg_vision_position_estimate_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from vision_position_estimate message.

Returns
Global Z position

Definition at line 299 of file mavlink_msg_vision_position_estimate.h.

static uint16_t mavlink_msg_vision_position_estimate_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint64_t  usec,
float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)
inlinestatic

Pack a vision_position_estimate 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
usecTimestamp (microseconds, synced to UNIX time or since system boot)
xGlobal X position
yGlobal Y position
zGlobal Z position
rollRoll angle in rad
pitchPitch angle in rad
yawYaw angle in rad
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 53 of file mavlink_msg_vision_position_estimate.h.

static uint16_t mavlink_msg_vision_position_estimate_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint64_t  usec,
float  x,
float  y,
float  z,
float  roll,
float  pitch,
float  yaw 
)
inlinestatic

Pack a vision_position_estimate 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
usecTimestamp (microseconds, synced to UNIX time or since system boot)
xGlobal X position
yGlobal Y position
zGlobal Z position
rollRoll angle in rad
pitchPitch angle in rad
yawYaw angle in rad
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 103 of file mavlink_msg_vision_position_estimate.h.



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