mavlink_msg_attitude_quaternion.h 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405
  1. #pragma once
  2. // MESSAGE ATTITUDE_QUATERNION PACKING
  3. #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
  4. typedef struct __mavlink_attitude_quaternion_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. float q1; /*< Quaternion component 1, w (1 in null-rotation)*/
  7. float q2; /*< Quaternion component 2, x (0 in null-rotation)*/
  8. float q3; /*< Quaternion component 3, y (0 in null-rotation)*/
  9. float q4; /*< Quaternion component 4, z (0 in 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 repr_offset_q[4]; /*< Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.*/
  14. } mavlink_attitude_quaternion_t;
  15. #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 48
  16. #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
  17. #define MAVLINK_MSG_ID_31_LEN 48
  18. #define MAVLINK_MSG_ID_31_MIN_LEN 32
  19. #define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
  20. #define MAVLINK_MSG_ID_31_CRC 246
  21. #define MAVLINK_MSG_ATTITUDE_QUATERNION_FIELD_REPR_OFFSET_Q_LEN 4
  22. #if MAVLINK_COMMAND_24BIT
  23. #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
  24. 31, \
  25. "ATTITUDE_QUATERNION", \
  26. 9, \
  27. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
  28. { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
  29. { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
  30. { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
  31. { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
  32. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
  33. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
  34. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
  35. { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
  36. } \
  37. }
  38. #else
  39. #define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
  40. "ATTITUDE_QUATERNION", \
  41. 9, \
  42. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
  43. { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
  44. { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
  45. { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
  46. { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
  47. { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
  48. { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
  49. { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
  50. { "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
  51. } \
  52. }
  53. #endif
  54. /**
  55. * @brief Pack a attitude_quaternion 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
  59. *
  60. * @param time_boot_ms [ms] Timestamp (time since system boot).
  61. * @param q1 Quaternion component 1, w (1 in null-rotation)
  62. * @param q2 Quaternion component 2, x (0 in null-rotation)
  63. * @param q3 Quaternion component 3, y (0 in null-rotation)
  64. * @param q4 Quaternion component 4, z (0 in null-rotation)
  65. * @param rollspeed [rad/s] Roll angular speed
  66. * @param pitchspeed [rad/s] Pitch angular speed
  67. * @param yawspeed [rad/s] Yaw angular speed
  68. * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
  69. * @return length of the message in bytes (excluding serial stream start sign)
  70. */
  71. static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  72. uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q)
  73. {
  74. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  75. char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
  76. _mav_put_uint32_t(buf, 0, time_boot_ms);
  77. _mav_put_float(buf, 4, q1);
  78. _mav_put_float(buf, 8, q2);
  79. _mav_put_float(buf, 12, q3);
  80. _mav_put_float(buf, 16, q4);
  81. _mav_put_float(buf, 20, rollspeed);
  82. _mav_put_float(buf, 24, pitchspeed);
  83. _mav_put_float(buf, 28, yawspeed);
  84. _mav_put_float_array(buf, 32, repr_offset_q, 4);
  85. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
  86. #else
  87. mavlink_attitude_quaternion_t packet;
  88. packet.time_boot_ms = time_boot_ms;
  89. packet.q1 = q1;
  90. packet.q2 = q2;
  91. packet.q3 = q3;
  92. packet.q4 = q4;
  93. packet.rollspeed = rollspeed;
  94. packet.pitchspeed = pitchspeed;
  95. packet.yawspeed = yawspeed;
  96. mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
  97. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
  98. #endif
  99. msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
  100. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  101. }
  102. /**
  103. * @brief Pack a attitude_quaternion 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 [ms] Timestamp (time since system boot).
  109. * @param q1 Quaternion component 1, w (1 in null-rotation)
  110. * @param q2 Quaternion component 2, x (0 in null-rotation)
  111. * @param q3 Quaternion component 3, y (0 in null-rotation)
  112. * @param q4 Quaternion component 4, z (0 in null-rotation)
  113. * @param rollspeed [rad/s] Roll angular speed
  114. * @param pitchspeed [rad/s] Pitch angular speed
  115. * @param yawspeed [rad/s] Yaw angular speed
  116. * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
  117. * @return length of the message in bytes (excluding serial stream start sign)
  118. */
  119. static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  120. mavlink_message_t* msg,
  121. uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,const float *repr_offset_q)
  122. {
  123. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  124. char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
  125. _mav_put_uint32_t(buf, 0, time_boot_ms);
  126. _mav_put_float(buf, 4, q1);
  127. _mav_put_float(buf, 8, q2);
  128. _mav_put_float(buf, 12, q3);
  129. _mav_put_float(buf, 16, q4);
  130. _mav_put_float(buf, 20, rollspeed);
  131. _mav_put_float(buf, 24, pitchspeed);
  132. _mav_put_float(buf, 28, yawspeed);
  133. _mav_put_float_array(buf, 32, repr_offset_q, 4);
  134. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
  135. #else
  136. mavlink_attitude_quaternion_t packet;
  137. packet.time_boot_ms = time_boot_ms;
  138. packet.q1 = q1;
  139. packet.q2 = q2;
  140. packet.q3 = q3;
  141. packet.q4 = q4;
  142. packet.rollspeed = rollspeed;
  143. packet.pitchspeed = pitchspeed;
  144. packet.yawspeed = yawspeed;
  145. mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
  146. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
  147. #endif
  148. msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
  149. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  150. }
  151. /**
  152. * @brief Encode a attitude_quaternion struct
  153. *
  154. * @param system_id ID of this system
  155. * @param component_id ID of this component (e.g. 200 for IMU)
  156. * @param msg The MAVLink message to compress the data into
  157. * @param attitude_quaternion C-struct to read the message contents from
  158. */
  159. 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)
  160. {
  161. 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, attitude_quaternion->repr_offset_q);
  162. }
  163. /**
  164. * @brief Encode a attitude_quaternion struct on a channel
  165. *
  166. * @param system_id ID of this system
  167. * @param component_id ID of this component (e.g. 200 for IMU)
  168. * @param chan The MAVLink channel this message will be sent over
  169. * @param msg The MAVLink message to compress the data into
  170. * @param attitude_quaternion C-struct to read the message contents from
  171. */
  172. static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
  173. {
  174. return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, 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, attitude_quaternion->repr_offset_q);
  175. }
  176. /**
  177. * @brief Send a attitude_quaternion message
  178. * @param chan MAVLink channel to send the message
  179. *
  180. * @param time_boot_ms [ms] Timestamp (time since system boot).
  181. * @param q1 Quaternion component 1, w (1 in null-rotation)
  182. * @param q2 Quaternion component 2, x (0 in null-rotation)
  183. * @param q3 Quaternion component 3, y (0 in null-rotation)
  184. * @param q4 Quaternion component 4, z (0 in null-rotation)
  185. * @param rollspeed [rad/s] Roll angular speed
  186. * @param pitchspeed [rad/s] Pitch angular speed
  187. * @param yawspeed [rad/s] Yaw angular speed
  188. * @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
  189. */
  190. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  191. 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, const float *repr_offset_q)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
  195. _mav_put_uint32_t(buf, 0, time_boot_ms);
  196. _mav_put_float(buf, 4, q1);
  197. _mav_put_float(buf, 8, q2);
  198. _mav_put_float(buf, 12, q3);
  199. _mav_put_float(buf, 16, q4);
  200. _mav_put_float(buf, 20, rollspeed);
  201. _mav_put_float(buf, 24, pitchspeed);
  202. _mav_put_float(buf, 28, yawspeed);
  203. _mav_put_float_array(buf, 32, repr_offset_q, 4);
  204. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  205. #else
  206. mavlink_attitude_quaternion_t packet;
  207. packet.time_boot_ms = time_boot_ms;
  208. packet.q1 = q1;
  209. packet.q2 = q2;
  210. packet.q3 = q3;
  211. packet.q4 = q4;
  212. packet.rollspeed = rollspeed;
  213. packet.pitchspeed = pitchspeed;
  214. packet.yawspeed = yawspeed;
  215. mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
  216. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  217. #endif
  218. }
  219. /**
  220. * @brief Send a attitude_quaternion message
  221. * @param chan MAVLink channel to send the message
  222. * @param struct The MAVLink struct to serialize
  223. */
  224. static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion)
  225. {
  226. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  227. mavlink_msg_attitude_quaternion_send(chan, 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, attitude_quaternion->repr_offset_q);
  228. #else
  229. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  230. #endif
  231. }
  232. #if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  233. /*
  234. This variant of _send() can be used to save stack space by re-using
  235. memory from the receive buffer. The caller provides a
  236. mavlink_message_t which is the size of a full mavlink message. This
  237. is usually the receive buffer for the channel, and allows a reply to an
  238. incoming message with minimum stack space usage.
  239. */
  240. static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q)
  241. {
  242. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  243. char *buf = (char *)msgbuf;
  244. _mav_put_uint32_t(buf, 0, time_boot_ms);
  245. _mav_put_float(buf, 4, q1);
  246. _mav_put_float(buf, 8, q2);
  247. _mav_put_float(buf, 12, q3);
  248. _mav_put_float(buf, 16, q4);
  249. _mav_put_float(buf, 20, rollspeed);
  250. _mav_put_float(buf, 24, pitchspeed);
  251. _mav_put_float(buf, 28, yawspeed);
  252. _mav_put_float_array(buf, 32, repr_offset_q, 4);
  253. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  254. #else
  255. mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
  256. packet->time_boot_ms = time_boot_ms;
  257. packet->q1 = q1;
  258. packet->q2 = q2;
  259. packet->q3 = q3;
  260. packet->q4 = q4;
  261. packet->rollspeed = rollspeed;
  262. packet->pitchspeed = pitchspeed;
  263. packet->yawspeed = yawspeed;
  264. mav_array_memcpy(packet->repr_offset_q, repr_offset_q, sizeof(float)*4);
  265. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
  266. #endif
  267. }
  268. #endif
  269. #endif
  270. // MESSAGE ATTITUDE_QUATERNION UNPACKING
  271. /**
  272. * @brief Get field time_boot_ms from attitude_quaternion message
  273. *
  274. * @return [ms] Timestamp (time since system boot).
  275. */
  276. static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
  277. {
  278. return _MAV_RETURN_uint32_t(msg, 0);
  279. }
  280. /**
  281. * @brief Get field q1 from attitude_quaternion message
  282. *
  283. * @return Quaternion component 1, w (1 in null-rotation)
  284. */
  285. static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
  286. {
  287. return _MAV_RETURN_float(msg, 4);
  288. }
  289. /**
  290. * @brief Get field q2 from attitude_quaternion message
  291. *
  292. * @return Quaternion component 2, x (0 in null-rotation)
  293. */
  294. static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
  295. {
  296. return _MAV_RETURN_float(msg, 8);
  297. }
  298. /**
  299. * @brief Get field q3 from attitude_quaternion message
  300. *
  301. * @return Quaternion component 3, y (0 in null-rotation)
  302. */
  303. static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
  304. {
  305. return _MAV_RETURN_float(msg, 12);
  306. }
  307. /**
  308. * @brief Get field q4 from attitude_quaternion message
  309. *
  310. * @return Quaternion component 4, z (0 in null-rotation)
  311. */
  312. static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
  313. {
  314. return _MAV_RETURN_float(msg, 16);
  315. }
  316. /**
  317. * @brief Get field rollspeed from attitude_quaternion message
  318. *
  319. * @return [rad/s] Roll angular speed
  320. */
  321. static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
  322. {
  323. return _MAV_RETURN_float(msg, 20);
  324. }
  325. /**
  326. * @brief Get field pitchspeed from attitude_quaternion message
  327. *
  328. * @return [rad/s] Pitch angular speed
  329. */
  330. static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
  331. {
  332. return _MAV_RETURN_float(msg, 24);
  333. }
  334. /**
  335. * @brief Get field yawspeed from attitude_quaternion message
  336. *
  337. * @return [rad/s] Yaw angular speed
  338. */
  339. static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
  340. {
  341. return _MAV_RETURN_float(msg, 28);
  342. }
  343. /**
  344. * @brief Get field repr_offset_q from attitude_quaternion message
  345. *
  346. * @return Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
  347. */
  348. static inline uint16_t mavlink_msg_attitude_quaternion_get_repr_offset_q(const mavlink_message_t* msg, float *repr_offset_q)
  349. {
  350. return _MAV_RETURN_float_array(msg, repr_offset_q, 4, 32);
  351. }
  352. /**
  353. * @brief Decode a attitude_quaternion message into a struct
  354. *
  355. * @param msg The message to decode
  356. * @param attitude_quaternion C-struct to decode the message contents into
  357. */
  358. static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion)
  359. {
  360. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  361. attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
  362. attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg);
  363. attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg);
  364. attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg);
  365. attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg);
  366. attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg);
  367. attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg);
  368. attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg);
  369. mavlink_msg_attitude_quaternion_get_repr_offset_q(msg, attitude_quaternion->repr_offset_q);
  370. #else
  371. uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN;
  372. memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
  373. memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), len);
  374. #endif
  375. }