2 // MESSAGE ATTITUDE PACKING
4 #define MAVLINK_MSG_ID_ATTITUDE 30
7 typedef struct __mavlink_attitude_t
{
8 uint32_t time_boot_ms
; /*< Timestamp (milliseconds since system boot)*/
9 float roll
; /*< Roll angle (rad, -pi..+pi)*/
10 float pitch
; /*< Pitch angle (rad, -pi..+pi)*/
11 float yaw
; /*< Yaw angle (rad, -pi..+pi)*/
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_t
;
17 #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
18 #define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28
19 #define MAVLINK_MSG_ID_30_LEN 28
20 #define MAVLINK_MSG_ID_30_MIN_LEN 28
22 #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
23 #define MAVLINK_MSG_ID_30_CRC 39
27 #if MAVLINK_COMMAND_24BIT
28 #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
32 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
33 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
34 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
35 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
36 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
37 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
38 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
42 #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
45 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
46 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
47 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
48 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
49 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
50 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
51 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
57 * @brief Pack a attitude message
58 * @param system_id ID of this system
59 * @param component_id ID of this component (e.g. 200 for IMU)
60 * @param msg The MAVLink message to compress the data into
62 * @param time_boot_ms Timestamp (milliseconds since system boot)
63 * @param roll Roll angle (rad, -pi..+pi)
64 * @param pitch Pitch angle (rad, -pi..+pi)
65 * @param yaw Yaw angle (rad, -pi..+pi)
66 * @param rollspeed Roll angular speed (rad/s)
67 * @param pitchspeed Pitch angular speed (rad/s)
68 * @param yawspeed Yaw angular speed (rad/s)
69 * @return length of the message in bytes (excluding serial stream start sign)
71 static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
72 uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
)
74 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
75 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
76 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
77 _mav_put_float(buf
, 4, roll
);
78 _mav_put_float(buf
, 8, pitch
);
79 _mav_put_float(buf
, 12, yaw
);
80 _mav_put_float(buf
, 16, rollspeed
);
81 _mav_put_float(buf
, 20, pitchspeed
);
82 _mav_put_float(buf
, 24, yawspeed
);
84 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
86 mavlink_attitude_t packet
;
87 packet
.time_boot_ms
= time_boot_ms
;
91 packet
.rollspeed
= rollspeed
;
92 packet
.pitchspeed
= pitchspeed
;
93 packet
.yawspeed
= yawspeed
;
95 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
98 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE
;
99 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
103 * @brief Pack a attitude message on a channel
104 * @param system_id ID of this system
105 * @param component_id ID of this component (e.g. 200 for IMU)
106 * @param chan The MAVLink channel this message will be sent over
107 * @param msg The MAVLink message to compress the data into
108 * @param time_boot_ms Timestamp (milliseconds since system boot)
109 * @param roll Roll angle (rad, -pi..+pi)
110 * @param pitch Pitch angle (rad, -pi..+pi)
111 * @param yaw Yaw angle (rad, -pi..+pi)
112 * @param rollspeed Roll angular speed (rad/s)
113 * @param pitchspeed Pitch angular speed (rad/s)
114 * @param yawspeed Yaw angular speed (rad/s)
115 * @return length of the message in bytes (excluding serial stream start sign)
117 static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
118 mavlink_message_t
* msg
,
119 uint32_t time_boot_ms
,float roll
,float pitch
,float yaw
,float rollspeed
,float pitchspeed
,float yawspeed
)
121 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
122 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
123 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
124 _mav_put_float(buf
, 4, roll
);
125 _mav_put_float(buf
, 8, pitch
);
126 _mav_put_float(buf
, 12, yaw
);
127 _mav_put_float(buf
, 16, rollspeed
);
128 _mav_put_float(buf
, 20, pitchspeed
);
129 _mav_put_float(buf
, 24, yawspeed
);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
133 mavlink_attitude_t packet
;
134 packet
.time_boot_ms
= time_boot_ms
;
136 packet
.pitch
= pitch
;
138 packet
.rollspeed
= rollspeed
;
139 packet
.pitchspeed
= pitchspeed
;
140 packet
.yawspeed
= yawspeed
;
142 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
145 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE
;
146 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
150 * @brief Encode a attitude struct
152 * @param system_id ID of this system
153 * @param component_id ID of this component (e.g. 200 for IMU)
154 * @param msg The MAVLink message to compress the data into
155 * @param attitude C-struct to read the message contents from
157 static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_attitude_t
* attitude
)
159 return mavlink_msg_attitude_pack(system_id
, component_id
, msg
, attitude
->time_boot_ms
, attitude
->roll
, attitude
->pitch
, attitude
->yaw
, attitude
->rollspeed
, attitude
->pitchspeed
, attitude
->yawspeed
);
163 * @brief Encode a attitude struct on a channel
165 * @param system_id ID of this system
166 * @param component_id ID of this component (e.g. 200 for IMU)
167 * @param chan The MAVLink channel this message will be sent over
168 * @param msg The MAVLink message to compress the data into
169 * @param attitude C-struct to read the message contents from
171 static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_attitude_t
* attitude
)
173 return mavlink_msg_attitude_pack_chan(system_id
, component_id
, chan
, msg
, attitude
->time_boot_ms
, attitude
->roll
, attitude
->pitch
, attitude
->yaw
, attitude
->rollspeed
, attitude
->pitchspeed
, attitude
->yawspeed
);
177 * @brief Send a attitude message
178 * @param chan MAVLink channel to send the message
180 * @param time_boot_ms Timestamp (milliseconds since system boot)
181 * @param roll Roll angle (rad, -pi..+pi)
182 * @param pitch Pitch angle (rad, -pi..+pi)
183 * @param yaw Yaw angle (rad, -pi..+pi)
184 * @param rollspeed Roll angular speed (rad/s)
185 * @param pitchspeed Pitch angular speed (rad/s)
186 * @param yawspeed Yaw angular speed (rad/s)
188 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
190 static inline void mavlink_msg_attitude_send(mavlink_channel_t chan
, uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
)
192 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
194 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
195 _mav_put_float(buf
, 4, roll
);
196 _mav_put_float(buf
, 8, pitch
);
197 _mav_put_float(buf
, 12, yaw
);
198 _mav_put_float(buf
, 16, rollspeed
);
199 _mav_put_float(buf
, 20, pitchspeed
);
200 _mav_put_float(buf
, 24, yawspeed
);
202 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
204 mavlink_attitude_t packet
;
205 packet
.time_boot_ms
= time_boot_ms
;
207 packet
.pitch
= pitch
;
209 packet
.rollspeed
= rollspeed
;
210 packet
.pitchspeed
= pitchspeed
;
211 packet
.yawspeed
= yawspeed
;
213 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
218 * @brief Send a attitude message
219 * @param chan MAVLink channel to send the message
220 * @param struct The MAVLink struct to serialize
222 static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan
, const mavlink_attitude_t
* attitude
)
224 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
225 mavlink_msg_attitude_send(chan
, attitude
->time_boot_ms
, attitude
->roll
, attitude
->pitch
, attitude
->yaw
, attitude
->rollspeed
, attitude
->pitchspeed
, attitude
->yawspeed
);
227 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)attitude
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
231 #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
233 This varient of _send() can be used to save stack space by re-using
234 memory from the receive buffer. The caller provides a
235 mavlink_message_t which is the size of a full mavlink message. This
236 is usually the receive buffer for the channel, and allows a reply to an
237 incoming message with minimum stack space usage.
239 static inline void mavlink_msg_attitude_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
)
241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
242 char *buf
= (char *)msgbuf
;
243 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
244 _mav_put_float(buf
, 4, roll
);
245 _mav_put_float(buf
, 8, pitch
);
246 _mav_put_float(buf
, 12, yaw
);
247 _mav_put_float(buf
, 16, rollspeed
);
248 _mav_put_float(buf
, 20, pitchspeed
);
249 _mav_put_float(buf
, 24, yawspeed
);
251 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
253 mavlink_attitude_t
*packet
= (mavlink_attitude_t
*)msgbuf
;
254 packet
->time_boot_ms
= time_boot_ms
;
256 packet
->pitch
= pitch
;
258 packet
->rollspeed
= rollspeed
;
259 packet
->pitchspeed
= pitchspeed
;
260 packet
->yawspeed
= yawspeed
;
262 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
269 // MESSAGE ATTITUDE UNPACKING
273 * @brief Get field time_boot_ms from attitude message
275 * @return Timestamp (milliseconds since system boot)
277 static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t
* msg
)
279 return _MAV_RETURN_uint32_t(msg
, 0);
283 * @brief Get field roll from attitude message
285 * @return Roll angle (rad, -pi..+pi)
287 static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t
* msg
)
289 return _MAV_RETURN_float(msg
, 4);
293 * @brief Get field pitch from attitude message
295 * @return Pitch angle (rad, -pi..+pi)
297 static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t
* msg
)
299 return _MAV_RETURN_float(msg
, 8);
303 * @brief Get field yaw from attitude message
305 * @return Yaw angle (rad, -pi..+pi)
307 static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t
* msg
)
309 return _MAV_RETURN_float(msg
, 12);
313 * @brief Get field rollspeed from attitude message
315 * @return Roll angular speed (rad/s)
317 static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t
* msg
)
319 return _MAV_RETURN_float(msg
, 16);
323 * @brief Get field pitchspeed from attitude message
325 * @return Pitch angular speed (rad/s)
327 static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t
* msg
)
329 return _MAV_RETURN_float(msg
, 20);
333 * @brief Get field yawspeed from attitude message
335 * @return Yaw angular speed (rad/s)
337 static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t
* msg
)
339 return _MAV_RETURN_float(msg
, 24);
343 * @brief Decode a attitude message into a struct
345 * @param msg The message to decode
346 * @param attitude C-struct to decode the message contents into
348 static inline void mavlink_msg_attitude_decode(const mavlink_message_t
* msg
, mavlink_attitude_t
* attitude
)
350 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
351 attitude
->time_boot_ms
= mavlink_msg_attitude_get_time_boot_ms(msg
);
352 attitude
->roll
= mavlink_msg_attitude_get_roll(msg
);
353 attitude
->pitch
= mavlink_msg_attitude_get_pitch(msg
);
354 attitude
->yaw
= mavlink_msg_attitude_get_yaw(msg
);
355 attitude
->rollspeed
= mavlink_msg_attitude_get_rollspeed(msg
);
356 attitude
->pitchspeed
= mavlink_msg_attitude_get_pitchspeed(msg
);
357 attitude
->yawspeed
= mavlink_msg_attitude_get_yawspeed(msg
);
359 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_ATTITUDE_LEN
? msg
->len
: MAVLINK_MSG_ID_ATTITUDE_LEN
;
360 memset(attitude
, 0, MAVLINK_MSG_ID_ATTITUDE_LEN
);
361 memcpy(attitude
, _MAV_PAYLOAD(msg
), len
);