Classes | Macros | Typedefs | Functions
mavlink_msg_local_position_ned_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_local_position_ned_cov_t
 

Macros

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV
 
#define MAVLINK_MSG_ID_64_CRC   59
 
#define MAVLINK_MSG_ID_64_LEN   229
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV   64
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC   59
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN   229
 
#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN   45
 

Typedefs

typedef struct __mavlink_local_position_ned_cov_t mavlink_local_position_ned_cov_t
 

Functions

static void mavlink_msg_local_position_ned_cov_decode (const mavlink_message_t *msg, mavlink_local_position_ned_cov_t *local_position_ned_cov)
 Decode a local_position_ned_cov message into a struct. More...
 
static uint16_t mavlink_msg_local_position_ned_cov_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_local_position_ned_cov_t *local_position_ned_cov)
 Encode a local_position_ned_cov struct. More...
 
static uint16_t mavlink_msg_local_position_ned_cov_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_local_position_ned_cov_t *local_position_ned_cov)
 Encode a local_position_ned_cov struct on a channel. More...
 
static float mavlink_msg_local_position_ned_cov_get_ax (const mavlink_message_t *msg)
 Get field ax from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_ay (const mavlink_message_t *msg)
 Get field ay from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_az (const mavlink_message_t *msg)
 Get field az from local_position_ned_cov message. More...
 
static uint16_t mavlink_msg_local_position_ned_cov_get_covariance (const mavlink_message_t *msg, float *covariance)
 Get field covariance from local_position_ned_cov message. More...
 
static uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type (const mavlink_message_t *msg)
 Get field estimator_type from local_position_ned_cov message. More...
 
static uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms (const mavlink_message_t *msg)
 Send a local_position_ned_cov message. More...
 
static uint64_t mavlink_msg_local_position_ned_cov_get_time_utc (const mavlink_message_t *msg)
 Get field time_utc from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_vx (const mavlink_message_t *msg)
 Get field vx from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_vy (const mavlink_message_t *msg)
 Get field vy from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_vz (const mavlink_message_t *msg)
 Get field vz from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_x (const mavlink_message_t *msg)
 Get field x from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_y (const mavlink_message_t *msg)
 Get field y from local_position_ned_cov message. More...
 
static float mavlink_msg_local_position_ned_cov_get_z (const mavlink_message_t *msg)
 Get field z from local_position_ned_cov message. More...
 
static uint16_t mavlink_msg_local_position_ned_cov_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
 Pack a local_position_ned_cov message. More...
 
static uint16_t mavlink_msg_local_position_ned_cov_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
 Pack a local_position_ned_cov message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV
Value:
{ \
"LOCAL_POSITION_NED_COV", \
13, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
{ "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
{ "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
{ "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
} \
}
#define NULL
Definition: usbd_def.h:50

Definition at line 30 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_ID_64_CRC   59

Definition at line 26 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_ID_64_LEN   229

Definition at line 23 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV   64

Definition at line 3 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC   59

Definition at line 25 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN   229

Definition at line 22 of file mavlink_msg_local_position_ned_cov.h.

#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN   45

Definition at line 28 of file mavlink_msg_local_position_ned_cov.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_local_position_ned_cov_decode ( const mavlink_message_t *  msg,
mavlink_local_position_ned_cov_t local_position_ned_cov 
)
inlinestatic

Decode a local_position_ned_cov message into a struct.

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

Definition at line 470 of file mavlink_msg_local_position_ned_cov.h.

static uint16_t mavlink_msg_local_position_ned_cov_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_local_position_ned_cov_t local_position_ned_cov 
)
inlinestatic

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

Definition at line 191 of file mavlink_msg_local_position_ned_cov.h.

static uint16_t mavlink_msg_local_position_ned_cov_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_local_position_ned_cov_t local_position_ned_cov 
)
inlinestatic

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

Definition at line 205 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_ax ( const mavlink_message_t *  msg)
inlinestatic

Get field ax from local_position_ned_cov message.

Returns
X Acceleration (m/s^2)

Definition at line 429 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_ay ( const mavlink_message_t *  msg)
inlinestatic

Get field ay from local_position_ned_cov message.

Returns
Y Acceleration (m/s^2)

Definition at line 439 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_az ( const mavlink_message_t *  msg)
inlinestatic

Get field az from local_position_ned_cov message.

Returns
Z Acceleration (m/s^2)

Definition at line 449 of file mavlink_msg_local_position_ned_cov.h.

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

Get field covariance from local_position_ned_cov message.

Returns
Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)

Definition at line 459 of file mavlink_msg_local_position_ned_cov.h.

static uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type ( const mavlink_message_t *  msg)
inlinestatic

Get field estimator_type from local_position_ned_cov message.

Returns
Class id of the estimator this estimate originated from.

Definition at line 359 of file mavlink_msg_local_position_ned_cov.h.

static uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a local_position_ned_cov message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot). 0 for system without monotonic timestamp
time_utcTimestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
estimator_typeClass id of the estimator this estimate originated from.
xX Position
yY Position
zZ Position
vxX Speed (m/s)
vyY Speed (m/s)
vzZ Speed (m/s)
axX Acceleration (m/s^2)
ayY Acceleration (m/s^2)
azZ Acceleration (m/s^2)
covarianceCovariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.) Get field time_boot_ms from local_position_ned_cov message
Returns
Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp

Definition at line 339 of file mavlink_msg_local_position_ned_cov.h.

static uint64_t mavlink_msg_local_position_ned_cov_get_time_utc ( const mavlink_message_t *  msg)
inlinestatic

Get field time_utc from local_position_ned_cov message.

Returns
Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.

Definition at line 349 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from local_position_ned_cov message.

Returns
X Speed (m/s)

Definition at line 399 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from local_position_ned_cov message.

Returns
Y Speed (m/s)

Definition at line 409 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from local_position_ned_cov message.

Returns
Z Speed (m/s)

Definition at line 419 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_x ( const mavlink_message_t *  msg)
inlinestatic

Get field x from local_position_ned_cov message.

Returns
X Position

Definition at line 369 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_y ( const mavlink_message_t *  msg)
inlinestatic

Get field y from local_position_ned_cov message.

Returns
Y Position

Definition at line 379 of file mavlink_msg_local_position_ned_cov.h.

static float mavlink_msg_local_position_ned_cov_get_z ( const mavlink_message_t *  msg)
inlinestatic

Get field z from local_position_ned_cov message.

Returns
Z Position

Definition at line 389 of file mavlink_msg_local_position_ned_cov.h.

static uint16_t mavlink_msg_local_position_ned_cov_pack ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint64_t  time_utc,
uint8_t  estimator_type,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  ax,
float  ay,
float  az,
const float *  covariance 
)
inlinestatic

Pack a local_position_ned_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). 0 for system without monotonic timestamp
time_utcTimestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
estimator_typeClass id of the estimator this estimate originated from.
xX Position
yY Position
zZ Position
vxX Speed (m/s)
vyY Speed (m/s)
vzZ Speed (m/s)
axX Acceleration (m/s^2)
ayY Acceleration (m/s^2)
azZ Acceleration (m/s^2)
covarianceCovariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 71 of file mavlink_msg_local_position_ned_cov.h.

static uint16_t mavlink_msg_local_position_ned_cov_pack_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
uint32_t  time_boot_ms,
uint64_t  time_utc,
uint8_t  estimator_type,
float  x,
float  y,
float  z,
float  vx,
float  vy,
float  vz,
float  ax,
float  ay,
float  az,
const float *  covariance 
)
inlinestatic

Pack a local_position_ned_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). 0 for system without monotonic timestamp
time_utcTimestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
estimator_typeClass id of the estimator this estimate originated from.
xX Position
yY Position
zZ Position
vxX Speed (m/s)
vyY Speed (m/s)
vzZ Speed (m/s)
axX Acceleration (m/s^2)
ayY Acceleration (m/s^2)
azZ Acceleration (m/s^2)
covarianceCovariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 137 of file mavlink_msg_local_position_ned_cov.h.



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