mavlink_msg_att_pos_mocap.h 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331
  1. #pragma once
  2. // MESSAGE ATT_POS_MOCAP PACKING
  3. #define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
  4. typedef struct __mavlink_att_pos_mocap_t {
  5. uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
  6. float q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
  7. float x; /*< [m] X position (NED)*/
  8. float y; /*< [m] Y position (NED)*/
  9. float z; /*< [m] Z position (NED)*/
  10. float covariance[21]; /*< Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
  11. } mavlink_att_pos_mocap_t;
  12. #define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 120
  13. #define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36
  14. #define MAVLINK_MSG_ID_138_LEN 120
  15. #define MAVLINK_MSG_ID_138_MIN_LEN 36
  16. #define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109
  17. #define MAVLINK_MSG_ID_138_CRC 109
  18. #define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4
  19. #define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_COVARIANCE_LEN 21
  20. #if MAVLINK_COMMAND_24BIT
  21. #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
  22. 138, \
  23. "ATT_POS_MOCAP", \
  24. 6, \
  25. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
  26. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
  27. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
  28. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
  29. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
  30. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \
  31. } \
  32. }
  33. #else
  34. #define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
  35. "ATT_POS_MOCAP", \
  36. 6, \
  37. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
  38. { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
  39. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
  40. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
  41. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
  42. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \
  43. } \
  44. }
  45. #endif
  46. /**
  47. * @brief Pack a att_pos_mocap message
  48. * @param system_id ID of this system
  49. * @param component_id ID of this component (e.g. 200 for IMU)
  50. * @param msg The MAVLink message to compress the data into
  51. *
  52. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  53. * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  54. * @param x [m] X position (NED)
  55. * @param y [m] Y position (NED)
  56. * @param z [m] Z position (NED)
  57. * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  58. * @return length of the message in bytes (excluding serial stream start sign)
  59. */
  60. static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  61. uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance)
  62. {
  63. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  64. char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
  65. _mav_put_uint64_t(buf, 0, time_usec);
  66. _mav_put_float(buf, 24, x);
  67. _mav_put_float(buf, 28, y);
  68. _mav_put_float(buf, 32, z);
  69. _mav_put_float_array(buf, 8, q, 4);
  70. _mav_put_float_array(buf, 36, covariance, 21);
  71. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
  72. #else
  73. mavlink_att_pos_mocap_t packet;
  74. packet.time_usec = time_usec;
  75. packet.x = x;
  76. packet.y = y;
  77. packet.z = z;
  78. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  79. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  80. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
  81. #endif
  82. msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
  83. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  84. }
  85. /**
  86. * @brief Pack a att_pos_mocap message on a channel
  87. * @param system_id ID of this system
  88. * @param component_id ID of this component (e.g. 200 for IMU)
  89. * @param chan The MAVLink channel this message will be sent over
  90. * @param msg The MAVLink message to compress the data into
  91. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  92. * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  93. * @param x [m] X position (NED)
  94. * @param y [m] Y position (NED)
  95. * @param z [m] Z position (NED)
  96. * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  100. mavlink_message_t* msg,
  101. uint64_t time_usec,const float *q,float x,float y,float z,const float *covariance)
  102. {
  103. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  104. char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
  105. _mav_put_uint64_t(buf, 0, time_usec);
  106. _mav_put_float(buf, 24, x);
  107. _mav_put_float(buf, 28, y);
  108. _mav_put_float(buf, 32, z);
  109. _mav_put_float_array(buf, 8, q, 4);
  110. _mav_put_float_array(buf, 36, covariance, 21);
  111. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
  112. #else
  113. mavlink_att_pos_mocap_t packet;
  114. packet.time_usec = time_usec;
  115. packet.x = x;
  116. packet.y = y;
  117. packet.z = z;
  118. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  119. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  120. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
  121. #endif
  122. msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
  123. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  124. }
  125. /**
  126. * @brief Encode a att_pos_mocap struct
  127. *
  128. * @param system_id ID of this system
  129. * @param component_id ID of this component (e.g. 200 for IMU)
  130. * @param msg The MAVLink message to compress the data into
  131. * @param att_pos_mocap C-struct to read the message contents from
  132. */
  133. static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
  134. {
  135. return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
  136. }
  137. /**
  138. * @brief Encode a att_pos_mocap struct on a channel
  139. *
  140. * @param system_id ID of this system
  141. * @param component_id ID of this component (e.g. 200 for IMU)
  142. * @param chan The MAVLink channel this message will be sent over
  143. * @param msg The MAVLink message to compress the data into
  144. * @param att_pos_mocap C-struct to read the message contents from
  145. */
  146. static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
  147. {
  148. return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
  149. }
  150. /**
  151. * @brief Send a att_pos_mocap message
  152. * @param chan MAVLink channel to send the message
  153. *
  154. * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  155. * @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  156. * @param x [m] X position (NED)
  157. * @param y [m] Y position (NED)
  158. * @param z [m] Z position (NED)
  159. * @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  160. */
  161. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  162. static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance)
  163. {
  164. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  165. char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
  166. _mav_put_uint64_t(buf, 0, time_usec);
  167. _mav_put_float(buf, 24, x);
  168. _mav_put_float(buf, 28, y);
  169. _mav_put_float(buf, 32, z);
  170. _mav_put_float_array(buf, 8, q, 4);
  171. _mav_put_float_array(buf, 36, covariance, 21);
  172. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  173. #else
  174. mavlink_att_pos_mocap_t packet;
  175. packet.time_usec = time_usec;
  176. packet.x = x;
  177. packet.y = y;
  178. packet.z = z;
  179. mav_array_memcpy(packet.q, q, sizeof(float)*4);
  180. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  181. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  182. #endif
  183. }
  184. /**
  185. * @brief Send a att_pos_mocap message
  186. * @param chan MAVLink channel to send the message
  187. * @param struct The MAVLink struct to serialize
  188. */
  189. static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap)
  190. {
  191. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  192. mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
  193. #else
  194. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  195. #endif
  196. }
  197. #if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  198. /*
  199. This variant of _send() can be used to save stack space by re-using
  200. memory from the receive buffer. The caller provides a
  201. mavlink_message_t which is the size of a full mavlink message. This
  202. is usually the receive buffer for the channel, and allows a reply to an
  203. incoming message with minimum stack space usage.
  204. */
  205. static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance)
  206. {
  207. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  208. char *buf = (char *)msgbuf;
  209. _mav_put_uint64_t(buf, 0, time_usec);
  210. _mav_put_float(buf, 24, x);
  211. _mav_put_float(buf, 28, y);
  212. _mav_put_float(buf, 32, z);
  213. _mav_put_float_array(buf, 8, q, 4);
  214. _mav_put_float_array(buf, 36, covariance, 21);
  215. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  216. #else
  217. mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf;
  218. packet->time_usec = time_usec;
  219. packet->x = x;
  220. packet->y = y;
  221. packet->z = z;
  222. mav_array_memcpy(packet->q, q, sizeof(float)*4);
  223. mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21);
  224. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
  225. #endif
  226. }
  227. #endif
  228. #endif
  229. // MESSAGE ATT_POS_MOCAP UNPACKING
  230. /**
  231. * @brief Get field time_usec from att_pos_mocap message
  232. *
  233. * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
  234. */
  235. static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg)
  236. {
  237. return _MAV_RETURN_uint64_t(msg, 0);
  238. }
  239. /**
  240. * @brief Get field q from att_pos_mocap message
  241. *
  242. * @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
  243. */
  244. static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q)
  245. {
  246. return _MAV_RETURN_float_array(msg, q, 4, 8);
  247. }
  248. /**
  249. * @brief Get field x from att_pos_mocap message
  250. *
  251. * @return [m] X position (NED)
  252. */
  253. static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg)
  254. {
  255. return _MAV_RETURN_float(msg, 24);
  256. }
  257. /**
  258. * @brief Get field y from att_pos_mocap message
  259. *
  260. * @return [m] Y position (NED)
  261. */
  262. static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg)
  263. {
  264. return _MAV_RETURN_float(msg, 28);
  265. }
  266. /**
  267. * @brief Get field z from att_pos_mocap message
  268. *
  269. * @return [m] Z position (NED)
  270. */
  271. static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg)
  272. {
  273. return _MAV_RETURN_float(msg, 32);
  274. }
  275. /**
  276. * @brief Get field covariance from att_pos_mocap message
  277. *
  278. * @return Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
  279. */
  280. static inline uint16_t mavlink_msg_att_pos_mocap_get_covariance(const mavlink_message_t* msg, float *covariance)
  281. {
  282. return _MAV_RETURN_float_array(msg, covariance, 21, 36);
  283. }
  284. /**
  285. * @brief Decode a att_pos_mocap message into a struct
  286. *
  287. * @param msg The message to decode
  288. * @param att_pos_mocap C-struct to decode the message contents into
  289. */
  290. static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap)
  291. {
  292. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  293. att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg);
  294. mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q);
  295. att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg);
  296. att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg);
  297. att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg);
  298. mavlink_msg_att_pos_mocap_get_covariance(msg, att_pos_mocap->covariance);
  299. #else
  300. uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN;
  301. memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
  302. memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len);
  303. #endif
  304. }