mavlink_msg_vision_position_estimate.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405
  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 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 usec [us] Timestamp (UNIX time or time since system boot)
  109. * @param x [m] Local X position
  110. * @param y [m] Local Y position
  111. * @param z [m] Local Z position
  112. * @param roll [rad] Roll angle
  113. * @param pitch [rad] Pitch angle
  114. * @param yaw [rad] Yaw angle
  115. * @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.
  116. * @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.
  117. * @return length of the message in bytes (excluding serial stream start sign)
  118. */
  119. static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  120. 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. 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);
  150. }
  151. /**
  152. * @brief Encode a vision_position_estimate 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 vision_position_estimate C-struct to read the message contents from
  158. */
  159. 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)
  160. {
  161. 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);
  162. }
  163. /**
  164. * @brief Encode a vision_position_estimate 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 vision_position_estimate C-struct to read the message contents from
  171. */
  172. 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)
  173. {
  174. 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);
  175. }
  176. /**
  177. * @brief Send a vision_position_estimate message
  178. * @param chan MAVLink channel to send the message
  179. *
  180. * @param usec [us] Timestamp (UNIX time or time since system boot)
  181. * @param x [m] Local X position
  182. * @param y [m] Local Y position
  183. * @param z [m] Local Z position
  184. * @param roll [rad] Roll angle
  185. * @param pitch [rad] Pitch angle
  186. * @param yaw [rad] Yaw angle
  187. * @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.
  188. * @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.
  189. */
  190. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  191. 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)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN];
  195. _mav_put_uint64_t(buf, 0, usec);
  196. _mav_put_float(buf, 8, x);
  197. _mav_put_float(buf, 12, y);
  198. _mav_put_float(buf, 16, z);
  199. _mav_put_float(buf, 20, roll);
  200. _mav_put_float(buf, 24, pitch);
  201. _mav_put_float(buf, 28, yaw);
  202. _mav_put_uint8_t(buf, 116, reset_counter);
  203. _mav_put_float_array(buf, 32, covariance, 21);
  204. _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);
  205. #else
  206. mavlink_vision_position_estimate_t packet;
  207. packet.usec = usec;
  208. packet.x = x;
  209. packet.y = y;
  210. packet.z = z;
  211. packet.roll = roll;
  212. packet.pitch = pitch;
  213. packet.yaw = yaw;
  214. packet.reset_counter = reset_counter;
  215. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
  216. _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);
  217. #endif
  218. }
  219. /**
  220. * @brief Send a vision_position_estimate 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_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_position_estimate_t* vision_position_estimate)
  225. {
  226. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  227. 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);
  228. #else
  229. _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);
  230. #endif
  231. }
  232. #if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_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_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)
  241. {
  242. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  243. char *buf = (char *)msgbuf;
  244. _mav_put_uint64_t(buf, 0, usec);
  245. _mav_put_float(buf, 8, x);
  246. _mav_put_float(buf, 12, y);
  247. _mav_put_float(buf, 16, z);
  248. _mav_put_float(buf, 20, roll);
  249. _mav_put_float(buf, 24, pitch);
  250. _mav_put_float(buf, 28, yaw);
  251. _mav_put_uint8_t(buf, 116, reset_counter);
  252. _mav_put_float_array(buf, 32, covariance, 21);
  253. _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);
  254. #else
  255. mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf;
  256. packet->usec = usec;
  257. packet->x = x;
  258. packet->y = y;
  259. packet->z = z;
  260. packet->roll = roll;
  261. packet->pitch = pitch;
  262. packet->yaw = yaw;
  263. packet->reset_counter = reset_counter;
  264. mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21);
  265. _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);
  266. #endif
  267. }
  268. #endif
  269. #endif
  270. // MESSAGE VISION_POSITION_ESTIMATE UNPACKING
  271. /**
  272. * @brief Get field usec from vision_position_estimate message
  273. *
  274. * @return [us] Timestamp (UNIX time or time since system boot)
  275. */
  276. static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg)
  277. {
  278. return _MAV_RETURN_uint64_t(msg, 0);
  279. }
  280. /**
  281. * @brief Get field x from vision_position_estimate message
  282. *
  283. * @return [m] Local X position
  284. */
  285. static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg)
  286. {
  287. return _MAV_RETURN_float(msg, 8);
  288. }
  289. /**
  290. * @brief Get field y from vision_position_estimate message
  291. *
  292. * @return [m] Local Y position
  293. */
  294. static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg)
  295. {
  296. return _MAV_RETURN_float(msg, 12);
  297. }
  298. /**
  299. * @brief Get field z from vision_position_estimate message
  300. *
  301. * @return [m] Local Z position
  302. */
  303. static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg)
  304. {
  305. return _MAV_RETURN_float(msg, 16);
  306. }
  307. /**
  308. * @brief Get field roll from vision_position_estimate message
  309. *
  310. * @return [rad] Roll angle
  311. */
  312. static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg)
  313. {
  314. return _MAV_RETURN_float(msg, 20);
  315. }
  316. /**
  317. * @brief Get field pitch from vision_position_estimate message
  318. *
  319. * @return [rad] Pitch angle
  320. */
  321. static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
  322. {
  323. return _MAV_RETURN_float(msg, 24);
  324. }
  325. /**
  326. * @brief Get field yaw from vision_position_estimate message
  327. *
  328. * @return [rad] Yaw angle
  329. */
  330. static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
  331. {
  332. return _MAV_RETURN_float(msg, 28);
  333. }
  334. /**
  335. * @brief Get field covariance from vision_position_estimate message
  336. *
  337. * @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.
  338. */
  339. static inline uint16_t mavlink_msg_vision_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance)
  340. {
  341. return _MAV_RETURN_float_array(msg, covariance, 21, 32);
  342. }
  343. /**
  344. * @brief Get field reset_counter from vision_position_estimate message
  345. *
  346. * @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.
  347. */
  348. static inline uint8_t mavlink_msg_vision_position_estimate_get_reset_counter(const mavlink_message_t* msg)
  349. {
  350. return _MAV_RETURN_uint8_t(msg, 116);
  351. }
  352. /**
  353. * @brief Decode a vision_position_estimate message into a struct
  354. *
  355. * @param msg The message to decode
  356. * @param vision_position_estimate C-struct to decode the message contents into
  357. */
  358. static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
  359. {
  360. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  361. vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);
  362. vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg);
  363. vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg);
  364. vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg);
  365. vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg);
  366. vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg);
  367. vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg);
  368. mavlink_msg_vision_position_estimate_get_covariance(msg, vision_position_estimate->covariance);
  369. vision_position_estimate->reset_counter = mavlink_msg_vision_position_estimate_get_reset_counter(msg);
  370. #else
  371. uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN;
  372. memset(vision_position_estimate, 0, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN);
  373. memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), len);
  374. #endif
  375. }