Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / lib / main / MAVLink / common / mavlink_msg_attitude_quaternion_cov.h
blobbc2351aa3cfbe0038a881ab0213e5b183dd1be61
1 #pragma once
2 // MESSAGE ATTITUDE_QUATERNION_COV PACKING
4 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
7 typedef struct __mavlink_attitude_quaternion_cov_t {
8 uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/
10 float rollspeed; /*< [rad/s] Roll angular speed*/
11 float pitchspeed; /*< [rad/s] Pitch angular speed*/
12 float yawspeed; /*< [rad/s] Yaw angular speed*/
13 float covariance[9]; /*< Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
14 } mavlink_attitude_quaternion_cov_t;
16 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 72
17 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN 72
18 #define MAVLINK_MSG_ID_61_LEN 72
19 #define MAVLINK_MSG_ID_61_MIN_LEN 72
21 #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 167
22 #define MAVLINK_MSG_ID_61_CRC 167
24 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
25 #define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
27 #if MAVLINK_COMMAND_24BIT
28 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
29 61, \
30 "ATTITUDE_QUATERNION_COV", \
31 6, \
32 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \
33 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
34 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
35 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
36 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
37 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
38 } \
40 #else
41 #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
42 "ATTITUDE_QUATERNION_COV", \
43 6, \
44 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_usec) }, \
45 { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
46 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
47 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
48 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
49 { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 36, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
50 } \
52 #endif
54 /**
55 * @brief Pack a attitude_quaternion_cov message
56 * @param system_id ID of this system
57 * @param component_id ID of this component (e.g. 200 for IMU)
58 * @param msg The MAVLink message to compress the data into
60 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
61 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
62 * @param rollspeed [rad/s] Roll angular speed
63 * @param pitchspeed [rad/s] Pitch angular speed
64 * @param yawspeed [rad/s] Yaw angular speed
65 * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
66 * @return length of the message in bytes (excluding serial stream start sign)
68 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
69 uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
72 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
73 _mav_put_uint64_t(buf, 0, time_usec);
74 _mav_put_float(buf, 24, rollspeed);
75 _mav_put_float(buf, 28, pitchspeed);
76 _mav_put_float(buf, 32, yawspeed);
77 _mav_put_float_array(buf, 8, q, 4);
78 _mav_put_float_array(buf, 36, covariance, 9);
79 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
80 #else
81 mavlink_attitude_quaternion_cov_t packet;
82 packet.time_usec = time_usec;
83 packet.rollspeed = rollspeed;
84 packet.pitchspeed = pitchspeed;
85 packet.yawspeed = yawspeed;
86 mav_array_memcpy(packet.q, q, sizeof(float)*4);
87 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
88 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
89 #endif
91 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
92 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
95 /**
96 * @brief Pack a attitude_quaternion_cov message on a channel
97 * @param system_id ID of this system
98 * @param component_id ID of this component (e.g. 200 for IMU)
99 * @param chan The MAVLink channel this message will be sent over
100 * @param msg The MAVLink message to compress the data into
101 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
102 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
103 * @param rollspeed [rad/s] Roll angular speed
104 * @param pitchspeed [rad/s] Pitch angular speed
105 * @param yawspeed [rad/s] Yaw angular speed
106 * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
107 * @return length of the message in bytes (excluding serial stream start sign)
109 static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110 mavlink_message_t* msg,
111 uint64_t time_usec,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance)
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
114 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
115 _mav_put_uint64_t(buf, 0, time_usec);
116 _mav_put_float(buf, 24, rollspeed);
117 _mav_put_float(buf, 28, pitchspeed);
118 _mav_put_float(buf, 32, yawspeed);
119 _mav_put_float_array(buf, 8, q, 4);
120 _mav_put_float_array(buf, 36, covariance, 9);
121 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
122 #else
123 mavlink_attitude_quaternion_cov_t packet;
124 packet.time_usec = time_usec;
125 packet.rollspeed = rollspeed;
126 packet.pitchspeed = pitchspeed;
127 packet.yawspeed = yawspeed;
128 mav_array_memcpy(packet.q, q, sizeof(float)*4);
129 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
130 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
131 #endif
133 msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
134 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
138 * @brief Encode a attitude_quaternion_cov struct
140 * @param system_id ID of this system
141 * @param component_id ID of this component (e.g. 200 for IMU)
142 * @param msg The MAVLink message to compress the data into
143 * @param attitude_quaternion_cov C-struct to read the message contents from
145 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
147 return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
151 * @brief Encode a attitude_quaternion_cov struct on a channel
153 * @param system_id ID of this system
154 * @param component_id ID of this component (e.g. 200 for IMU)
155 * @param chan The MAVLink channel this message will be sent over
156 * @param msg The MAVLink message to compress the data into
157 * @param attitude_quaternion_cov C-struct to read the message contents from
159 static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
161 return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
165 * @brief Send a attitude_quaternion_cov message
166 * @param chan MAVLink channel to send the message
168 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
169 * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
170 * @param rollspeed [rad/s] Roll angular speed
171 * @param pitchspeed [rad/s] Pitch angular speed
172 * @param yawspeed [rad/s] Yaw angular speed
173 * @param covariance Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
175 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
177 static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
179 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
180 char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
181 _mav_put_uint64_t(buf, 0, time_usec);
182 _mav_put_float(buf, 24, rollspeed);
183 _mav_put_float(buf, 28, pitchspeed);
184 _mav_put_float(buf, 32, yawspeed);
185 _mav_put_float_array(buf, 8, q, 4);
186 _mav_put_float_array(buf, 36, covariance, 9);
187 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
188 #else
189 mavlink_attitude_quaternion_cov_t packet;
190 packet.time_usec = time_usec;
191 packet.rollspeed = rollspeed;
192 packet.pitchspeed = pitchspeed;
193 packet.yawspeed = yawspeed;
194 mav_array_memcpy(packet.q, q, sizeof(float)*4);
195 mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
196 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
197 #endif
201 * @brief Send a attitude_quaternion_cov message
202 * @param chan MAVLink channel to send the message
203 * @param struct The MAVLink struct to serialize
205 static inline void mavlink_msg_attitude_quaternion_cov_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
207 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
208 mavlink_msg_attitude_quaternion_cov_send(chan, attitude_quaternion_cov->time_usec, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
209 #else
210 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)attitude_quaternion_cov, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
211 #endif
214 #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
216 This varient of _send() can be used to save stack space by re-using
217 memory from the receive buffer. The caller provides a
218 mavlink_message_t which is the size of a full mavlink message. This
219 is usually the receive buffer for the channel, and allows a reply to an
220 incoming message with minimum stack space usage.
222 static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
224 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 char *buf = (char *)msgbuf;
226 _mav_put_uint64_t(buf, 0, time_usec);
227 _mav_put_float(buf, 24, rollspeed);
228 _mav_put_float(buf, 28, pitchspeed);
229 _mav_put_float(buf, 32, yawspeed);
230 _mav_put_float_array(buf, 8, q, 4);
231 _mav_put_float_array(buf, 36, covariance, 9);
232 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
233 #else
234 mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf;
235 packet->time_usec = time_usec;
236 packet->rollspeed = rollspeed;
237 packet->pitchspeed = pitchspeed;
238 packet->yawspeed = yawspeed;
239 mav_array_memcpy(packet->q, q, sizeof(float)*4);
240 mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9);
241 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
242 #endif
244 #endif
246 #endif
248 // MESSAGE ATTITUDE_QUATERNION_COV UNPACKING
252 * @brief Get field time_usec from attitude_quaternion_cov message
254 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
256 static inline uint64_t mavlink_msg_attitude_quaternion_cov_get_time_usec(const mavlink_message_t* msg)
258 return _MAV_RETURN_uint64_t(msg, 0);
262 * @brief Get field q from attitude_quaternion_cov message
264 * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
266 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q)
268 return _MAV_RETURN_float_array(msg, q, 4, 8);
272 * @brief Get field rollspeed from attitude_quaternion_cov message
274 * @return [rad/s] Roll angular speed
276 static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg)
278 return _MAV_RETURN_float(msg, 24);
282 * @brief Get field pitchspeed from attitude_quaternion_cov message
284 * @return [rad/s] Pitch angular speed
286 static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg)
288 return _MAV_RETURN_float(msg, 28);
292 * @brief Get field yawspeed from attitude_quaternion_cov message
294 * @return [rad/s] Yaw angular speed
296 static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg)
298 return _MAV_RETURN_float(msg, 32);
302 * @brief Get field covariance from attitude_quaternion_cov message
304 * @return Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
306 static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
308 return _MAV_RETURN_float_array(msg, covariance, 9, 36);
312 * @brief Decode a attitude_quaternion_cov message into a struct
314 * @param msg The message to decode
315 * @param attitude_quaternion_cov C-struct to decode the message contents into
317 static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
319 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
320 attitude_quaternion_cov->time_usec = mavlink_msg_attitude_quaternion_cov_get_time_usec(msg);
321 mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q);
322 attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg);
323 attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg);
324 attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg);
325 mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance);
326 #else
327 uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN;
328 memset(attitude_quaternion_cov, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
329 memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), len);
330 #endif