Classes | Macros | Typedefs | Functions
mavlink_msg_global_position_int_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_global_position_int_cov_t
 

Macros

#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV
 
#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN   36
 
#define MAVLINK_MSG_ID_63_CRC   51
 
#define MAVLINK_MSG_ID_63_LEN   185
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV   63
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC   51
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN   185
 

Typedefs

typedef struct __mavlink_global_position_int_cov_t mavlink_global_position_int_cov_t
 

Functions

static void mavlink_msg_global_position_int_cov_decode (const mavlink_message_t *msg, mavlink_global_position_int_cov_t *global_position_int_cov)
 Decode a global_position_int_cov message into a struct. More...
 
static uint16_t mavlink_msg_global_position_int_cov_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_global_position_int_cov_t *global_position_int_cov)
 Encode a global_position_int_cov struct. More...
 
static uint16_t mavlink_msg_global_position_int_cov_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_global_position_int_cov_t *global_position_int_cov)
 Encode a global_position_int_cov struct on a channel. More...
 
static int32_t mavlink_msg_global_position_int_cov_get_alt (const mavlink_message_t *msg)
 Get field alt from global_position_int_cov message. More...
 
static uint16_t mavlink_msg_global_position_int_cov_get_covariance (const mavlink_message_t *msg, float *covariance)
 Get field covariance from global_position_int_cov message. More...
 
static uint8_t mavlink_msg_global_position_int_cov_get_estimator_type (const mavlink_message_t *msg)
 Get field estimator_type from global_position_int_cov message. More...
 
static int32_t mavlink_msg_global_position_int_cov_get_lat (const mavlink_message_t *msg)
 Get field lat from global_position_int_cov message. More...
 
static int32_t mavlink_msg_global_position_int_cov_get_lon (const mavlink_message_t *msg)
 Get field lon from global_position_int_cov message. More...
 
static int32_t mavlink_msg_global_position_int_cov_get_relative_alt (const mavlink_message_t *msg)
 Get field relative_alt from global_position_int_cov message. More...
 
static uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms (const mavlink_message_t *msg)
 Send a global_position_int_cov message. More...
 
static uint64_t mavlink_msg_global_position_int_cov_get_time_utc (const mavlink_message_t *msg)
 Get field time_utc from global_position_int_cov message. More...
 
static float mavlink_msg_global_position_int_cov_get_vx (const mavlink_message_t *msg)
 Get field vx from global_position_int_cov message. More...
 
static float mavlink_msg_global_position_int_cov_get_vy (const mavlink_message_t *msg)
 Get field vy from global_position_int_cov message. More...
 
static float mavlink_msg_global_position_int_cov_get_vz (const mavlink_message_t *msg)
 Get field vz from global_position_int_cov message. More...
 
static uint16_t mavlink_msg_global_position_int_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, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
 Pack a global_position_int_cov message. More...
 
static uint16_t mavlink_msg_global_position_int_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, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
 Pack a global_position_int_cov message on a channel. More...
 

Macro Definition Documentation

#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV
Value:
{ \
"GLOBAL_POSITION_INT_COV", \
11, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
} \
}
float alt(float press)
Definition: turbomath.cpp:470
#define NULL
Definition: usbd_def.h:50

Definition at line 28 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN   36

Definition at line 26 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_ID_63_CRC   51

Definition at line 24 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_ID_63_LEN   185

Definition at line 21 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV   63

Definition at line 3 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC   51

Definition at line 23 of file mavlink_msg_global_position_int_cov.h.

#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN   185

Definition at line 20 of file mavlink_msg_global_position_int_cov.h.

Typedef Documentation

Function Documentation

static void mavlink_msg_global_position_int_cov_decode ( const mavlink_message_t *  msg,
mavlink_global_position_int_cov_t global_position_int_cov 
)
inlinestatic

Decode a global_position_int_cov message into a struct.

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

Definition at line 424 of file mavlink_msg_global_position_int_cov.h.

static uint16_t mavlink_msg_global_position_int_cov_encode ( uint8_t  system_id,
uint8_t  component_id,
mavlink_message_t *  msg,
const mavlink_global_position_int_cov_t global_position_int_cov 
)
inlinestatic

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

Definition at line 175 of file mavlink_msg_global_position_int_cov.h.

static uint16_t mavlink_msg_global_position_int_cov_encode_chan ( uint8_t  system_id,
uint8_t  component_id,
uint8_t  chan,
mavlink_message_t *  msg,
const mavlink_global_position_int_cov_t global_position_int_cov 
)
inlinestatic

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

Definition at line 189 of file mavlink_msg_global_position_int_cov.h.

static int32_t mavlink_msg_global_position_int_cov_get_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field alt from global_position_int_cov message.

Returns
Altitude in meters, expressed as * 1000 (millimeters), above MSL

Definition at line 363 of file mavlink_msg_global_position_int_cov.h.

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

Get field covariance from global_position_int_cov message.

Returns
Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)

Definition at line 413 of file mavlink_msg_global_position_int_cov.h.

static uint8_t mavlink_msg_global_position_int_cov_get_estimator_type ( const mavlink_message_t *  msg)
inlinestatic

Get field estimator_type from global_position_int_cov message.

Returns
Class id of the estimator this estimate originated from.

Definition at line 333 of file mavlink_msg_global_position_int_cov.h.

static int32_t mavlink_msg_global_position_int_cov_get_lat ( const mavlink_message_t *  msg)
inlinestatic

Get field lat from global_position_int_cov message.

Returns
Latitude, expressed as degrees * 1E7

Definition at line 343 of file mavlink_msg_global_position_int_cov.h.

static int32_t mavlink_msg_global_position_int_cov_get_lon ( const mavlink_message_t *  msg)
inlinestatic

Get field lon from global_position_int_cov message.

Returns
Longitude, expressed as degrees * 1E7

Definition at line 353 of file mavlink_msg_global_position_int_cov.h.

static int32_t mavlink_msg_global_position_int_cov_get_relative_alt ( const mavlink_message_t *  msg)
inlinestatic

Get field relative_alt from global_position_int_cov message.

Returns
Altitude above ground in meters, expressed as * 1000 (millimeters)

Definition at line 373 of file mavlink_msg_global_position_int_cov.h.

static uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms ( const mavlink_message_t *  msg)
inlinestatic

Send a global_position_int_cov message.

Parameters
chanMAVLink channel to send the message
time_boot_msTimestamp (milliseconds since system boot)
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.
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altAltitude in meters, expressed as * 1000 (millimeters), above MSL
relative_altAltitude above ground in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s
vyGround Y Speed (Longitude), expressed as m/s
vzGround Z Speed (Altitude), expressed as m/s
covarianceCovariance matrix (first six entries are the first ROW, next six entries are the second row, etc.) Get field time_boot_ms from global_position_int_cov message
Returns
Timestamp (milliseconds since system boot)

Definition at line 313 of file mavlink_msg_global_position_int_cov.h.

static uint64_t mavlink_msg_global_position_int_cov_get_time_utc ( const mavlink_message_t *  msg)
inlinestatic

Get field time_utc from global_position_int_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 323 of file mavlink_msg_global_position_int_cov.h.

static float mavlink_msg_global_position_int_cov_get_vx ( const mavlink_message_t *  msg)
inlinestatic

Get field vx from global_position_int_cov message.

Returns
Ground X Speed (Latitude), expressed as m/s

Definition at line 383 of file mavlink_msg_global_position_int_cov.h.

static float mavlink_msg_global_position_int_cov_get_vy ( const mavlink_message_t *  msg)
inlinestatic

Get field vy from global_position_int_cov message.

Returns
Ground Y Speed (Longitude), expressed as m/s

Definition at line 393 of file mavlink_msg_global_position_int_cov.h.

static float mavlink_msg_global_position_int_cov_get_vz ( const mavlink_message_t *  msg)
inlinestatic

Get field vz from global_position_int_cov message.

Returns
Ground Z Speed (Altitude), expressed as m/s

Definition at line 403 of file mavlink_msg_global_position_int_cov.h.

static uint16_t mavlink_msg_global_position_int_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,
int32_t  lat,
int32_t  lon,
int32_t  alt,
int32_t  relative_alt,
float  vx,
float  vy,
float  vz,
const float *  covariance 
)
inlinestatic

Pack a global_position_int_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)
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.
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altAltitude in meters, expressed as * 1000 (millimeters), above MSL
relative_altAltitude above ground in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s
vyGround Y Speed (Longitude), expressed as m/s
vzGround Z Speed (Altitude), expressed as m/s
covarianceCovariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 65 of file mavlink_msg_global_position_int_cov.h.

static uint16_t mavlink_msg_global_position_int_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,
int32_t  lat,
int32_t  lon,
int32_t  alt,
int32_t  relative_alt,
float  vx,
float  vy,
float  vz,
const float *  covariance 
)
inlinestatic

Pack a global_position_int_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)
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.
latLatitude, expressed as degrees * 1E7
lonLongitude, expressed as degrees * 1E7
altAltitude in meters, expressed as * 1000 (millimeters), above MSL
relative_altAltitude above ground in meters, expressed as * 1000 (millimeters)
vxGround X Speed (Latitude), expressed as m/s
vyGround Y Speed (Longitude), expressed as m/s
vzGround Z Speed (Altitude), expressed as m/s
covarianceCovariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
Returns
length of the message in bytes (excluding serial stream start sign)

Definition at line 125 of file mavlink_msg_global_position_int_cov.h.



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