1 // MESSAGE ATTITUDE PACKING
3 #define MAVLINK_MSG_ID_ATTITUDE 30
5 typedef struct __mavlink_attitude_t
7 uint32_t time_boot_ms
; ///< Timestamp (milliseconds since system boot)
8 float roll
; ///< Roll angle (rad, -pi..+pi)
9 float pitch
; ///< Pitch angle (rad, -pi..+pi)
10 float yaw
; ///< Yaw angle (rad, -pi..+pi)
11 float rollspeed
; ///< Roll angular speed (rad/s)
12 float pitchspeed
; ///< Pitch angular speed (rad/s)
13 float yawspeed
; ///< Yaw angular speed (rad/s)
16 #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
17 #define MAVLINK_MSG_ID_30_LEN 28
19 #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
20 #define MAVLINK_MSG_ID_30_CRC 39
24 #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
27 { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
28 { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
29 { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
30 { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
31 { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
32 { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
33 { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
39 * @brief Pack a attitude message
40 * @param system_id ID of this system
41 * @param component_id ID of this component (e.g. 200 for IMU)
42 * @param msg The MAVLink message to compress the data into
44 * @param time_boot_ms Timestamp (milliseconds since system boot)
45 * @param roll Roll angle (rad, -pi..+pi)
46 * @param pitch Pitch angle (rad, -pi..+pi)
47 * @param yaw Yaw angle (rad, -pi..+pi)
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)
53 static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
54 uint32_t time_boot_ms
, float roll
, float pitch
, float yaw
, float rollspeed
, float pitchspeed
, float yawspeed
)
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
58 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
59 _mav_put_float(buf
, 4, roll
);
60 _mav_put_float(buf
, 8, pitch
);
61 _mav_put_float(buf
, 12, yaw
);
62 _mav_put_float(buf
, 16, rollspeed
);
63 _mav_put_float(buf
, 20, pitchspeed
);
64 _mav_put_float(buf
, 24, yawspeed
);
66 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
68 mavlink_attitude_t packet
;
69 packet
.time_boot_ms
= time_boot_ms
;
73 packet
.rollspeed
= rollspeed
;
74 packet
.pitchspeed
= pitchspeed
;
75 packet
.yawspeed
= yawspeed
;
77 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
80 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE
;
82 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
84 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
89 * @brief Pack a attitude message on a channel
90 * @param system_id ID of this system
91 * @param component_id ID of this component (e.g. 200 for IMU)
92 * @param chan The MAVLink channel this message will be sent over
93 * @param msg The MAVLink message to compress the data into
94 * @param time_boot_ms Timestamp (milliseconds since system boot)
95 * @param roll Roll angle (rad, -pi..+pi)
96 * @param pitch Pitch angle (rad, -pi..+pi)
97 * @param yaw Yaw angle (rad, -pi..+pi)
98 * @param rollspeed Roll angular speed (rad/s)
99 * @param pitchspeed Pitch angular speed (rad/s)
100 * @param yawspeed Yaw angular speed (rad/s)
101 * @return length of the message in bytes (excluding serial stream start sign)
103 static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
104 mavlink_message_t
* msg
,
105 uint32_t time_boot_ms
,float roll
,float pitch
,float yaw
,float rollspeed
,float pitchspeed
,float yawspeed
)
107 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
108 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
109 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
110 _mav_put_float(buf
, 4, roll
);
111 _mav_put_float(buf
, 8, pitch
);
112 _mav_put_float(buf
, 12, yaw
);
113 _mav_put_float(buf
, 16, rollspeed
);
114 _mav_put_float(buf
, 20, pitchspeed
);
115 _mav_put_float(buf
, 24, yawspeed
);
117 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
119 mavlink_attitude_t packet
;
120 packet
.time_boot_ms
= time_boot_ms
;
122 packet
.pitch
= pitch
;
124 packet
.rollspeed
= rollspeed
;
125 packet
.pitchspeed
= pitchspeed
;
126 packet
.yawspeed
= yawspeed
;
128 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
131 msg
->msgid
= MAVLINK_MSG_ID_ATTITUDE
;
132 #if MAVLINK_CRC_EXTRA
133 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
135 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
140 * @brief Encode a attitude struct
142 * @param system_id ID of this system
143 * @param component_id ID of this component (e.g. 200 for IMU)
144 * @param msg The MAVLink message to compress the data into
145 * @param attitude C-struct to read the message contents from
147 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
)
149 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
);
153 * @brief Encode a attitude struct on a channel
155 * @param system_id ID of this system
156 * @param component_id ID of this component (e.g. 200 for IMU)
157 * @param chan The MAVLink channel this message will be sent over
158 * @param msg The MAVLink message to compress the data into
159 * @param attitude C-struct to read the message contents from
161 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
)
163 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
);
167 * @brief Send a attitude message
168 * @param chan MAVLink channel to send the message
170 * @param time_boot_ms Timestamp (milliseconds since system boot)
171 * @param roll Roll angle (rad, -pi..+pi)
172 * @param pitch Pitch angle (rad, -pi..+pi)
173 * @param yaw Yaw angle (rad, -pi..+pi)
174 * @param rollspeed Roll angular speed (rad/s)
175 * @param pitchspeed Pitch angular speed (rad/s)
176 * @param yawspeed Yaw angular speed (rad/s)
178 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
180 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
)
182 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
183 char buf
[MAVLINK_MSG_ID_ATTITUDE_LEN
];
184 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
185 _mav_put_float(buf
, 4, roll
);
186 _mav_put_float(buf
, 8, pitch
);
187 _mav_put_float(buf
, 12, yaw
);
188 _mav_put_float(buf
, 16, rollspeed
);
189 _mav_put_float(buf
, 20, pitchspeed
);
190 _mav_put_float(buf
, 24, yawspeed
);
192 #if MAVLINK_CRC_EXTRA
193 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
195 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
198 mavlink_attitude_t packet
;
199 packet
.time_boot_ms
= time_boot_ms
;
201 packet
.pitch
= pitch
;
203 packet
.rollspeed
= rollspeed
;
204 packet
.pitchspeed
= pitchspeed
;
205 packet
.yawspeed
= yawspeed
;
207 #if MAVLINK_CRC_EXTRA
208 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
210 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)&packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
215 #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
217 This varient of _send() can be used to save stack space by re-using
218 memory from the receive buffer. The caller provides a
219 mavlink_message_t which is the size of a full mavlink message. This
220 is usually the receive buffer for the channel, and allows a reply to an
221 incoming message with minimum stack space usage.
223 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
)
225 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
226 char *buf
= (char *)msgbuf
;
227 _mav_put_uint32_t(buf
, 0, time_boot_ms
);
228 _mav_put_float(buf
, 4, roll
);
229 _mav_put_float(buf
, 8, pitch
);
230 _mav_put_float(buf
, 12, yaw
);
231 _mav_put_float(buf
, 16, rollspeed
);
232 _mav_put_float(buf
, 20, pitchspeed
);
233 _mav_put_float(buf
, 24, yawspeed
);
235 #if MAVLINK_CRC_EXTRA
236 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
238 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, buf
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
241 mavlink_attitude_t
*packet
= (mavlink_attitude_t
*)msgbuf
;
242 packet
->time_boot_ms
= time_boot_ms
;
244 packet
->pitch
= pitch
;
246 packet
->rollspeed
= rollspeed
;
247 packet
->pitchspeed
= pitchspeed
;
248 packet
->yawspeed
= yawspeed
;
250 #if MAVLINK_CRC_EXTRA
251 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
, MAVLINK_MSG_ID_ATTITUDE_CRC
);
253 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_ATTITUDE
, (const char *)packet
, MAVLINK_MSG_ID_ATTITUDE_LEN
);
261 // MESSAGE ATTITUDE UNPACKING
265 * @brief Get field time_boot_ms from attitude message
267 * @return Timestamp (milliseconds since system boot)
269 static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t
* msg
)
271 return _MAV_RETURN_uint32_t(msg
, 0);
275 * @brief Get field roll from attitude message
277 * @return Roll angle (rad, -pi..+pi)
279 static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t
* msg
)
281 return _MAV_RETURN_float(msg
, 4);
285 * @brief Get field pitch from attitude message
287 * @return Pitch angle (rad, -pi..+pi)
289 static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t
* msg
)
291 return _MAV_RETURN_float(msg
, 8);
295 * @brief Get field yaw from attitude message
297 * @return Yaw angle (rad, -pi..+pi)
299 static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t
* msg
)
301 return _MAV_RETURN_float(msg
, 12);
305 * @brief Get field rollspeed from attitude message
307 * @return Roll angular speed (rad/s)
309 static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t
* msg
)
311 return _MAV_RETURN_float(msg
, 16);
315 * @brief Get field pitchspeed from attitude message
317 * @return Pitch angular speed (rad/s)
319 static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t
* msg
)
321 return _MAV_RETURN_float(msg
, 20);
325 * @brief Get field yawspeed from attitude message
327 * @return Yaw angular speed (rad/s)
329 static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t
* msg
)
331 return _MAV_RETURN_float(msg
, 24);
335 * @brief Decode a attitude message into a struct
337 * @param msg The message to decode
338 * @param attitude C-struct to decode the message contents into
340 static inline void mavlink_msg_attitude_decode(const mavlink_message_t
* msg
, mavlink_attitude_t
* attitude
)
342 #if MAVLINK_NEED_BYTE_SWAP
343 attitude
->time_boot_ms
= mavlink_msg_attitude_get_time_boot_ms(msg
);
344 attitude
->roll
= mavlink_msg_attitude_get_roll(msg
);
345 attitude
->pitch
= mavlink_msg_attitude_get_pitch(msg
);
346 attitude
->yaw
= mavlink_msg_attitude_get_yaw(msg
);
347 attitude
->rollspeed
= mavlink_msg_attitude_get_rollspeed(msg
);
348 attitude
->pitchspeed
= mavlink_msg_attitude_get_pitchspeed(msg
);
349 attitude
->yawspeed
= mavlink_msg_attitude_get_yawspeed(msg
);
351 memcpy(attitude
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_ATTITUDE_LEN
);