3 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63 20 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185 21 #define MAVLINK_MSG_ID_63_LEN 185 23 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51 24 #define MAVLINK_MSG_ID_63_CRC 51 26 #define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36 28 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \ 29 "GLOBAL_POSITION_INT_COV", \ 31 { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \ 32 { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \ 33 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \ 34 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \ 35 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \ 36 { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \ 37 { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \ 38 { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \ 39 { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \ 40 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \ 41 { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \ 66 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)
68 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 80 _mav_put_float_array(buf, 40, covariance, 36);
126 mavlink_message_t* msg,
127 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)
129 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 141 _mav_put_float_array(buf, 40, covariance, 36);
160 #if MAVLINK_CRC_EXTRA 177 return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->
time_boot_ms, global_position_int_cov->
time_utc, global_position_int_cov->
estimator_type, global_position_int_cov->
lat, global_position_int_cov->
lon, global_position_int_cov->
alt, global_position_int_cov->
relative_alt, global_position_int_cov->
vx, global_position_int_cov->
vy, global_position_int_cov->
vz, global_position_int_cov->
covariance);
191 return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->
time_boot_ms, global_position_int_cov->
time_utc, global_position_int_cov->
estimator_type, global_position_int_cov->
lat, global_position_int_cov->
lon, global_position_int_cov->
alt, global_position_int_cov->
relative_alt, global_position_int_cov->
vx, global_position_int_cov->
vy, global_position_int_cov->
vz, global_position_int_cov->
covariance);
210 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 212 static inline void mavlink_msg_global_position_int_cov_send(
mavlink_channel_t chan, 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)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 226 _mav_put_float_array(buf, 40, covariance, 36);
227 #if MAVLINK_CRC_EXTRA 245 #if MAVLINK_CRC_EXTRA 253 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN 261 static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, 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)
263 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 264 char *buf = (
char *)msgbuf;
275 _mav_put_float_array(buf, 40, covariance, 36);
276 #if MAVLINK_CRC_EXTRA 294 #if MAVLINK_CRC_EXTRA 315 return _MAV_RETURN_uint32_t(msg, 8);
325 return _MAV_RETURN_uint64_t(msg, 0);
345 return _MAV_RETURN_int32_t(msg, 12);
355 return _MAV_RETURN_int32_t(msg, 16);
365 return _MAV_RETURN_int32_t(msg, 20);
375 return _MAV_RETURN_int32_t(msg, 24);
385 return _MAV_RETURN_float(msg, 28);
395 return _MAV_RETURN_float(msg, 32);
405 return _MAV_RETURN_float(msg, 36);
415 return _MAV_RETURN_float_array(msg, covariance, 36, 40);
426 #if MAVLINK_NEED_BYTE_SWAP #define _mav_put_float(buf, wire_offset, b)
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.
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.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC
#define _MAV_RETURN_uint8_t(msg, wire_offset)
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.
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.
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.
struct __mavlink_global_position_int_cov_t mavlink_global_position_int_cov_t
static float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t *msg)
Get field vy from global_position_int_cov message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define _mav_put_int32_t(buf, wire_offset, b)
#define _MAV_PAYLOAD_NON_CONST(msg)
static float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t *msg)
Get field vz from global_position_int_cov message.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV
#define _MAV_PAYLOAD(msg)
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.
static float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t *msg)
Get field vx from global_position_int_cov message.
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.
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN
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.
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.
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.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
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.
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
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.
#define _mav_put_uint32_t(buf, wire_offset, b)
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.