3 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT 193
15 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 22
16 #define MAVLINK_MSG_ID_193_LEN 22
18 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC 71
19 #define MAVLINK_MSG_ID_193_CRC 71
23 #define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
24 "EKF_STATUS_REPORT", \
26 { { "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \
27 { "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \
28 { "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \
29 { "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \
30 { "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \
31 { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \
50 static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51 uint16_t
flags,
float velocity_variance,
float pos_horiz_variance,
float pos_vert_variance,
float compass_variance,
float terrain_alt_variance)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97 static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98 mavlink_message_t* msg,
99 uint16_t
flags,
float velocity_variance,
float pos_horiz_variance,
float pos_vert_variance,
float compass_variance,
float terrain_alt_variance)
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
124 #if MAVLINK_CRC_EXTRA
139 static inline uint16_t mavlink_msg_ekf_status_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_ekf_status_report_t* ekf_status_report)
153 static inline uint16_t mavlink_msg_ekf_status_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_ekf_status_report_t* ekf_status_report)
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 static inline void mavlink_msg_ekf_status_report_send(
mavlink_channel_t chan, uint16_t flags,
float velocity_variance,
float pos_horiz_variance,
float pos_vert_variance,
float compass_variance,
float terrain_alt_variance)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 #if MAVLINK_CRC_EXTRA
196 #if MAVLINK_CRC_EXTRA
204 #if MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
212 static inline void mavlink_msg_ekf_status_report_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint16_t flags,
float velocity_variance,
float pos_horiz_variance,
float pos_vert_variance,
float compass_variance,
float terrain_alt_variance)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 char *buf = (
char *)msgbuf;
223 #if MAVLINK_CRC_EXTRA
237 #if MAVLINK_CRC_EXTRA
256 static inline uint16_t mavlink_msg_ekf_status_report_get_flags(
const mavlink_message_t* msg)
258 return _MAV_RETURN_uint16_t(msg, 20);
266 static inline float mavlink_msg_ekf_status_report_get_velocity_variance(
const mavlink_message_t* msg)
268 return _MAV_RETURN_float(msg, 0);
276 static inline float mavlink_msg_ekf_status_report_get_pos_horiz_variance(
const mavlink_message_t* msg)
278 return _MAV_RETURN_float(msg, 4);
286 static inline float mavlink_msg_ekf_status_report_get_pos_vert_variance(
const mavlink_message_t* msg)
288 return _MAV_RETURN_float(msg, 8);
296 static inline float mavlink_msg_ekf_status_report_get_compass_variance(
const mavlink_message_t* msg)
298 return _MAV_RETURN_float(msg, 12);
306 static inline float mavlink_msg_ekf_status_report_get_terrain_alt_variance(
const mavlink_message_t* msg)
308 return _MAV_RETURN_float(msg, 16);
317 static inline void mavlink_msg_ekf_status_report_decode(
const mavlink_message_t* msg,
mavlink_ekf_status_report_t* ekf_status_report)
319 #if MAVLINK_NEED_BYTE_SWAP
320 ekf_status_report->
velocity_variance = mavlink_msg_ekf_status_report_get_velocity_variance(msg);
321 ekf_status_report->
pos_horiz_variance = mavlink_msg_ekf_status_report_get_pos_horiz_variance(msg);
322 ekf_status_report->
pos_vert_variance = mavlink_msg_ekf_status_report_get_pos_vert_variance(msg);
323 ekf_status_report->
compass_variance = mavlink_msg_ekf_status_report_get_compass_variance(msg);
324 ekf_status_report->
terrain_alt_variance = mavlink_msg_ekf_status_report_get_terrain_alt_variance(msg);
325 ekf_status_report->
flags = mavlink_msg_ekf_status_report_get_flags(msg);
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
uint16_t flags
Flags.
Definition: mavlink_msg_ekf_status_report.h:12
float pos_horiz_variance
Horizontal Position variance.
Definition: mavlink_msg_ekf_status_report.h:8
struct __mavlink_ekf_status_report_t mavlink_ekf_status_report_t
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN
Definition: mavlink_msg_ekf_status_report.h:15
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.
Definition: mavlink_helpers.h:105
Definition: mavlink_msg_ekf_status_report.h:5
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
mavlink_channel_t
Definition: mavlink_types.h:178
float terrain_alt_variance
Terrain Altitude variance.
Definition: mavlink_msg_ekf_status_report.h:11
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t flags
Definition: ledstrip.h:11
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT
Definition: mavlink_msg_ekf_status_report.h:3
#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC
Definition: mavlink_msg_ekf_status_report.h:18
float compass_variance
Compass variance.
Definition: mavlink_msg_ekf_status_report.h:10
float velocity_variance
Velocity variance.
Definition: mavlink_msg_ekf_status_report.h:7
float pos_vert_variance
Vertical Position variance.
Definition: mavlink_msg_ekf_status_report.h:9
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
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.
Definition: mavlink_helpers.h:71