mavlink_msg_vision_speed_estimate.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390
  1. #pragma once
  2. // MESSAGE VISION_SPEED_ESTIMATE PACKING
  3. #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
  4. typedef struct __mavlink_vision_speed_estimate_t {
  5. uint64_t usec; /*< [us] Timestamp (UNIX time or time since system boot)*/
  6. float x; /*< [m/s] Global X speed*/
  7. float y; /*< [m/s] Global Y speed*/
  8. float z; /*< [m/s] Global Z speed*/
  9. float covariance[9]; /*< Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.*/
  10. 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.*/
  11. } mavlink_vision_speed_estimate_t;
  12. #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 57
  13. #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN 20
  14. #define MAVLINK_MSG_ID_103_LEN 57
  15. #define MAVLINK_MSG_ID_103_MIN_LEN 20
  16. #define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208
  17. #define MAVLINK_MSG_ID_103_CRC 208
  18. #define MAVLINK_MSG_VISION_SPEED_ESTIMATE_FIELD_COVARIANCE_LEN 9
  19. #if MAVLINK_COMMAND_24BIT
  20. #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
  21. 103, \
  22. "VISION_SPEED_ESTIMATE", \
  23. 6, \
  24. { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
  25. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
  26. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
  27. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
  28. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \
  29. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \
  30. } \
  31. }
  32. #else
  33. #define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
  34. "VISION_SPEED_ESTIMATE", \
  35. 6, \
  36. { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
  37. { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
  38. { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
  39. { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
  40. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 20, offsetof(mavlink_vision_speed_estimate_t, covariance) }, \
  41. { "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_vision_speed_estimate_t, reset_counter) }, \
  42. } \
  43. }
  44. #endif
  45. /**
  46. * @brief Pack a vision_speed_estimate message
  47. * @param system_id ID of this system
  48. * @param component_id ID of this component (e.g. 200 for IMU)
  49. * @param msg The MAVLink message to compress the data into
  50. *
  51. * @param usec [us] Timestamp (UNIX time or time since system boot)
  52. * @param x [m/s] Global X speed
  53. * @param y [m/s] Global Y speed
  54. * @param z [m/s] Global Z speed
  55. * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
  56. * @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.
  57. * @return length of the message in bytes (excluding serial stream start sign)
  58. */
  59. static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  60. uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter)
  61. {
  62. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  63. char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
  64. _mav_put_uint64_t(buf, 0, usec);
  65. _mav_put_float(buf, 8, x);
  66. _mav_put_float(buf, 12, y);
  67. _mav_put_float(buf, 16, z);
  68. _mav_put_uint8_t(buf, 56, reset_counter);
  69. _mav_put_float_array(buf, 20, covariance, 9);
  70. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  71. #else
  72. mavlink_vision_speed_estimate_t packet;
  73. packet.usec = usec;
  74. packet.x = x;
  75. packet.y = y;
  76. packet.z = z;
  77. packet.reset_counter = reset_counter;
  78. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
  79. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  80. #endif
  81. msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
  82. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  83. }
  84. /**
  85. * @brief Pack a vision_speed_estimate message
  86. * @param system_id ID of this system
  87. * @param component_id ID of this component (e.g. 200 for IMU)
  88. * @param status MAVLink status structure
  89. * @param msg The MAVLink message to compress the data into
  90. *
  91. * @param usec [us] Timestamp (UNIX time or time since system boot)
  92. * @param x [m/s] Global X speed
  93. * @param y [m/s] Global Y speed
  94. * @param z [m/s] Global Z speed
  95. * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
  96. * @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.
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_vision_speed_estimate_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  100. uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter)
  101. {
  102. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  103. char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
  104. _mav_put_uint64_t(buf, 0, usec);
  105. _mav_put_float(buf, 8, x);
  106. _mav_put_float(buf, 12, y);
  107. _mav_put_float(buf, 16, z);
  108. _mav_put_uint8_t(buf, 56, reset_counter);
  109. _mav_put_float_array(buf, 20, covariance, 9);
  110. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  111. #else
  112. mavlink_vision_speed_estimate_t packet;
  113. packet.usec = usec;
  114. packet.x = x;
  115. packet.y = y;
  116. packet.z = z;
  117. packet.reset_counter = reset_counter;
  118. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
  119. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  120. #endif
  121. msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
  122. #if MAVLINK_CRC_EXTRA
  123. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  124. #else
  125. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  126. #endif
  127. }
  128. /**
  129. * @brief Pack a vision_speed_estimate message on a channel
  130. * @param system_id ID of this system
  131. * @param component_id ID of this component (e.g. 200 for IMU)
  132. * @param chan The MAVLink channel this message will be sent over
  133. * @param msg The MAVLink message to compress the data into
  134. * @param usec [us] Timestamp (UNIX time or time since system boot)
  135. * @param x [m/s] Global X speed
  136. * @param y [m/s] Global Y speed
  137. * @param z [m/s] Global Z speed
  138. * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
  139. * @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.
  140. * @return length of the message in bytes (excluding serial stream start sign)
  141. */
  142. static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  143. mavlink_message_t* msg,
  144. uint64_t usec,float x,float y,float z,const float *covariance,uint8_t reset_counter)
  145. {
  146. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  147. char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
  148. _mav_put_uint64_t(buf, 0, usec);
  149. _mav_put_float(buf, 8, x);
  150. _mav_put_float(buf, 12, y);
  151. _mav_put_float(buf, 16, z);
  152. _mav_put_uint8_t(buf, 56, reset_counter);
  153. _mav_put_float_array(buf, 20, covariance, 9);
  154. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  155. #else
  156. mavlink_vision_speed_estimate_t packet;
  157. packet.usec = usec;
  158. packet.x = x;
  159. packet.y = y;
  160. packet.z = z;
  161. packet.reset_counter = reset_counter;
  162. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
  163. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  164. #endif
  165. msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
  166. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  167. }
  168. /**
  169. * @brief Encode a vision_speed_estimate struct
  170. *
  171. * @param system_id ID of this system
  172. * @param component_id ID of this component (e.g. 200 for IMU)
  173. * @param msg The MAVLink message to compress the data into
  174. * @param vision_speed_estimate C-struct to read the message contents from
  175. */
  176. static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
  177. {
  178. return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter);
  179. }
  180. /**
  181. * @brief Encode a vision_speed_estimate struct on a channel
  182. *
  183. * @param system_id ID of this system
  184. * @param component_id ID of this component (e.g. 200 for IMU)
  185. * @param chan The MAVLink channel this message will be sent over
  186. * @param msg The MAVLink message to compress the data into
  187. * @param vision_speed_estimate C-struct to read the message contents from
  188. */
  189. static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
  190. {
  191. return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter);
  192. }
  193. /**
  194. * @brief Encode a vision_speed_estimate struct with provided status structure
  195. *
  196. * @param system_id ID of this system
  197. * @param component_id ID of this component (e.g. 200 for IMU)
  198. * @param status MAVLink status structure
  199. * @param msg The MAVLink message to compress the data into
  200. * @param vision_speed_estimate C-struct to read the message contents from
  201. */
  202. static inline uint16_t mavlink_msg_vision_speed_estimate_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
  203. {
  204. return mavlink_msg_vision_speed_estimate_pack_status(system_id, component_id, _status, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter);
  205. }
  206. /**
  207. * @brief Send a vision_speed_estimate message
  208. * @param chan MAVLink channel to send the message
  209. *
  210. * @param usec [us] Timestamp (UNIX time or time since system boot)
  211. * @param x [m/s] Global X speed
  212. * @param y [m/s] Global Y speed
  213. * @param z [m/s] Global Z speed
  214. * @param covariance Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
  215. * @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.
  216. */
  217. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  218. static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter)
  219. {
  220. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  221. char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN];
  222. _mav_put_uint64_t(buf, 0, usec);
  223. _mav_put_float(buf, 8, x);
  224. _mav_put_float(buf, 12, y);
  225. _mav_put_float(buf, 16, z);
  226. _mav_put_uint8_t(buf, 56, reset_counter);
  227. _mav_put_float_array(buf, 20, covariance, 9);
  228. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  229. #else
  230. mavlink_vision_speed_estimate_t packet;
  231. packet.usec = usec;
  232. packet.x = x;
  233. packet.y = y;
  234. packet.z = z;
  235. packet.reset_counter = reset_counter;
  236. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
  237. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  238. #endif
  239. }
  240. /**
  241. * @brief Send a vision_speed_estimate message
  242. * @param chan MAVLink channel to send the message
  243. * @param struct The MAVLink struct to serialize
  244. */
  245. static inline void mavlink_msg_vision_speed_estimate_send_struct(mavlink_channel_t chan, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
  246. {
  247. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  248. mavlink_msg_vision_speed_estimate_send(chan, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z, vision_speed_estimate->covariance, vision_speed_estimate->reset_counter);
  249. #else
  250. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)vision_speed_estimate, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  251. #endif
  252. }
  253. #if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  254. /*
  255. This variant of _send() can be used to save stack space by re-using
  256. memory from the receive buffer. The caller provides a
  257. mavlink_message_t which is the size of a full mavlink message. This
  258. is usually the receive buffer for the channel, and allows a reply to an
  259. incoming message with minimum stack space usage.
  260. */
  261. static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, const float *covariance, uint8_t reset_counter)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. char *buf = (char *)msgbuf;
  265. _mav_put_uint64_t(buf, 0, usec);
  266. _mav_put_float(buf, 8, x);
  267. _mav_put_float(buf, 12, y);
  268. _mav_put_float(buf, 16, z);
  269. _mav_put_uint8_t(buf, 56, reset_counter);
  270. _mav_put_float_array(buf, 20, covariance, 9);
  271. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  272. #else
  273. mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf;
  274. packet->usec = usec;
  275. packet->x = x;
  276. packet->y = y;
  277. packet->z = z;
  278. packet->reset_counter = reset_counter;
  279. mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9);
  280. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC);
  281. #endif
  282. }
  283. #endif
  284. #endif
  285. // MESSAGE VISION_SPEED_ESTIMATE UNPACKING
  286. /**
  287. * @brief Get field usec from vision_speed_estimate message
  288. *
  289. * @return [us] Timestamp (UNIX time or time since system boot)
  290. */
  291. static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg)
  292. {
  293. return _MAV_RETURN_uint64_t(msg, 0);
  294. }
  295. /**
  296. * @brief Get field x from vision_speed_estimate message
  297. *
  298. * @return [m/s] Global X speed
  299. */
  300. static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
  301. {
  302. return _MAV_RETURN_float(msg, 8);
  303. }
  304. /**
  305. * @brief Get field y from vision_speed_estimate message
  306. *
  307. * @return [m/s] Global Y speed
  308. */
  309. static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
  310. {
  311. return _MAV_RETURN_float(msg, 12);
  312. }
  313. /**
  314. * @brief Get field z from vision_speed_estimate message
  315. *
  316. * @return [m/s] Global Z speed
  317. */
  318. static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
  319. {
  320. return _MAV_RETURN_float(msg, 16);
  321. }
  322. /**
  323. * @brief Get field covariance from vision_speed_estimate message
  324. *
  325. * @return Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array.
  326. */
  327. static inline uint16_t mavlink_msg_vision_speed_estimate_get_covariance(const mavlink_message_t* msg, float *covariance)
  328. {
  329. return _MAV_RETURN_float_array(msg, covariance, 9, 20);
  330. }
  331. /**
  332. * @brief Get field reset_counter from vision_speed_estimate message
  333. *
  334. * @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.
  335. */
  336. static inline uint8_t mavlink_msg_vision_speed_estimate_get_reset_counter(const mavlink_message_t* msg)
  337. {
  338. return _MAV_RETURN_uint8_t(msg, 56);
  339. }
  340. /**
  341. * @brief Decode a vision_speed_estimate message into a struct
  342. *
  343. * @param msg The message to decode
  344. * @param vision_speed_estimate C-struct to decode the message contents into
  345. */
  346. static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
  347. {
  348. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  349. vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
  350. vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
  351. vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
  352. vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
  353. mavlink_msg_vision_speed_estimate_get_covariance(msg, vision_speed_estimate->covariance);
  354. vision_speed_estimate->reset_counter = mavlink_msg_vision_speed_estimate_get_reset_counter(msg);
  355. #else
  356. uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN;
  357. memset(vision_speed_estimate, 0, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN);
  358. memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), len);
  359. #endif
  360. }