2 // MESSAGE VICON_POSITION_ESTIMATE PACKING
4 #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104
7 typedef struct __mavlink_vicon_position_estimate_t
{
8 uint64_t usec
; /*< [us] Timestamp (UNIX time or time since system boot)*/
9 float x
; /*< [m] Global X position*/
10 float y
; /*< [m] Global Y position*/
11 float z
; /*< [m] Global Z position*/
12 float roll
; /*< [rad] Roll angle*/
13 float pitch
; /*< [rad] Pitch angle*/
14 float yaw
; /*< [rad] Yaw angle*/
15 float covariance
[21]; /*< Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
16 } mavlink_vicon_position_estimate_t
;
18 #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 116
19 #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN 32
20 #define MAVLINK_MSG_ID_104_LEN 116
21 #define MAVLINK_MSG_ID_104_MIN_LEN 32
23 #define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56
24 #define MAVLINK_MSG_ID_104_CRC 56
26 #define MAVLINK_MSG_VICON_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21
28 #if MAVLINK_COMMAND_24BIT
29 #define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \
31 "VICON_POSITION_ESTIMATE", \
33 { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \
34 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \
35 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \
36 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \
37 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \
38 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \
39 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \
40 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vicon_position_estimate_t, covariance) }, \
44 #define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \
45 "VICON_POSITION_ESTIMATE", \
47 { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \
48 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \
49 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \
50 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \
51 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \
52 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \
53 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \
54 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vicon_position_estimate_t, covariance) }, \
60 * @brief Pack a vicon_position_estimate message
61 * @param system_id ID of this system
62 * @param component_id ID of this component (e.g. 200 for IMU)
63 * @param msg The MAVLink message to compress the data into
65 * @param usec [us] Timestamp (UNIX time or time since system boot)
66 * @param x [m] Global X position
67 * @param y [m] Global Y position
68 * @param z [m] Global Z position
69 * @param roll [rad] Roll angle
70 * @param pitch [rad] Pitch angle
71 * @param yaw [rad] Yaw angle
72 * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
73 * @return length of the message in bytes (excluding serial stream start sign)
75 static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
76 uint64_t usec
, float x
, float y
, float z
, float roll
, float pitch
, float yaw
, const float *covariance
)
78 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
79 char buf
[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
];
80 _mav_put_uint64_t(buf
, 0, usec
);
81 _mav_put_float(buf
, 8, x
);
82 _mav_put_float(buf
, 12, y
);
83 _mav_put_float(buf
, 16, z
);
84 _mav_put_float(buf
, 20, roll
);
85 _mav_put_float(buf
, 24, pitch
);
86 _mav_put_float(buf
, 28, yaw
);
87 _mav_put_float_array(buf
, 32, covariance
, 21);
88 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
);
90 mavlink_vicon_position_estimate_t packet
;
98 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*21);
99 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
);
102 msg
->msgid
= MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
;
103 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
107 * @brief Pack a vicon_position_estimate message on a channel
108 * @param system_id ID of this system
109 * @param component_id ID of this component (e.g. 200 for IMU)
110 * @param chan The MAVLink channel this message will be sent over
111 * @param msg The MAVLink message to compress the data into
112 * @param usec [us] Timestamp (UNIX time or time since system boot)
113 * @param x [m] Global X position
114 * @param y [m] Global Y position
115 * @param z [m] Global Z position
116 * @param roll [rad] Roll angle
117 * @param pitch [rad] Pitch angle
118 * @param yaw [rad] Yaw angle
119 * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
120 * @return length of the message in bytes (excluding serial stream start sign)
122 static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
123 mavlink_message_t
* msg
,
124 uint64_t usec
,float x
,float y
,float z
,float roll
,float pitch
,float yaw
,const float *covariance
)
126 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
127 char buf
[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
];
128 _mav_put_uint64_t(buf
, 0, usec
);
129 _mav_put_float(buf
, 8, x
);
130 _mav_put_float(buf
, 12, y
);
131 _mav_put_float(buf
, 16, z
);
132 _mav_put_float(buf
, 20, roll
);
133 _mav_put_float(buf
, 24, pitch
);
134 _mav_put_float(buf
, 28, yaw
);
135 _mav_put_float_array(buf
, 32, covariance
, 21);
136 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
);
138 mavlink_vicon_position_estimate_t packet
;
144 packet
.pitch
= pitch
;
146 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*21);
147 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
);
150 msg
->msgid
= MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
;
151 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
155 * @brief Encode a vicon_position_estimate struct
157 * @param system_id ID of this system
158 * @param component_id ID of this component (e.g. 200 for IMU)
159 * @param msg The MAVLink message to compress the data into
160 * @param vicon_position_estimate C-struct to read the message contents from
162 static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_vicon_position_estimate_t
* vicon_position_estimate
)
164 return mavlink_msg_vicon_position_estimate_pack(system_id
, component_id
, msg
, vicon_position_estimate
->usec
, vicon_position_estimate
->x
, vicon_position_estimate
->y
, vicon_position_estimate
->z
, vicon_position_estimate
->roll
, vicon_position_estimate
->pitch
, vicon_position_estimate
->yaw
, vicon_position_estimate
->covariance
);
168 * @brief Encode a vicon_position_estimate struct on a channel
170 * @param system_id ID of this system
171 * @param component_id ID of this component (e.g. 200 for IMU)
172 * @param chan The MAVLink channel this message will be sent over
173 * @param msg The MAVLink message to compress the data into
174 * @param vicon_position_estimate C-struct to read the message contents from
176 static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_vicon_position_estimate_t
* vicon_position_estimate
)
178 return mavlink_msg_vicon_position_estimate_pack_chan(system_id
, component_id
, chan
, msg
, vicon_position_estimate
->usec
, vicon_position_estimate
->x
, vicon_position_estimate
->y
, vicon_position_estimate
->z
, vicon_position_estimate
->roll
, vicon_position_estimate
->pitch
, vicon_position_estimate
->yaw
, vicon_position_estimate
->covariance
);
182 * @brief Send a vicon_position_estimate message
183 * @param chan MAVLink channel to send the message
185 * @param usec [us] Timestamp (UNIX time or time since system boot)
186 * @param x [m] Global X position
187 * @param y [m] Global Y position
188 * @param z [m] Global Z position
189 * @param roll [rad] Roll angle
190 * @param pitch [rad] Pitch angle
191 * @param yaw [rad] Yaw angle
192 * @param covariance Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
194 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
196 static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan
, uint64_t usec
, float x
, float y
, float z
, float roll
, float pitch
, float yaw
, const float *covariance
)
198 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
199 char buf
[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
];
200 _mav_put_uint64_t(buf
, 0, usec
);
201 _mav_put_float(buf
, 8, x
);
202 _mav_put_float(buf
, 12, y
);
203 _mav_put_float(buf
, 16, z
);
204 _mav_put_float(buf
, 20, roll
);
205 _mav_put_float(buf
, 24, pitch
);
206 _mav_put_float(buf
, 28, yaw
);
207 _mav_put_float_array(buf
, 32, covariance
, 21);
208 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
, buf
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
210 mavlink_vicon_position_estimate_t packet
;
216 packet
.pitch
= pitch
;
218 mav_array_memcpy(packet
.covariance
, covariance
, sizeof(float)*21);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
, (const char *)&packet
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
224 * @brief Send a vicon_position_estimate message
225 * @param chan MAVLink channel to send the message
226 * @param struct The MAVLink struct to serialize
228 static inline void mavlink_msg_vicon_position_estimate_send_struct(mavlink_channel_t chan
, const mavlink_vicon_position_estimate_t
* vicon_position_estimate
)
230 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
231 mavlink_msg_vicon_position_estimate_send(chan
, vicon_position_estimate
->usec
, vicon_position_estimate
->x
, vicon_position_estimate
->y
, vicon_position_estimate
->z
, vicon_position_estimate
->roll
, vicon_position_estimate
->pitch
, vicon_position_estimate
->yaw
, vicon_position_estimate
->covariance
);
233 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
, (const char *)vicon_position_estimate
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
237 #if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
239 This varient of _send() can be used to save stack space by re-using
240 memory from the receive buffer. The caller provides a
241 mavlink_message_t which is the size of a full mavlink message. This
242 is usually the receive buffer for the channel, and allows a reply to an
243 incoming message with minimum stack space usage.
245 static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t usec
, float x
, float y
, float z
, float roll
, float pitch
, float yaw
, const float *covariance
)
247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248 char *buf
= (char *)msgbuf
;
249 _mav_put_uint64_t(buf
, 0, usec
);
250 _mav_put_float(buf
, 8, x
);
251 _mav_put_float(buf
, 12, y
);
252 _mav_put_float(buf
, 16, z
);
253 _mav_put_float(buf
, 20, roll
);
254 _mav_put_float(buf
, 24, pitch
);
255 _mav_put_float(buf
, 28, yaw
);
256 _mav_put_float_array(buf
, 32, covariance
, 21);
257 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
, buf
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
259 mavlink_vicon_position_estimate_t
*packet
= (mavlink_vicon_position_estimate_t
*)msgbuf
;
265 packet
->pitch
= pitch
;
267 mav_array_memcpy(packet
->covariance
, covariance
, sizeof(float)*21);
268 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
, (const char *)packet
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_MIN_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC
);
275 // MESSAGE VICON_POSITION_ESTIMATE UNPACKING
279 * @brief Get field usec from vicon_position_estimate message
281 * @return [us] Timestamp (UNIX time or time since system boot)
283 static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t
* msg
)
285 return _MAV_RETURN_uint64_t(msg
, 0);
289 * @brief Get field x from vicon_position_estimate message
291 * @return [m] Global X position
293 static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t
* msg
)
295 return _MAV_RETURN_float(msg
, 8);
299 * @brief Get field y from vicon_position_estimate message
301 * @return [m] Global Y position
303 static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t
* msg
)
305 return _MAV_RETURN_float(msg
, 12);
309 * @brief Get field z from vicon_position_estimate message
311 * @return [m] Global Z position
313 static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t
* msg
)
315 return _MAV_RETURN_float(msg
, 16);
319 * @brief Get field roll from vicon_position_estimate message
321 * @return [rad] Roll angle
323 static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t
* msg
)
325 return _MAV_RETURN_float(msg
, 20);
329 * @brief Get field pitch from vicon_position_estimate message
331 * @return [rad] Pitch angle
333 static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t
* msg
)
335 return _MAV_RETURN_float(msg
, 24);
339 * @brief Get field yaw from vicon_position_estimate message
341 * @return [rad] Yaw angle
343 static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t
* msg
)
345 return _MAV_RETURN_float(msg
, 28);
349 * @brief Get field covariance from vicon_position_estimate message
351 * @return Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
353 static inline uint16_t mavlink_msg_vicon_position_estimate_get_covariance(const mavlink_message_t
* msg
, float *covariance
)
355 return _MAV_RETURN_float_array(msg
, covariance
, 21, 32);
359 * @brief Decode a vicon_position_estimate message into a struct
361 * @param msg The message to decode
362 * @param vicon_position_estimate C-struct to decode the message contents into
364 static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t
* msg
, mavlink_vicon_position_estimate_t
* vicon_position_estimate
)
366 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
367 vicon_position_estimate
->usec
= mavlink_msg_vicon_position_estimate_get_usec(msg
);
368 vicon_position_estimate
->x
= mavlink_msg_vicon_position_estimate_get_x(msg
);
369 vicon_position_estimate
->y
= mavlink_msg_vicon_position_estimate_get_y(msg
);
370 vicon_position_estimate
->z
= mavlink_msg_vicon_position_estimate_get_z(msg
);
371 vicon_position_estimate
->roll
= mavlink_msg_vicon_position_estimate_get_roll(msg
);
372 vicon_position_estimate
->pitch
= mavlink_msg_vicon_position_estimate_get_pitch(msg
);
373 vicon_position_estimate
->yaw
= mavlink_msg_vicon_position_estimate_get_yaw(msg
);
374 mavlink_msg_vicon_position_estimate_get_covariance(msg
, vicon_position_estimate
->covariance
);
376 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
? msg
->len
: MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
;
377 memset(vicon_position_estimate
, 0, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN
);
378 memcpy(vicon_position_estimate
, _MAV_PAYLOAD(msg
), len
);