NinjaFlight
 All Data Structures Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
mavlink_msg_ekf_status_report.h
Go to the documentation of this file.
1 // MESSAGE EKF_STATUS_REPORT PACKING
2 
3 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT 193
4 
6 {
12  uint16_t flags;
14 
15 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 22
16 #define MAVLINK_MSG_ID_193_LEN 22
17 
18 #define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC 71
19 #define MAVLINK_MSG_ID_193_CRC 71
20 
21 
22 
23 #define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
24  "EKF_STATUS_REPORT", \
25  6, \
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) }, \
32  } \
33 }
34 
35 
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)
52 {
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55  _mav_put_float(buf, 0, velocity_variance);
56  _mav_put_float(buf, 4, pos_horiz_variance);
57  _mav_put_float(buf, 8, pos_vert_variance);
58  _mav_put_float(buf, 12, compass_variance);
59  _mav_put_float(buf, 16, terrain_alt_variance);
60  _mav_put_uint16_t(buf, 20, flags);
61 
63 #else
65  packet.velocity_variance = velocity_variance;
66  packet.pos_horiz_variance = pos_horiz_variance;
67  packet.pos_vert_variance = pos_vert_variance;
68  packet.compass_variance = compass_variance;
69  packet.terrain_alt_variance = terrain_alt_variance;
70  packet.flags = flags;
71 
73 #endif
74 
76 #if MAVLINK_CRC_EXTRA
78 #else
79  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
80 #endif
81 }
82 
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)
100 {
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103  _mav_put_float(buf, 0, velocity_variance);
104  _mav_put_float(buf, 4, pos_horiz_variance);
105  _mav_put_float(buf, 8, pos_vert_variance);
106  _mav_put_float(buf, 12, compass_variance);
107  _mav_put_float(buf, 16, terrain_alt_variance);
108  _mav_put_uint16_t(buf, 20, flags);
109 
111 #else
113  packet.velocity_variance = velocity_variance;
114  packet.pos_horiz_variance = pos_horiz_variance;
115  packet.pos_vert_variance = pos_vert_variance;
116  packet.compass_variance = compass_variance;
117  packet.terrain_alt_variance = terrain_alt_variance;
118  packet.flags = flags;
119 
121 #endif
122 
124 #if MAVLINK_CRC_EXTRA
126 #else
127  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
128 #endif
129 }
130 
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)
140 {
141  return mavlink_msg_ekf_status_report_pack(system_id, component_id, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance);
142 }
143 
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)
154 {
155  return mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, chan, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance);
156 }
157 
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
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)
172 {
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
175  _mav_put_float(buf, 0, velocity_variance);
176  _mav_put_float(buf, 4, pos_horiz_variance);
177  _mav_put_float(buf, 8, pos_vert_variance);
178  _mav_put_float(buf, 12, compass_variance);
179  _mav_put_float(buf, 16, terrain_alt_variance);
180  _mav_put_uint16_t(buf, 20, flags);
181 
182 #if MAVLINK_CRC_EXTRA
184 #else
185  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
186 #endif
187 #else
189  packet.velocity_variance = velocity_variance;
190  packet.pos_horiz_variance = pos_horiz_variance;
191  packet.pos_vert_variance = pos_vert_variance;
192  packet.compass_variance = compass_variance;
193  packet.terrain_alt_variance = terrain_alt_variance;
194  packet.flags = flags;
195 
196 #if MAVLINK_CRC_EXTRA
197  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)&packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
198 #else
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)&packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
200 #endif
201 #endif
202 }
203 
204 #if MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
205 /*
206  This varient of _send() can be used to save stack space by re-using
207  memory from the receive buffer. The caller provides a
208  mavlink_message_t which is the size of a full mavlink message. This
209  is usually the receive buffer for the channel, and allows a reply to an
210  incoming message with minimum stack space usage.
211  */
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)
213 {
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215  char *buf = (char *)msgbuf;
216  _mav_put_float(buf, 0, velocity_variance);
217  _mav_put_float(buf, 4, pos_horiz_variance);
218  _mav_put_float(buf, 8, pos_vert_variance);
219  _mav_put_float(buf, 12, compass_variance);
220  _mav_put_float(buf, 16, terrain_alt_variance);
221  _mav_put_uint16_t(buf, 20, flags);
222 
223 #if MAVLINK_CRC_EXTRA
225 #else
226  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
227 #endif
228 #else
230  packet->velocity_variance = velocity_variance;
231  packet->pos_horiz_variance = pos_horiz_variance;
232  packet->pos_vert_variance = pos_vert_variance;
233  packet->compass_variance = compass_variance;
234  packet->terrain_alt_variance = terrain_alt_variance;
235  packet->flags = flags;
236 
237 #if MAVLINK_CRC_EXTRA
238  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
239 #else
240  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
241 #endif
242 #endif
243 }
244 #endif
245 
246 #endif
247 
248 // MESSAGE EKF_STATUS_REPORT UNPACKING
249 
250 
256 static inline uint16_t mavlink_msg_ekf_status_report_get_flags(const mavlink_message_t* msg)
257 {
258  return _MAV_RETURN_uint16_t(msg, 20);
259 }
260 
266 static inline float mavlink_msg_ekf_status_report_get_velocity_variance(const mavlink_message_t* msg)
267 {
268  return _MAV_RETURN_float(msg, 0);
269 }
270 
276 static inline float mavlink_msg_ekf_status_report_get_pos_horiz_variance(const mavlink_message_t* msg)
277 {
278  return _MAV_RETURN_float(msg, 4);
279 }
280 
286 static inline float mavlink_msg_ekf_status_report_get_pos_vert_variance(const mavlink_message_t* msg)
287 {
288  return _MAV_RETURN_float(msg, 8);
289 }
290 
296 static inline float mavlink_msg_ekf_status_report_get_compass_variance(const mavlink_message_t* msg)
297 {
298  return _MAV_RETURN_float(msg, 12);
299 }
300 
306 static inline float mavlink_msg_ekf_status_report_get_terrain_alt_variance(const mavlink_message_t* msg)
307 {
308  return _MAV_RETURN_float(msg, 16);
309 }
310 
317 static inline void mavlink_msg_ekf_status_report_decode(const mavlink_message_t* msg, mavlink_ekf_status_report_t* ekf_status_report)
318 {
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);
326 #else
327  memcpy(ekf_status_report, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
328 #endif
329 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:145
uint16_t flags
Definition: ledstrip.h:11
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139