1 // MESSAGE ATT_POS_MOCAP PACKING
3 #define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
5 typedef struct __mavlink_att_pos_mocap_t
7 uint64_t time_usec
; ///< Timestamp (micros since boot or Unix epoch)
8 float q
[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
9 float x
; ///< X position in meters (NED)
10 float y
; ///< Y position in meters (NED)
11 float z
; ///< Z position in meters (NED)
12 } mavlink_att_pos_mocap_t
;
14 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
15 #define MAVLINK_MSG_ID_138_LEN 36
17 #define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109
18 #define MAVLINK_MSG_ID_138_CRC 109
20 #define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4
22 #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
25 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
26 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
27 { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
28 { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
29 { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
35 * @brief Pack a att_pos_mocap message
36 * @param system_id ID of this system
37 * @param component_id ID of this component (e.g. 200 for IMU)
38 * @param msg The MAVLink message to compress the data into
40 * @param time_usec Timestamp (micros since boot or Unix epoch)
41 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
42 * @param x X position in meters (NED)
43 * @param y Y position in meters (NED)
44 * @param z Z position in meters (NED)
45 * @return length of the message in bytes (excluding serial stream start sign)
47 static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
48 uint64_t time_usec
, const float *q
, float x
, float y
, float z
)
50 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51 char buf
[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
];
52 _mav_put_uint64_t(buf
, 0, time_usec
);
53 _mav_put_float(buf
, 24, x
);
54 _mav_put_float(buf
, 28, y
);
55 _mav_put_float(buf
, 32, z
);
56 _mav_put_float_array(buf
, 8, q
, 4);
57 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
59 mavlink_att_pos_mocap_t packet
;
60 packet
.time_usec
= time_usec
;
64 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
68 msg
->msgid
= MAVLINK_MSG_ID_ATT_POS_MOCAP
;
70 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
72 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
77 * @brief Pack a att_pos_mocap message on a channel
78 * @param system_id ID of this system
79 * @param component_id ID of this component (e.g. 200 for IMU)
80 * @param chan The MAVLink channel this message will be sent over
81 * @param msg The MAVLink message to compress the data into
82 * @param time_usec Timestamp (micros since boot or Unix epoch)
83 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
84 * @param x X position in meters (NED)
85 * @param y Y position in meters (NED)
86 * @param z Z position in meters (NED)
87 * @return length of the message in bytes (excluding serial stream start sign)
89 static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
90 mavlink_message_t
* msg
,
91 uint64_t time_usec
,const float *q
,float x
,float y
,float z
)
93 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
94 char buf
[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
];
95 _mav_put_uint64_t(buf
, 0, time_usec
);
96 _mav_put_float(buf
, 24, x
);
97 _mav_put_float(buf
, 28, y
);
98 _mav_put_float(buf
, 32, z
);
99 _mav_put_float_array(buf
, 8, q
, 4);
100 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
102 mavlink_att_pos_mocap_t packet
;
103 packet
.time_usec
= time_usec
;
107 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
108 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
111 msg
->msgid
= MAVLINK_MSG_ID_ATT_POS_MOCAP
;
112 #if MAVLINK_CRC_EXTRA
113 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
115 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
120 * @brief Encode a att_pos_mocap struct
122 * @param system_id ID of this system
123 * @param component_id ID of this component (e.g. 200 for IMU)
124 * @param msg The MAVLink message to compress the data into
125 * @param att_pos_mocap C-struct to read the message contents from
127 static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_att_pos_mocap_t
* att_pos_mocap
)
129 return mavlink_msg_att_pos_mocap_pack(system_id
, component_id
, msg
, att_pos_mocap
->time_usec
, att_pos_mocap
->q
, att_pos_mocap
->x
, att_pos_mocap
->y
, att_pos_mocap
->z
);
133 * @brief Encode a att_pos_mocap struct on a channel
135 * @param system_id ID of this system
136 * @param component_id ID of this component (e.g. 200 for IMU)
137 * @param chan The MAVLink channel this message will be sent over
138 * @param msg The MAVLink message to compress the data into
139 * @param att_pos_mocap C-struct to read the message contents from
141 static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_att_pos_mocap_t
* att_pos_mocap
)
143 return mavlink_msg_att_pos_mocap_pack_chan(system_id
, component_id
, chan
, msg
, att_pos_mocap
->time_usec
, att_pos_mocap
->q
, att_pos_mocap
->x
, att_pos_mocap
->y
, att_pos_mocap
->z
);
147 * @brief Send a att_pos_mocap message
148 * @param chan MAVLink channel to send the message
150 * @param time_usec Timestamp (micros since boot or Unix epoch)
151 * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
152 * @param x X position in meters (NED)
153 * @param y Y position in meters (NED)
154 * @param z Z position in meters (NED)
156 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
158 static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan
, uint64_t time_usec
, const float *q
, float x
, float y
, float z
)
160 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
161 char buf
[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
];
162 _mav_put_uint64_t(buf
, 0, time_usec
);
163 _mav_put_float(buf
, 24, x
);
164 _mav_put_float(buf
, 28, y
);
165 _mav_put_float(buf
, 32, z
);
166 _mav_put_float_array(buf
, 8, q
, 4);
167 #if MAVLINK_CRC_EXTRA
168 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
170 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
173 mavlink_att_pos_mocap_t packet
;
174 packet
.time_usec
= time_usec
;
178 mav_array_memcpy(packet
.q
, q
, sizeof(float)*4);
179 #if MAVLINK_CRC_EXTRA
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, (const char *)&packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
182 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, (const char *)&packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
187 #if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
189 This varient of _send() can be used to save stack space by re-using
190 memory from the receive buffer. The caller provides a
191 mavlink_message_t which is the size of a full mavlink message. This
192 is usually the receive buffer for the channel, and allows a reply to an
193 incoming message with minimum stack space usage.
195 static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint64_t time_usec
, const float *q
, float x
, float y
, float z
)
197 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
198 char *buf
= (char *)msgbuf
;
199 _mav_put_uint64_t(buf
, 0, time_usec
);
200 _mav_put_float(buf
, 24, x
);
201 _mav_put_float(buf
, 28, y
);
202 _mav_put_float(buf
, 32, z
);
203 _mav_put_float_array(buf
, 8, q
, 4);
204 #if MAVLINK_CRC_EXTRA
205 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
207 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, buf
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
210 mavlink_att_pos_mocap_t
*packet
= (mavlink_att_pos_mocap_t
*)msgbuf
;
211 packet
->time_usec
= time_usec
;
215 mav_array_memcpy(packet
->q
, q
, sizeof(float)*4);
216 #if MAVLINK_CRC_EXTRA
217 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, (const char *)packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC
);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATT_POS_MOCAP
, (const char *)packet
, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);
227 // MESSAGE ATT_POS_MOCAP UNPACKING
231 * @brief Get field time_usec from att_pos_mocap message
233 * @return Timestamp (micros since boot or Unix epoch)
235 static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t
* msg
)
237 return _MAV_RETURN_uint64_t(msg
, 0);
241 * @brief Get field q from att_pos_mocap message
243 * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
245 static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t
* msg
, float *q
)
247 return _MAV_RETURN_float_array(msg
, q
, 4, 8);
251 * @brief Get field x from att_pos_mocap message
253 * @return X position in meters (NED)
255 static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t
* msg
)
257 return _MAV_RETURN_float(msg
, 24);
261 * @brief Get field y from att_pos_mocap message
263 * @return Y position in meters (NED)
265 static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t
* msg
)
267 return _MAV_RETURN_float(msg
, 28);
271 * @brief Get field z from att_pos_mocap message
273 * @return Z position in meters (NED)
275 static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t
* msg
)
277 return _MAV_RETURN_float(msg
, 32);
281 * @brief Decode a att_pos_mocap message into a struct
283 * @param msg The message to decode
284 * @param att_pos_mocap C-struct to decode the message contents into
286 static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t
* msg
, mavlink_att_pos_mocap_t
* att_pos_mocap
)
288 #if MAVLINK_NEED_BYTE_SWAP
289 att_pos_mocap
->time_usec
= mavlink_msg_att_pos_mocap_get_time_usec(msg
);
290 mavlink_msg_att_pos_mocap_get_q(msg
, att_pos_mocap
->q
);
291 att_pos_mocap
->x
= mavlink_msg_att_pos_mocap_get_x(msg
);
292 att_pos_mocap
->y
= mavlink_msg_att_pos_mocap_get_y(msg
);
293 att_pos_mocap
->z
= mavlink_msg_att_pos_mocap_get_z(msg
);
295 memcpy(att_pos_mocap
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN
);