mavlink_msg_attitude.h 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363
  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 on a channel
  91. * @param system_id ID of this system
  92. * @param component_id ID of this component (e.g. 200 for IMU)
  93. * @param chan The MAVLink channel this message will be sent over
  94. * @param msg The MAVLink message to compress the data into
  95. * @param time_boot_ms [ms] Timestamp (time since system boot).
  96. * @param roll [rad] Roll angle (-pi..+pi)
  97. * @param pitch [rad] Pitch angle (-pi..+pi)
  98. * @param yaw [rad] Yaw angle (-pi..+pi)
  99. * @param rollspeed [rad/s] Roll angular speed
  100. * @param pitchspeed [rad/s] Pitch angular speed
  101. * @param yawspeed [rad/s] Yaw angular speed
  102. * @return length of the message in bytes (excluding serial stream start sign)
  103. */
  104. static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  105. 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. 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);
  131. }
  132. /**
  133. * @brief Encode a attitude struct
  134. *
  135. * @param system_id ID of this system
  136. * @param component_id ID of this component (e.g. 200 for IMU)
  137. * @param msg The MAVLink message to compress the data into
  138. * @param attitude C-struct to read the message contents from
  139. */
  140. 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)
  141. {
  142. 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);
  143. }
  144. /**
  145. * @brief Encode a attitude struct on a channel
  146. *
  147. * @param system_id ID of this system
  148. * @param component_id ID of this component (e.g. 200 for IMU)
  149. * @param chan The MAVLink channel this message will be sent over
  150. * @param msg The MAVLink message to compress the data into
  151. * @param attitude C-struct to read the message contents from
  152. */
  153. 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)
  154. {
  155. 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);
  156. }
  157. /**
  158. * @brief Send a attitude message
  159. * @param chan MAVLink channel to send the message
  160. *
  161. * @param time_boot_ms [ms] Timestamp (time since system boot).
  162. * @param roll [rad] Roll angle (-pi..+pi)
  163. * @param pitch [rad] Pitch angle (-pi..+pi)
  164. * @param yaw [rad] Yaw angle (-pi..+pi)
  165. * @param rollspeed [rad/s] Roll angular speed
  166. * @param pitchspeed [rad/s] Pitch angular speed
  167. * @param yawspeed [rad/s] Yaw angular speed
  168. */
  169. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  170. 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)
  171. {
  172. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  173. char buf[MAVLINK_MSG_ID_ATTITUDE_LEN];
  174. _mav_put_uint32_t(buf, 0, time_boot_ms);
  175. _mav_put_float(buf, 4, roll);
  176. _mav_put_float(buf, 8, pitch);
  177. _mav_put_float(buf, 12, yaw);
  178. _mav_put_float(buf, 16, rollspeed);
  179. _mav_put_float(buf, 20, pitchspeed);
  180. _mav_put_float(buf, 24, yawspeed);
  181. _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);
  182. #else
  183. mavlink_attitude_t packet;
  184. packet.time_boot_ms = time_boot_ms;
  185. packet.roll = roll;
  186. packet.pitch = pitch;
  187. packet.yaw = yaw;
  188. packet.rollspeed = rollspeed;
  189. packet.pitchspeed = pitchspeed;
  190. packet.yawspeed = yawspeed;
  191. _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);
  192. #endif
  193. }
  194. /**
  195. * @brief Send a attitude message
  196. * @param chan MAVLink channel to send the message
  197. * @param struct The MAVLink struct to serialize
  198. */
  199. static inline void mavlink_msg_attitude_send_struct(mavlink_channel_t chan, const mavlink_attitude_t* attitude)
  200. {
  201. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  202. mavlink_msg_attitude_send(chan, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
  203. #else
  204. _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);
  205. #endif
  206. }
  207. #if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  208. /*
  209. This variant of _send() can be used to save stack space by re-using
  210. memory from the receive buffer. The caller provides a
  211. mavlink_message_t which is the size of a full mavlink message. This
  212. is usually the receive buffer for the channel, and allows a reply to an
  213. incoming message with minimum stack space usage.
  214. */
  215. 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)
  216. {
  217. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  218. char *buf = (char *)msgbuf;
  219. _mav_put_uint32_t(buf, 0, time_boot_ms);
  220. _mav_put_float(buf, 4, roll);
  221. _mav_put_float(buf, 8, pitch);
  222. _mav_put_float(buf, 12, yaw);
  223. _mav_put_float(buf, 16, rollspeed);
  224. _mav_put_float(buf, 20, pitchspeed);
  225. _mav_put_float(buf, 24, yawspeed);
  226. _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);
  227. #else
  228. mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
  229. packet->time_boot_ms = time_boot_ms;
  230. packet->roll = roll;
  231. packet->pitch = pitch;
  232. packet->yaw = yaw;
  233. packet->rollspeed = rollspeed;
  234. packet->pitchspeed = pitchspeed;
  235. packet->yawspeed = yawspeed;
  236. _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);
  237. #endif
  238. }
  239. #endif
  240. #endif
  241. // MESSAGE ATTITUDE UNPACKING
  242. /**
  243. * @brief Get field time_boot_ms from attitude message
  244. *
  245. * @return [ms] Timestamp (time since system boot).
  246. */
  247. static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
  248. {
  249. return _MAV_RETURN_uint32_t(msg, 0);
  250. }
  251. /**
  252. * @brief Get field roll from attitude message
  253. *
  254. * @return [rad] Roll angle (-pi..+pi)
  255. */
  256. static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
  257. {
  258. return _MAV_RETURN_float(msg, 4);
  259. }
  260. /**
  261. * @brief Get field pitch from attitude message
  262. *
  263. * @return [rad] Pitch angle (-pi..+pi)
  264. */
  265. static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
  266. {
  267. return _MAV_RETURN_float(msg, 8);
  268. }
  269. /**
  270. * @brief Get field yaw from attitude message
  271. *
  272. * @return [rad] Yaw angle (-pi..+pi)
  273. */
  274. static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
  275. {
  276. return _MAV_RETURN_float(msg, 12);
  277. }
  278. /**
  279. * @brief Get field rollspeed from attitude message
  280. *
  281. * @return [rad/s] Roll angular speed
  282. */
  283. static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
  284. {
  285. return _MAV_RETURN_float(msg, 16);
  286. }
  287. /**
  288. * @brief Get field pitchspeed from attitude message
  289. *
  290. * @return [rad/s] Pitch angular speed
  291. */
  292. static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
  293. {
  294. return _MAV_RETURN_float(msg, 20);
  295. }
  296. /**
  297. * @brief Get field yawspeed from attitude message
  298. *
  299. * @return [rad/s] Yaw angular speed
  300. */
  301. static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
  302. {
  303. return _MAV_RETURN_float(msg, 24);
  304. }
  305. /**
  306. * @brief Decode a attitude message into a struct
  307. *
  308. * @param msg The message to decode
  309. * @param attitude C-struct to decode the message contents into
  310. */
  311. static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
  312. {
  313. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  314. attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
  315. attitude->roll = mavlink_msg_attitude_get_roll(msg);
  316. attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
  317. attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
  318. attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
  319. attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
  320. attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
  321. #else
  322. uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_LEN;
  323. memset(attitude, 0, MAVLINK_MSG_ID_ATTITUDE_LEN);
  324. memcpy(attitude, _MAV_PAYLOAD(msg), len);
  325. #endif
  326. }