mavlink_msg_attitude.h 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428
  1. #pragma once
  2. // MESSAGE ATTITUDE PACKING
  3. #define MAVLINK_MSG_ID_ATTITUDE 30
  4. typedef struct __mavlink_attitude_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. float roll; /*< [rad] Roll angle (-pi..+pi)*/
  7. float pitch; /*< [rad] Pitch angle (-pi..+pi)*/
  8. float yaw; /*< [rad] Yaw angle (-pi..+pi)*/
  9. float rollspeed; /*< [rad/s] Roll angular speed*/
  10. float pitchspeed; /*< [rad/s] Pitch angular speed*/
  11. float yawspeed; /*< [rad/s] Yaw angular speed*/
  12. } mavlink_attitude_t;
  13. #define MAVLINK_MSG_ID_ATTITUDE_LEN 28
  14. #define MAVLINK_MSG_ID_ATTITUDE_MIN_LEN 28
  15. #define MAVLINK_MSG_ID_30_LEN 28
  16. #define MAVLINK_MSG_ID_30_MIN_LEN 28
  17. #define MAVLINK_MSG_ID_ATTITUDE_CRC 39
  18. #define MAVLINK_MSG_ID_30_CRC 39
  19. #if MAVLINK_COMMAND_24BIT
  20. #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
  21. 30, \
  22. "ATTITUDE", \
  23. 7, \
  24. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
  25. { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
  26. { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
  27. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
  28. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
  29. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
  30. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
  31. } \
  32. }
  33. #else
  34. #define MAVLINK_MESSAGE_INFO_ATTITUDE { \
  35. "ATTITUDE", \
  36. 7, \
  37. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
  38. { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
  39. { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
  40. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
  41. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
  42. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
  43. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
  44. } \
  45. }
  46. #endif
  47. /**
  48. * @brief Pack a attitude message
  49. * @param system_id ID of this system
  50. * @param component_id ID of this component (e.g. 200 for IMU)
  51. * @param msg The MAVLink message to compress the data into
  52. *
  53. * @param time_boot_ms [ms] Timestamp (time since system boot).
  54. * @param roll [rad] Roll angle (-pi..+pi)
  55. * @param pitch [rad] Pitch angle (-pi..+pi)
  56. * @param yaw [rad] Yaw angle (-pi..+pi)
  57. * @param rollspeed [rad/s] Roll angular speed
  58. * @param pitchspeed [rad/s] Pitch angular speed
  59. * @param yawspeed [rad/s] Yaw angular speed
  60. * @return length of the message in bytes (excluding serial stream start sign)
  61. */
  62. static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  63. uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
  64. {
  65. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  66. char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
  67. _mav_put_uint32_t(buf, 0, time_boot_ms);
  68. _mav_put_float(buf, 4, roll);
  69. _mav_put_float(buf, 8, pitch);
  70. _mav_put_float(buf, 12, yaw);
  71. _mav_put_float(buf, 16, rollspeed);
  72. _mav_put_float(buf, 20, pitchspeed);
  73. _mav_put_float(buf, 24, yawspeed);
  74. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
  75. #else
  76. mavlink_attitude_t packet;
  77. packet.time_boot_ms = time_boot_ms;
  78. packet.roll = roll;
  79. packet.pitch = pitch;
  80. packet.yaw = yaw;
  81. packet.rollspeed = rollspeed;
  82. packet.pitchspeed = pitchspeed;
  83. packet.yawspeed = yawspeed;
  84. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
  85. #endif
  86. msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
  87. 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);
  88. }
  89. /**
  90. * @brief Pack a attitude message
  91. * @param system_id ID of this system
  92. * @param component_id ID of this component (e.g. 200 for IMU)
  93. * @param status MAVLink status structure
  94. * @param msg The MAVLink message to compress the data into
  95. *
  96. * @param time_boot_ms [ms] Timestamp (time since system boot).
  97. * @param roll [rad] Roll angle (-pi..+pi)
  98. * @param pitch [rad] Pitch angle (-pi..+pi)
  99. * @param yaw [rad] Yaw angle (-pi..+pi)
  100. * @param rollspeed [rad/s] Roll angular speed
  101. * @param pitchspeed [rad/s] Pitch angular speed
  102. * @param yawspeed [rad/s] Yaw angular speed
  103. * @return length of the message in bytes (excluding serial stream start sign)
  104. */
  105. static inline uint16_t mavlink_msg_attitude_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  106. uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
  107. {
  108. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  109. char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
  110. _mav_put_uint32_t(buf, 0, time_boot_ms);
  111. _mav_put_float(buf, 4, roll);
  112. _mav_put_float(buf, 8, pitch);
  113. _mav_put_float(buf, 12, yaw);
  114. _mav_put_float(buf, 16, rollspeed);
  115. _mav_put_float(buf, 20, pitchspeed);
  116. _mav_put_float(buf, 24, yawspeed);
  117. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
  118. #else
  119. mavlink_attitude_t packet;
  120. packet.time_boot_ms = time_boot_ms;
  121. packet.roll = roll;
  122. packet.pitch = pitch;
  123. packet.yaw = yaw;
  124. packet.rollspeed = rollspeed;
  125. packet.pitchspeed = pitchspeed;
  126. packet.yawspeed = yawspeed;
  127. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
  128. #endif
  129. msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
  130. #if MAVLINK_CRC_EXTRA
  131. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
  132. #else
  133. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_LEN);
  134. #endif
  135. }
  136. /**
  137. * @brief Pack a attitude message on a channel
  138. * @param system_id ID of this system
  139. * @param component_id ID of this component (e.g. 200 for IMU)
  140. * @param chan The MAVLink channel this message will be sent over
  141. * @param msg The MAVLink message to compress the data into
  142. * @param time_boot_ms [ms] Timestamp (time since system boot).
  143. * @param roll [rad] Roll angle (-pi..+pi)
  144. * @param pitch [rad] Pitch angle (-pi..+pi)
  145. * @param yaw [rad] Yaw angle (-pi..+pi)
  146. * @param rollspeed [rad/s] Roll angular speed
  147. * @param pitchspeed [rad/s] Pitch angular speed
  148. * @param yawspeed [rad/s] Yaw angular speed
  149. * @return length of the message in bytes (excluding serial stream start sign)
  150. */
  151. static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  152. mavlink_message_t* msg,
  153. uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
  154. {
  155. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  156. char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
  157. _mav_put_uint32_t(buf, 0, time_boot_ms);
  158. _mav_put_float(buf, 4, roll);
  159. _mav_put_float(buf, 8, pitch);
  160. _mav_put_float(buf, 12, yaw);
  161. _mav_put_float(buf, 16, rollspeed);
  162. _mav_put_float(buf, 20, pitchspeed);
  163. _mav_put_float(buf, 24, yawspeed);
  164. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
  165. #else
  166. mavlink_attitude_t packet;
  167. packet.time_boot_ms = time_boot_ms;
  168. packet.roll = roll;
  169. packet.pitch = pitch;
  170. packet.yaw = yaw;
  171. packet.rollspeed = rollspeed;
  172. packet.pitchspeed = pitchspeed;
  173. packet.yawspeed = yawspeed;
  174. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
  175. #endif
  176. msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
  177. 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);
  178. }
  179. /**
  180. * @brief Encode a attitude struct
  181. *
  182. * @param system_id ID of this system
  183. * @param component_id ID of this component (e.g. 200 for IMU)
  184. * @param msg The MAVLink message to compress the data into
  185. * @param attitude C-struct to read the message contents from
  186. */
  187. 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)
  188. {
  189. 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);
  190. }
  191. /**
  192. * @brief Encode a attitude struct on a channel
  193. *
  194. * @param system_id ID of this system
  195. * @param component_id ID of this component (e.g. 200 for IMU)
  196. * @param chan The MAVLink channel this message will be sent over
  197. * @param msg The MAVLink message to compress the data into
  198. * @param attitude C-struct to read the message contents from
  199. */
  200. 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)
  201. {
  202. 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);
  203. }
  204. /**
  205. * @brief Encode a attitude struct with provided status structure
  206. *
  207. * @param system_id ID of this system
  208. * @param component_id ID of this component (e.g. 200 for IMU)
  209. * @param status MAVLink status structure
  210. * @param msg The MAVLink message to compress the data into
  211. * @param attitude C-struct to read the message contents from
  212. */
  213. static inline uint16_t mavlink_msg_attitude_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
  214. {
  215. return mavlink_msg_attitude_pack_status(system_id, component_id, _status, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
  216. }
  217. /**
  218. * @brief Send a attitude message
  219. * @param chan MAVLink channel to send the message
  220. *
  221. * @param time_boot_ms [ms] Timestamp (time since system boot).
  222. * @param roll [rad] Roll angle (-pi..+pi)
  223. * @param pitch [rad] Pitch angle (-pi..+pi)
  224. * @param yaw [rad] Yaw angle (-pi..+pi)
  225. * @param rollspeed [rad/s] Roll angular speed
  226. * @param pitchspeed [rad/s] Pitch angular speed
  227. * @param yawspeed [rad/s] Yaw angular speed
  228. */
  229. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  230. 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)
  231. {
  232. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  233. char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
  234. _mav_put_uint32_t(buf, 0, time_boot_ms);
  235. _mav_put_float(buf, 4, roll);
  236. _mav_put_float(buf, 8, pitch);
  237. _mav_put_float(buf, 12, yaw);
  238. _mav_put_float(buf, 16, rollspeed);
  239. _mav_put_float(buf, 20, pitchspeed);
  240. _mav_put_float(buf, 24, yawspeed);
  241. _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);
  242. #else
  243. mavlink_attitude_t packet;
  244. packet.time_boot_ms = time_boot_ms;
  245. packet.roll = roll;
  246. packet.pitch = pitch;
  247. packet.yaw = yaw;
  248. packet.rollspeed = rollspeed;
  249. packet.pitchspeed = pitchspeed;
  250. packet.yawspeed = yawspeed;
  251. _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);
  252. #endif
  253. }
  254. /**
  255. * @brief Send a attitude message
  256. * @param chan MAVLink channel to send the message
  257. * @param struct The MAVLink struct to serialize
  258. */
  259. static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude)
  260. {
  261. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  262. mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
  263. #else
  264. _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);
  265. #endif
  266. }
  267. #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  268. /*
  269. This variant of _send() can be used to save stack space by re-using
  270. memory from the receive buffer. The caller provides a
  271. mavlink_message_t which is the size of a full mavlink message. This
  272. is usually the receive buffer for the channel, and allows a reply to an
  273. incoming message with minimum stack space usage.
  274. */
  275. 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)
  276. {
  277. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  278. char *buf = (char *)msgbuf;
  279. _mav_put_uint32_t(buf, 0, time_boot_ms);
  280. _mav_put_float(buf, 4, roll);
  281. _mav_put_float(buf, 8, pitch);
  282. _mav_put_float(buf, 12, yaw);
  283. _mav_put_float(buf, 16, rollspeed);
  284. _mav_put_float(buf, 20, pitchspeed);
  285. _mav_put_float(buf, 24, yawspeed);
  286. _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);
  287. #else
  288. mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
  289. packet->time_boot_ms = time_boot_ms;
  290. packet->roll = roll;
  291. packet->pitch = pitch;
  292. packet->yaw = yaw;
  293. packet->rollspeed = rollspeed;
  294. packet->pitchspeed = pitchspeed;
  295. packet->yawspeed = yawspeed;
  296. _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);
  297. #endif
  298. }
  299. #endif
  300. #endif
  301. // MESSAGE ATTITUDE UNPACKING
  302. /**
  303. * @brief Get field time_boot_ms from attitude message
  304. *
  305. * @return [ms] Timestamp (time since system boot).
  306. */
  307. static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
  308. {
  309. return _MAV_RETURN_uint32_t(msg, 0);
  310. }
  311. /**
  312. * @brief Get field roll from attitude message
  313. *
  314. * @return [rad] Roll angle (-pi..+pi)
  315. */
  316. static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
  317. {
  318. return _MAV_RETURN_float(msg, 4);
  319. }
  320. /**
  321. * @brief Get field pitch from attitude message
  322. *
  323. * @return [rad] Pitch angle (-pi..+pi)
  324. */
  325. static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
  326. {
  327. return _MAV_RETURN_float(msg, 8);
  328. }
  329. /**
  330. * @brief Get field yaw from attitude message
  331. *
  332. * @return [rad] Yaw angle (-pi..+pi)
  333. */
  334. static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
  335. {
  336. return _MAV_RETURN_float(msg, 12);
  337. }
  338. /**
  339. * @brief Get field rollspeed from attitude message
  340. *
  341. * @return [rad/s] Roll angular speed
  342. */
  343. static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
  344. {
  345. return _MAV_RETURN_float(msg, 16);
  346. }
  347. /**
  348. * @brief Get field pitchspeed from attitude message
  349. *
  350. * @return [rad/s] Pitch angular speed
  351. */
  352. static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
  353. {
  354. return _MAV_RETURN_float(msg, 20);
  355. }
  356. /**
  357. * @brief Get field yawspeed from attitude message
  358. *
  359. * @return [rad/s] Yaw angular speed
  360. */
  361. static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
  362. {
  363. return _MAV_RETURN_float(msg, 24);
  364. }
  365. /**
  366. * @brief Decode a attitude message into a struct
  367. *
  368. * @param msg The message to decode
  369. * @param attitude C-struct to decode the message contents into
  370. */
  371. static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
  372. {
  373. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  374. attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
  375. attitude->roll = mavlink_msg_attitude_get_roll(msg);
  376. attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
  377. attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
  378. attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
  379. attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
  380. attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
  381. #else
  382. uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN;
  383. memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN);
  384. memcpy(attitude, _MAV_PAYLOAD(msg), len);
  385. #endif
  386. }