mavlink_msg_vision_position_estimate.h 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474
  1. #pragma once
  2. // MESSAGE VISION_POSITION_ESTIMATE PACKING
  3. #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102
  4. typedef struct __mavlink_vision_position_estimate_t {
  5. uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/
  6. float x; /*< [m] Local X position*/
  7. float y; /*< [m] Local Y position*/
  8. float z; /*< [m] Local Z position*/
  9. float roll; /*< [rad] Roll angle*/
  10. float pitch; /*< [rad] Pitch angle*/
  11. float yaw; /*< [rad] Yaw angle*/
  12. float covariance[21]; /*< Row-major representation of 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.*/
  13. uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/
  14. } mavlink_vision_position_estimate_t;
  15. #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 117
  16. #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN 32
  17. #define MAVLINK_MSG_ID_102_LEN 117
  18. #define MAVLINK_MSG_ID_102_MIN_LEN 32
  19. #define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158
  20. #define MAVLINK_MSG_ID_102_CRC 158
  21. #define MAVLINK_MSG_VISION_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21
  22. #if MAVLINK_COMMAND_24BIT
  23. #define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \
  24. 102, \
  25. "VISION_POSITION_ESTIMATE", \
  26. 9, \
  27. { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \
  28. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \
  29. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \
  30. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \
  31. { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \
  32. { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \
  33. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \
  34. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vision_position_estimate_t, covariance) }, \
  35. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_vision_position_estimate_t, reset_counter) }, \
  36. } \
  37. }
  38. #else
  39. #define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \
  40. "VISION_POSITION_ESTIMATE", \
  41. 9, \
  42. { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \
  43. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \
  44. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \
  45. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \
  46. { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \
  47. { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \
  48. { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \
  49. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_vision_position_estimate_t, covariance) }, \
  50. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_vision_position_estimate_t, reset_counter) }, \
  51. } \
  52. }
  53. #endif
  54. /**
  55. * @brief Pack a vision_position_estimate 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 usec [us] Timestamp (UNIX time or time since system boot)
  61. * @param x [m] Local X position
  62. * @param y [m] Local Y position
  63. * @param z [m] Local Z position
  64. * @param roll [rad] Roll angle
  65. * @param pitch [rad] Pitch angle
  66. * @param yaw [rad] Yaw angle
  67. * @param covariance Row-major representation of 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.
  68. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  69. * @return length of the message in bytes (excluding serial stream start sign)
  70. */
  71. static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  72. uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter)
  73. {
  74. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  75. char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN];
  76. _mav_put_uint64_t(buf, 0, usec);
  77. _mav_put_float(buf, 8, x);
  78. _mav_put_float(buf, 12, y);
  79. _mav_put_float(buf, 16, z);
  80. _mav_put_float(buf, 20, roll);
  81. _mav_put_float(buf, 24, pitch);
  82. _mav_put_float(buf, 28, yaw);
  83. _mav_put_uint8_t(buf, 116, reset_counter);
  84. _mav_put_float_array(buf, 32, covariance, 21);
  85. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  86. #else
  87. mavlink_vision_position_estimate_t packet;
  88. packet.usec = usec;
  89. packet.x = x;
  90. packet.y = y;
  91. packet.z = z;
  92. packet.roll = roll;
  93. packet.pitch = pitch;
  94. packet.yaw = yaw;
  95. packet.reset_counter = reset_counter;
  96. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  97. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  98. #endif
  99. msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
  100. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  101. }
  102. /**
  103. * @brief Pack a vision_position_estimate message
  104. * @param system_id ID of this system
  105. * @param component_id ID of this component (e.g. 200 for IMU)
  106. * @param status MAVLink status structure
  107. * @param msg The MAVLink message to compress the data into
  108. *
  109. * @param usec [us] Timestamp (UNIX time or time since system boot)
  110. * @param x [m] Local X position
  111. * @param y [m] Local Y position
  112. * @param z [m] Local Z position
  113. * @param roll [rad] Roll angle
  114. * @param pitch [rad] Pitch angle
  115. * @param yaw [rad] Yaw angle
  116. * @param covariance Row-major representation of 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.
  117. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  118. * @return length of the message in bytes (excluding serial stream start sign)
  119. */
  120. static inline uint16_t mavlink_msg_vision_position_estimate_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  121. uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter)
  122. {
  123. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  124. char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN];
  125. _mav_put_uint64_t(buf, 0, usec);
  126. _mav_put_float(buf, 8, x);
  127. _mav_put_float(buf, 12, y);
  128. _mav_put_float(buf, 16, z);
  129. _mav_put_float(buf, 20, roll);
  130. _mav_put_float(buf, 24, pitch);
  131. _mav_put_float(buf, 28, yaw);
  132. _mav_put_uint8_t(buf, 116, reset_counter);
  133. _mav_put_float_array(buf, 32, covariance, 21);
  134. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  135. #else
  136. mavlink_vision_position_estimate_t packet;
  137. packet.usec = usec;
  138. packet.x = x;
  139. packet.y = y;
  140. packet.z = z;
  141. packet.roll = roll;
  142. packet.pitch = pitch;
  143. packet.yaw = yaw;
  144. packet.reset_counter = reset_counter;
  145. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  146. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  147. #endif
  148. msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
  149. #if MAVLINK_CRC_EXTRA
  150. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  151. #else
  152. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  153. #endif
  154. }
  155. /**
  156. * @brief Pack a vision_position_estimate message on a channel
  157. * @param system_id ID of this system
  158. * @param component_id ID of this component (e.g. 200 for IMU)
  159. * @param chan The MAVLink channel this message will be sent over
  160. * @param msg The MAVLink message to compress the data into
  161. * @param usec [us] Timestamp (UNIX time or time since system boot)
  162. * @param x [m] Local X position
  163. * @param y [m] Local Y position
  164. * @param z [m] Local Z position
  165. * @param roll [rad] Roll angle
  166. * @param pitch [rad] Pitch angle
  167. * @param yaw [rad] Yaw angle
  168. * @param covariance Row-major representation of 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.
  169. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  170. * @return length of the message in bytes (excluding serial stream start sign)
  171. */
  172. static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  173. mavlink_message_t* msg,
  174. uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw,const float *covariance,uint8_t reset_counter)
  175. {
  176. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  177. char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN];
  178. _mav_put_uint64_t(buf, 0, usec);
  179. _mav_put_float(buf, 8, x);
  180. _mav_put_float(buf, 12, y);
  181. _mav_put_float(buf, 16, z);
  182. _mav_put_float(buf, 20, roll);
  183. _mav_put_float(buf, 24, pitch);
  184. _mav_put_float(buf, 28, yaw);
  185. _mav_put_uint8_t(buf, 116, reset_counter);
  186. _mav_put_float_array(buf, 32, covariance, 21);
  187. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  188. #else
  189. mavlink_vision_position_estimate_t packet;
  190. packet.usec = usec;
  191. packet.x = x;
  192. packet.y = y;
  193. packet.z = z;
  194. packet.roll = roll;
  195. packet.pitch = pitch;
  196. packet.yaw = yaw;
  197. packet.reset_counter = reset_counter;
  198. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  199. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  200. #endif
  201. msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
  202. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  203. }
  204. /**
  205. * @brief Encode a vision_position_estimate struct
  206. *
  207. * @param system_id ID of this system
  208. * @param component_id ID of this component (e.g. 200 for IMU)
  209. * @param msg The MAVLink message to compress the data into
  210. * @param vision_position_estimate C-struct to read the message contents from
  211. */
  212. static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
  213. {
  214. return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter);
  215. }
  216. /**
  217. * @brief Encode a vision_position_estimate struct on a channel
  218. *
  219. * @param system_id ID of this system
  220. * @param component_id ID of this component (e.g. 200 for IMU)
  221. * @param chan The MAVLink channel this message will be sent over
  222. * @param msg The MAVLink message to compress the data into
  223. * @param vision_position_estimate C-struct to read the message contents from
  224. */
  225. static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
  226. {
  227. return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter);
  228. }
  229. /**
  230. * @brief Encode a vision_position_estimate struct with provided status structure
  231. *
  232. * @param system_id ID of this system
  233. * @param component_id ID of this component (e.g. 200 for IMU)
  234. * @param status MAVLink status structure
  235. * @param msg The MAVLink message to compress the data into
  236. * @param vision_position_estimate C-struct to read the message contents from
  237. */
  238. static inline uint16_t mavlink_msg_vision_position_estimate_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
  239. {
  240. return mavlink_msg_vision_position_estimate_pack_status(system_id, component_id, _status, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter);
  241. }
  242. /**
  243. * @brief Send a vision_position_estimate message
  244. * @param chan MAVLink channel to send the message
  245. *
  246. * @param usec [us] Timestamp (UNIX time or time since system boot)
  247. * @param x [m] Local X position
  248. * @param y [m] Local Y position
  249. * @param z [m] Local Z position
  250. * @param roll [rad] Roll angle
  251. * @param pitch [rad] Pitch angle
  252. * @param yaw [rad] Yaw angle
  253. * @param covariance Row-major representation of 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.
  254. * @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  255. */
  256. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  257. static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter)
  258. {
  259. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  260. char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN];
  261. _mav_put_uint64_t(buf, 0, usec);
  262. _mav_put_float(buf, 8, x);
  263. _mav_put_float(buf, 12, y);
  264. _mav_put_float(buf, 16, z);
  265. _mav_put_float(buf, 20, roll);
  266. _mav_put_float(buf, 24, pitch);
  267. _mav_put_float(buf, 28, yaw);
  268. _mav_put_uint8_t(buf, 116, reset_counter);
  269. _mav_put_float_array(buf, 32, covariance, 21);
  270. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  271. #else
  272. mavlink_vision_position_estimate_t packet;
  273. packet.usec = usec;
  274. packet.x = x;
  275. packet.y = y;
  276. packet.z = z;
  277. packet.roll = roll;
  278. packet.pitch = pitch;
  279. packet.yaw = yaw;
  280. packet.reset_counter = reset_counter;
  281. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  282. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  283. #endif
  284. }
  285. /**
  286. * @brief Send a vision_position_estimate message
  287. * @param chan MAVLink channel to send the message
  288. * @param struct The MAVLink struct to serialize
  289. */
  290. static inline void mavlink_msg_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_position_estimate_t* vision_position_estimate)
  291. {
  292. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  293. mavlink_msg_vision_position_estimate_send(chan, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw, vision_position_estimate->covariance, vision_position_estimate->reset_counter);
  294. #else
  295. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)vision_position_estimate, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  296. #endif
  297. }
  298. #if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  299. /*
  300. This variant of _send() can be used to save stack space by re-using
  301. memory from the receive buffer. The caller provides a
  302. mavlink_message_t which is the size of a full mavlink message. This
  303. is usually the receive buffer for the channel, and allows a reply to an
  304. incoming message with minimum stack space usage.
  305. */
  306. static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter)
  307. {
  308. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  309. char *buf = (char *)msgbuf;
  310. _mav_put_uint64_t(buf, 0, usec);
  311. _mav_put_float(buf, 8, x);
  312. _mav_put_float(buf, 12, y);
  313. _mav_put_float(buf, 16, z);
  314. _mav_put_float(buf, 20, roll);
  315. _mav_put_float(buf, 24, pitch);
  316. _mav_put_float(buf, 28, yaw);
  317. _mav_put_uint8_t(buf, 116, reset_counter);
  318. _mav_put_float_array(buf, 32, covariance, 21);
  319. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  320. #else
  321. mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf;
  322. packet->usec = usec;
  323. packet->x = x;
  324. packet->y = y;
  325. packet->z = z;
  326. packet->roll = roll;
  327. packet->pitch = pitch;
  328. packet->yaw = yaw;
  329. packet->reset_counter = reset_counter;
  330. mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21);
  331. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC);
  332. #endif
  333. }
  334. #endif
  335. #endif
  336. // MESSAGE VISION_POSITION_ESTIMATE UNPACKING
  337. /**
  338. * @brief Get field usec from vision_position_estimate message
  339. *
  340. * @return [us] Timestamp (UNIX time or time since system boot)
  341. */
  342. static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg)
  343. {
  344. return _MAV_RETURN_uint64_t(msg, 0);
  345. }
  346. /**
  347. * @brief Get field x from vision_position_estimate message
  348. *
  349. * @return [m] Local X position
  350. */
  351. static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg)
  352. {
  353. return _MAV_RETURN_float(msg, 8);
  354. }
  355. /**
  356. * @brief Get field y from vision_position_estimate message
  357. *
  358. * @return [m] Local Y position
  359. */
  360. static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg)
  361. {
  362. return _MAV_RETURN_float(msg, 12);
  363. }
  364. /**
  365. * @brief Get field z from vision_position_estimate message
  366. *
  367. * @return [m] Local Z position
  368. */
  369. static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg)
  370. {
  371. return _MAV_RETURN_float(msg, 16);
  372. }
  373. /**
  374. * @brief Get field roll from vision_position_estimate message
  375. *
  376. * @return [rad] Roll angle
  377. */
  378. static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg)
  379. {
  380. return _MAV_RETURN_float(msg, 20);
  381. }
  382. /**
  383. * @brief Get field pitch from vision_position_estimate message
  384. *
  385. * @return [rad] Pitch angle
  386. */
  387. static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
  388. {
  389. return _MAV_RETURN_float(msg, 24);
  390. }
  391. /**
  392. * @brief Get field yaw from vision_position_estimate message
  393. *
  394. * @return [rad] Yaw angle
  395. */
  396. static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
  397. {
  398. return _MAV_RETURN_float(msg, 28);
  399. }
  400. /**
  401. * @brief Get field covariance from vision_position_estimate message
  402. *
  403. * @return Row-major representation of 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.
  404. */
  405. static inline uint16_t mavlink_msg_vision_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance)
  406. {
  407. return _MAV_RETURN_float_array(msg, covariance, 21, 32);
  408. }
  409. /**
  410. * @brief Get field reset_counter from vision_position_estimate message
  411. *
  412. * @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
  413. */
  414. static inline uint8_t mavlink_msg_vision_position_estimate_get_reset_counter(const mavlink_message_t* msg)
  415. {
  416. return _MAV_RETURN_uint8_t(msg, 116);
  417. }
  418. /**
  419. * @brief Decode a vision_position_estimate message into a struct
  420. *
  421. * @param msg The message to decode
  422. * @param vision_position_estimate C-struct to decode the message contents into
  423. */
  424. static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
  425. {
  426. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  427. vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);
  428. vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg);
  429. vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg);
  430. vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg);
  431. vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg);
  432. vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg);
  433. vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg);
  434. mavlink_msg_vision_position_estimate_get_covariance(msg, vision_position_estimate->covariance);
  435. vision_position_estimate->reset_counter = mavlink_msg_vision_position_estimate_get_reset_counter(msg);
  436. #else
  437. uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN;
  438. memset(vision_position_estimate, 0, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  439. memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), len);
  440. #endif
  441. }