3 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64 22 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229 23 #define MAVLINK_MSG_ID_64_LEN 229 25 #define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59 26 #define MAVLINK_MSG_ID_64_CRC 59 28 #define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45 30 #define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \ 31 "LOCAL_POSITION_NED_COV", \ 33 { { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \ 34 { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \ 35 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \ 36 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \ 37 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \ 38 { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \ 39 { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \ 40 { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \ 41 { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \ 42 { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \ 43 { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \ 44 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \ 45 { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \ 72 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)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 88 _mav_put_float_array(buf, 48, covariance, 45);
109 #if MAVLINK_CRC_EXTRA 138 mavlink_message_t* msg,
139 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)
141 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 155 _mav_put_float_array(buf, 48, covariance, 45);
176 #if MAVLINK_CRC_EXTRA 193 return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->
time_boot_ms, local_position_ned_cov->
time_utc, local_position_ned_cov->
estimator_type, local_position_ned_cov->
x, local_position_ned_cov->
y, local_position_ned_cov->
z, local_position_ned_cov->
vx, local_position_ned_cov->
vy, local_position_ned_cov->
vz, local_position_ned_cov->
ax, local_position_ned_cov->
ay, local_position_ned_cov->
az, local_position_ned_cov->
covariance);
207 return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->
time_boot_ms, local_position_ned_cov->
time_utc, local_position_ned_cov->
estimator_type, local_position_ned_cov->
x, local_position_ned_cov->
y, local_position_ned_cov->
z, local_position_ned_cov->
vx, local_position_ned_cov->
vy, local_position_ned_cov->
vz, local_position_ned_cov->
ax, local_position_ned_cov->
ay, local_position_ned_cov->
az, local_position_ned_cov->
covariance);
228 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 230 static inline void mavlink_msg_local_position_ned_cov_send(
mavlink_channel_t chan, 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)
232 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 246 _mav_put_float_array(buf, 48, covariance, 45);
247 #if MAVLINK_CRC_EXTRA 267 #if MAVLINK_CRC_EXTRA 275 #if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN 283 static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, 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)
285 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 286 char *buf = (
char *)msgbuf;
299 _mav_put_float_array(buf, 48, covariance, 45);
300 #if MAVLINK_CRC_EXTRA 320 #if MAVLINK_CRC_EXTRA 341 return _MAV_RETURN_uint32_t(msg, 8);
351 return _MAV_RETURN_uint64_t(msg, 0);
371 return _MAV_RETURN_float(msg, 12);
381 return _MAV_RETURN_float(msg, 16);
391 return _MAV_RETURN_float(msg, 20);
401 return _MAV_RETURN_float(msg, 24);
411 return _MAV_RETURN_float(msg, 28);
421 return _MAV_RETURN_float(msg, 32);
431 return _MAV_RETURN_float(msg, 36);
441 return _MAV_RETURN_float(msg, 40);
451 return _MAV_RETURN_float(msg, 44);
461 return _MAV_RETURN_float_array(msg, covariance, 45, 48);
472 #if MAVLINK_NEED_BYTE_SWAP
#define _mav_put_float(buf, wire_offset, b)
static float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t *msg)
Get field ay from local_position_ned_cov message.
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.
#define _MAV_RETURN_uint8_t(msg, wire_offset)
static float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t *msg)
Get field vy from local_position_ned_cov message.
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV
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.
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.
#define _mav_put_uint8_t(buf, wire_offset, b)
#define _mav_put_uint64_t(buf, wire_offset, b)
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC
#define _MAV_PAYLOAD_NON_CONST(msg)
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.
static float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t *msg)
Get field x from local_position_ned_cov message.
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.
static float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t *msg)
Get field ax from local_position_ned_cov message.
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.
#define _MAV_PAYLOAD(msg)
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.
static float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t *msg)
Get field vx from local_position_ned_cov message.
static float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t *msg)
Get field vz from local_position_ned_cov message.
static float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t *msg)
Get field z from local_position_ned_cov message.
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN
static void mav_array_memcpy(void *dest, const void *src, size_t n)
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.
struct __mavlink_local_position_ned_cov_t mavlink_local_position_ned_cov_t
static float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t *msg)
Get field az from local_position_ned_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 float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t *msg)
Get field y from local_position_ned_cov message.
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.
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.
#define _mav_put_uint32_t(buf, wire_offset, b)