Details | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
1702 | - | 1 | // MESSAGE ATTITUDE_QUATERNION PACKING |
2 | |||
3 | #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 |
||
4 | |||
5 | typedef struct __mavlink_attitude_quaternion_t |
||
6 | { |
||
7 | uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) |
||
8 | float q1; ///< Quaternion component 1 |
||
9 | float q2; ///< Quaternion component 2 |
||
10 | float q3; ///< Quaternion component 3 |
||
11 | float q4; ///< Quaternion component 4 |
||
12 | float rollspeed; ///< Roll angular speed (rad/s) |
||
13 | float pitchspeed; ///< Pitch angular speed (rad/s) |
||
14 | float yawspeed; ///< Yaw angular speed (rad/s) |
||
15 | } mavlink_attitude_quaternion_t; |
||
16 | |||
17 | #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 |
||
18 | #define MAVLINK_MSG_ID_31_LEN 32 |
||
19 | |||
20 | |||
21 | |||
22 | #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ |
||
23 | "ATTITUDE_QUATERNION", \ |
||
24 | 8, \ |
||
25 | { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ |
||
26 | { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ |
||
27 | { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ |
||
28 | { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ |
||
29 | { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ |
||
30 | { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ |
||
31 | { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ |
||
32 | { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ |
||
33 | } \ |
||
34 | } |
||
35 | |||
36 | |||
37 | /** |
||
38 | * @brief Pack a attitude_quaternion message |
||
39 | * @param system_id ID of this system |
||
40 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
41 | * @param msg The MAVLink message to compress the data into |
||
42 | * |
||
43 | * @param time_boot_ms Timestamp (milliseconds since system boot) |
||
44 | * @param q1 Quaternion component 1 |
||
45 | * @param q2 Quaternion component 2 |
||
46 | * @param q3 Quaternion component 3 |
||
47 | * @param q4 Quaternion component 4 |
||
48 | * @param rollspeed Roll angular speed (rad/s) |
||
49 | * @param pitchspeed Pitch angular speed (rad/s) |
||
50 | * @param yawspeed Yaw angular speed (rad/s) |
||
51 | * @return length of the message in bytes (excluding serial stream start sign) |
||
52 | */ |
||
53 | static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, |
||
54 | uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) |
||
55 | { |
||
56 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
57 | char buf[32]; |
||
58 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
59 | _mav_put_float(buf, 4, q1); |
||
60 | _mav_put_float(buf, 8, q2); |
||
61 | _mav_put_float(buf, 12, q3); |
||
62 | _mav_put_float(buf, 16, q4); |
||
63 | _mav_put_float(buf, 20, rollspeed); |
||
64 | _mav_put_float(buf, 24, pitchspeed); |
||
65 | _mav_put_float(buf, 28, yawspeed); |
||
66 | |||
67 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); |
||
68 | #else |
||
69 | mavlink_attitude_quaternion_t packet; |
||
70 | packet.time_boot_ms = time_boot_ms; |
||
71 | packet.q1 = q1; |
||
72 | packet.q2 = q2; |
||
73 | packet.q3 = q3; |
||
74 | packet.q4 = q4; |
||
75 | packet.rollspeed = rollspeed; |
||
76 | packet.pitchspeed = pitchspeed; |
||
77 | packet.yawspeed = yawspeed; |
||
78 | |||
79 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); |
||
80 | #endif |
||
81 | |||
82 | msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; |
||
83 | return mavlink_finalize_message(msg, system_id, component_id, 32, 246); |
||
84 | } |
||
85 | |||
86 | /** |
||
87 | * @brief Pack a attitude_quaternion message on a channel |
||
88 | * @param system_id ID of this system |
||
89 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
90 | * @param chan The MAVLink channel this message was sent over |
||
91 | * @param msg The MAVLink message to compress the data into |
||
92 | * @param time_boot_ms Timestamp (milliseconds since system boot) |
||
93 | * @param q1 Quaternion component 1 |
||
94 | * @param q2 Quaternion component 2 |
||
95 | * @param q3 Quaternion component 3 |
||
96 | * @param q4 Quaternion component 4 |
||
97 | * @param rollspeed Roll angular speed (rad/s) |
||
98 | * @param pitchspeed Pitch angular speed (rad/s) |
||
99 | * @param yawspeed Yaw angular speed (rad/s) |
||
100 | * @return length of the message in bytes (excluding serial stream start sign) |
||
101 | */ |
||
102 | static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, |
||
103 | mavlink_message_t* msg, |
||
104 | uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) |
||
105 | { |
||
106 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
107 | char buf[32]; |
||
108 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
109 | _mav_put_float(buf, 4, q1); |
||
110 | _mav_put_float(buf, 8, q2); |
||
111 | _mav_put_float(buf, 12, q3); |
||
112 | _mav_put_float(buf, 16, q4); |
||
113 | _mav_put_float(buf, 20, rollspeed); |
||
114 | _mav_put_float(buf, 24, pitchspeed); |
||
115 | _mav_put_float(buf, 28, yawspeed); |
||
116 | |||
117 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32); |
||
118 | #else |
||
119 | mavlink_attitude_quaternion_t packet; |
||
120 | packet.time_boot_ms = time_boot_ms; |
||
121 | packet.q1 = q1; |
||
122 | packet.q2 = q2; |
||
123 | packet.q3 = q3; |
||
124 | packet.q4 = q4; |
||
125 | packet.rollspeed = rollspeed; |
||
126 | packet.pitchspeed = pitchspeed; |
||
127 | packet.yawspeed = yawspeed; |
||
128 | |||
129 | memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32); |
||
130 | #endif |
||
131 | |||
132 | msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; |
||
133 | return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 246); |
||
134 | } |
||
135 | |||
136 | /** |
||
137 | * @brief Encode a attitude_quaternion struct into a message |
||
138 | * |
||
139 | * @param system_id ID of this system |
||
140 | * @param component_id ID of this component (e.g. 200 for IMU) |
||
141 | * @param msg The MAVLink message to compress the data into |
||
142 | * @param attitude_quaternion C-struct to read the message contents from |
||
143 | */ |
||
144 | static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) |
||
145 | { |
||
146 | return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); |
||
147 | } |
||
148 | |||
149 | /** |
||
150 | * @brief Send a attitude_quaternion message |
||
151 | * @param chan MAVLink channel to send the message |
||
152 | * |
||
153 | * @param time_boot_ms Timestamp (milliseconds since system boot) |
||
154 | * @param q1 Quaternion component 1 |
||
155 | * @param q2 Quaternion component 2 |
||
156 | * @param q3 Quaternion component 3 |
||
157 | * @param q4 Quaternion component 4 |
||
158 | * @param rollspeed Roll angular speed (rad/s) |
||
159 | * @param pitchspeed Pitch angular speed (rad/s) |
||
160 | * @param yawspeed Yaw angular speed (rad/s) |
||
161 | */ |
||
162 | #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS |
||
163 | |||
164 | static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) |
||
165 | { |
||
166 | #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS |
||
167 | char buf[32]; |
||
168 | _mav_put_uint32_t(buf, 0, time_boot_ms); |
||
169 | _mav_put_float(buf, 4, q1); |
||
170 | _mav_put_float(buf, 8, q2); |
||
171 | _mav_put_float(buf, 12, q3); |
||
172 | _mav_put_float(buf, 16, q4); |
||
173 | _mav_put_float(buf, 20, rollspeed); |
||
174 | _mav_put_float(buf, 24, pitchspeed); |
||
175 | _mav_put_float(buf, 28, yawspeed); |
||
176 | |||
177 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, 32, 246); |
||
178 | #else |
||
179 | mavlink_attitude_quaternion_t packet; |
||
180 | packet.time_boot_ms = time_boot_ms; |
||
181 | packet.q1 = q1; |
||
182 | packet.q2 = q2; |
||
183 | packet.q3 = q3; |
||
184 | packet.q4 = q4; |
||
185 | packet.rollspeed = rollspeed; |
||
186 | packet.pitchspeed = pitchspeed; |
||
187 | packet.yawspeed = yawspeed; |
||
188 | |||
189 | _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, 32, 246); |
||
190 | #endif |
||
191 | } |
||
192 | |||
193 | #endif |
||
194 | |||
195 | // MESSAGE ATTITUDE_QUATERNION UNPACKING |
||
196 | |||
197 | |||
198 | /** |
||
199 | * @brief Get field time_boot_ms from attitude_quaternion message |
||
200 | * |
||
201 | * @return Timestamp (milliseconds since system boot) |
||
202 | */ |
||
203 | static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) |
||
204 | { |
||
205 | return _MAV_RETURN_uint32_t(msg, 0); |
||
206 | } |
||
207 | |||
208 | /** |
||
209 | * @brief Get field q1 from attitude_quaternion message |
||
210 | * |
||
211 | * @return Quaternion component 1 |
||
212 | */ |
||
213 | static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) |
||
214 | { |
||
215 | return _MAV_RETURN_float(msg, 4); |
||
216 | } |
||
217 | |||
218 | /** |
||
219 | * @brief Get field q2 from attitude_quaternion message |
||
220 | * |
||
221 | * @return Quaternion component 2 |
||
222 | */ |
||
223 | static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) |
||
224 | { |
||
225 | return _MAV_RETURN_float(msg, 8); |
||
226 | } |
||
227 | |||
228 | /** |
||
229 | * @brief Get field q3 from attitude_quaternion message |
||
230 | * |
||
231 | * @return Quaternion component 3 |
||
232 | */ |
||
233 | static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) |
||
234 | { |
||
235 | return _MAV_RETURN_float(msg, 12); |
||
236 | } |
||
237 | |||
238 | /** |
||
239 | * @brief Get field q4 from attitude_quaternion message |
||
240 | * |
||
241 | * @return Quaternion component 4 |
||
242 | */ |
||
243 | static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) |
||
244 | { |
||
245 | return _MAV_RETURN_float(msg, 16); |
||
246 | } |
||
247 | |||
248 | /** |
||
249 | * @brief Get field rollspeed from attitude_quaternion message |
||
250 | * |
||
251 | * @return Roll angular speed (rad/s) |
||
252 | */ |
||
253 | static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) |
||
254 | { |
||
255 | return _MAV_RETURN_float(msg, 20); |
||
256 | } |
||
257 | |||
258 | /** |
||
259 | * @brief Get field pitchspeed from attitude_quaternion message |
||
260 | * |
||
261 | * @return Pitch angular speed (rad/s) |
||
262 | */ |
||
263 | static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) |
||
264 | { |
||
265 | return _MAV_RETURN_float(msg, 24); |
||
266 | } |
||
267 | |||
268 | /** |
||
269 | * @brief Get field yawspeed from attitude_quaternion message |
||
270 | * |
||
271 | * @return Yaw angular speed (rad/s) |
||
272 | */ |
||
273 | static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) |
||
274 | { |
||
275 | return _MAV_RETURN_float(msg, 28); |
||
276 | } |
||
277 | |||
278 | /** |
||
279 | * @brief Decode a attitude_quaternion message into a struct |
||
280 | * |
||
281 | * @param msg The message to decode |
||
282 | * @param attitude_quaternion C-struct to decode the message contents into |
||
283 | */ |
||
284 | static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) |
||
285 | { |
||
286 | #if MAVLINK_NEED_BYTE_SWAP |
||
287 | attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); |
||
288 | attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); |
||
289 | attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); |
||
290 | attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); |
||
291 | attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); |
||
292 | attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); |
||
293 | attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); |
||
294 | attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); |
||
295 | #else |
||
296 | memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), 32); |
||
297 | #endif |
||
298 | } |