mavlink_msg_global_position_int_cov.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430
  1. #pragma once
  2. // MESSAGE GLOBAL_POSITION_INT_COV PACKING
  3. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
  4. typedef struct __mavlink_global_position_int_cov_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. int32_t lat; /*< [degE7] Latitude*/
  7. int32_t lon; /*< [degE7] Longitude*/
  8. int32_t alt; /*< [mm] Altitude in meters above MSL*/
  9. int32_t relative_alt; /*< [mm] Altitude above ground*/
  10. float vx; /*< [m/s] Ground X Speed (Latitude)*/
  11. float vy; /*< [m/s] Ground Y Speed (Longitude)*/
  12. float vz; /*< [m/s] Ground Z Speed (Altitude)*/
  13. float covariance[36]; /*< Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.*/
  14. uint8_t estimator_type; /*< Class id of the estimator this estimate originated from.*/
  15. } mavlink_global_position_int_cov_t;
  16. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 181
  17. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN 181
  18. #define MAVLINK_MSG_ID_63_LEN 181
  19. #define MAVLINK_MSG_ID_63_MIN_LEN 181
  20. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 119
  21. #define MAVLINK_MSG_ID_63_CRC 119
  22. #define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
  23. #if MAVLINK_COMMAND_24BIT
  24. #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
  25. 63, \
  26. "GLOBAL_POSITION_INT_COV", \
  27. 10, \
  28. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \
  29. { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
  30. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \
  31. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \
  32. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \
  33. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
  34. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \
  35. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \
  36. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \
  37. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
  38. } \
  39. }
  40. #else
  41. #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
  42. "GLOBAL_POSITION_INT_COV", \
  43. 10, \
  44. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_usec) }, \
  45. { "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 180, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
  46. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, lat) }, \
  47. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lon) }, \
  48. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, alt) }, \
  49. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
  50. { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_int_cov_t, vx) }, \
  51. { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vy) }, \
  52. { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vz) }, \
  53. { "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 36, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
  54. } \
  55. }
  56. #endif
  57. /**
  58. * @brief Pack a global_position_int_cov message
  59. * @param system_id ID of this system
  60. * @param component_id ID of this component (e.g. 200 for IMU)
  61. * @param msg The MAVLink message to compress the data into
  62. *
  63. * @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.
  64. * @param estimator_type Class id of the estimator this estimate originated from.
  65. * @param lat [degE7] Latitude
  66. * @param lon [degE7] Longitude
  67. * @param alt [mm] Altitude in meters above MSL
  68. * @param relative_alt [mm] Altitude above ground
  69. * @param vx [m/s] Ground X Speed (Latitude)
  70. * @param vy [m/s] Ground Y Speed (Longitude)
  71. * @param vz [m/s] Ground Z Speed (Altitude)
  72. * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
  73. * @return length of the message in bytes (excluding serial stream start sign)
  74. */
  75. static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  76. uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
  77. {
  78. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  79. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
  80. _mav_put_uint64_t(buf, 0, time_usec);
  81. _mav_put_int32_t(buf, 8, lat);
  82. _mav_put_int32_t(buf, 12, lon);
  83. _mav_put_int32_t(buf, 16, alt);
  84. _mav_put_int32_t(buf, 20, relative_alt);
  85. _mav_put_float(buf, 24, vx);
  86. _mav_put_float(buf, 28, vy);
  87. _mav_put_float(buf, 32, vz);
  88. _mav_put_uint8_t(buf, 180, estimator_type);
  89. _mav_put_float_array(buf, 36, covariance, 36);
  90. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
  91. #else
  92. mavlink_global_position_int_cov_t packet;
  93. packet.time_usec = time_usec;
  94. packet.lat = lat;
  95. packet.lon = lon;
  96. packet.alt = alt;
  97. packet.relative_alt = relative_alt;
  98. packet.vx = vx;
  99. packet.vy = vy;
  100. packet.vz = vz;
  101. packet.estimator_type = estimator_type;
  102. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
  103. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
  104. #endif
  105. msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
  106. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  107. }
  108. /**
  109. * @brief Pack a global_position_int_cov message on a channel
  110. * @param system_id ID of this system
  111. * @param component_id ID of this component (e.g. 200 for IMU)
  112. * @param chan The MAVLink channel this message will be sent over
  113. * @param msg The MAVLink message to compress the data into
  114. * @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.
  115. * @param estimator_type Class id of the estimator this estimate originated from.
  116. * @param lat [degE7] Latitude
  117. * @param lon [degE7] Longitude
  118. * @param alt [mm] Altitude in meters above MSL
  119. * @param relative_alt [mm] Altitude above ground
  120. * @param vx [m/s] Ground X Speed (Latitude)
  121. * @param vy [m/s] Ground Y Speed (Longitude)
  122. * @param vz [m/s] Ground Z Speed (Altitude)
  123. * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
  124. * @return length of the message in bytes (excluding serial stream start sign)
  125. */
  126. static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  127. mavlink_message_t* msg,
  128. uint64_t time_usec,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance)
  129. {
  130. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  131. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
  132. _mav_put_uint64_t(buf, 0, time_usec);
  133. _mav_put_int32_t(buf, 8, lat);
  134. _mav_put_int32_t(buf, 12, lon);
  135. _mav_put_int32_t(buf, 16, alt);
  136. _mav_put_int32_t(buf, 20, relative_alt);
  137. _mav_put_float(buf, 24, vx);
  138. _mav_put_float(buf, 28, vy);
  139. _mav_put_float(buf, 32, vz);
  140. _mav_put_uint8_t(buf, 180, estimator_type);
  141. _mav_put_float_array(buf, 36, covariance, 36);
  142. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
  143. #else
  144. mavlink_global_position_int_cov_t packet;
  145. packet.time_usec = time_usec;
  146. packet.lat = lat;
  147. packet.lon = lon;
  148. packet.alt = alt;
  149. packet.relative_alt = relative_alt;
  150. packet.vx = vx;
  151. packet.vy = vy;
  152. packet.vz = vz;
  153. packet.estimator_type = estimator_type;
  154. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
  155. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
  156. #endif
  157. msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
  158. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  159. }
  160. /**
  161. * @brief Encode a global_position_int_cov struct
  162. *
  163. * @param system_id ID of this system
  164. * @param component_id ID of this component (e.g. 200 for IMU)
  165. * @param msg The MAVLink message to compress the data into
  166. * @param global_position_int_cov C-struct to read the message contents from
  167. */
  168. static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
  169. {
  170. return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
  171. }
  172. /**
  173. * @brief Encode a global_position_int_cov struct on a channel
  174. *
  175. * @param system_id ID of this system
  176. * @param component_id ID of this component (e.g. 200 for IMU)
  177. * @param chan The MAVLink channel this message will be sent over
  178. * @param msg The MAVLink message to compress the data into
  179. * @param global_position_int_cov C-struct to read the message contents from
  180. */
  181. static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
  182. {
  183. return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
  184. }
  185. /**
  186. * @brief Send a global_position_int_cov message
  187. * @param chan MAVLink channel to send the message
  188. *
  189. * @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.
  190. * @param estimator_type Class id of the estimator this estimate originated from.
  191. * @param lat [degE7] Latitude
  192. * @param lon [degE7] Longitude
  193. * @param alt [mm] Altitude in meters above MSL
  194. * @param relative_alt [mm] Altitude above ground
  195. * @param vx [m/s] Ground X Speed (Latitude)
  196. * @param vy [m/s] Ground Y Speed (Longitude)
  197. * @param vz [m/s] Ground Z Speed (Altitude)
  198. * @param covariance Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
  199. */
  200. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  201. static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
  202. {
  203. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  204. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
  205. _mav_put_uint64_t(buf, 0, time_usec);
  206. _mav_put_int32_t(buf, 8, lat);
  207. _mav_put_int32_t(buf, 12, lon);
  208. _mav_put_int32_t(buf, 16, alt);
  209. _mav_put_int32_t(buf, 20, relative_alt);
  210. _mav_put_float(buf, 24, vx);
  211. _mav_put_float(buf, 28, vy);
  212. _mav_put_float(buf, 32, vz);
  213. _mav_put_uint8_t(buf, 180, estimator_type);
  214. _mav_put_float_array(buf, 36, covariance, 36);
  215. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  216. #else
  217. mavlink_global_position_int_cov_t packet;
  218. packet.time_usec = time_usec;
  219. packet.lat = lat;
  220. packet.lon = lon;
  221. packet.alt = alt;
  222. packet.relative_alt = relative_alt;
  223. packet.vx = vx;
  224. packet.vy = vy;
  225. packet.vz = vz;
  226. packet.estimator_type = estimator_type;
  227. mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
  228. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  229. #endif
  230. }
  231. /**
  232. * @brief Send a global_position_int_cov message
  233. * @param chan MAVLink channel to send the message
  234. * @param struct The MAVLink struct to serialize
  235. */
  236. static inline void mavlink_msg_global_position_int_cov_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_cov_t* global_position_int_cov)
  237. {
  238. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  239. mavlink_msg_global_position_int_cov_send(chan, global_position_int_cov->time_usec, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
  240. #else
  241. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)global_position_int_cov, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  242. #endif
  243. }
  244. #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  245. /*
  246. This variant of _send() can be used to save stack space by re-using
  247. memory from the receive buffer. The caller provides a
  248. mavlink_message_t which is the size of a full mavlink message. This
  249. is usually the receive buffer for the channel, and allows a reply to an
  250. incoming message with minimum stack space usage.
  251. */
  252. static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
  253. {
  254. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  255. char *buf = (char *)msgbuf;
  256. _mav_put_uint64_t(buf, 0, time_usec);
  257. _mav_put_int32_t(buf, 8, lat);
  258. _mav_put_int32_t(buf, 12, lon);
  259. _mav_put_int32_t(buf, 16, alt);
  260. _mav_put_int32_t(buf, 20, relative_alt);
  261. _mav_put_float(buf, 24, vx);
  262. _mav_put_float(buf, 28, vy);
  263. _mav_put_float(buf, 32, vz);
  264. _mav_put_uint8_t(buf, 180, estimator_type);
  265. _mav_put_float_array(buf, 36, covariance, 36);
  266. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  267. #else
  268. mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf;
  269. packet->time_usec = time_usec;
  270. packet->lat = lat;
  271. packet->lon = lon;
  272. packet->alt = alt;
  273. packet->relative_alt = relative_alt;
  274. packet->vx = vx;
  275. packet->vy = vy;
  276. packet->vz = vz;
  277. packet->estimator_type = estimator_type;
  278. mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
  279. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
  280. #endif
  281. }
  282. #endif
  283. #endif
  284. // MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
  285. /**
  286. * @brief Get field time_usec from global_position_int_cov message
  287. *
  288. * @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.
  289. */
  290. static inline uint64_t mavlink_msg_global_position_int_cov_get_time_usec(const mavlink_message_t* msg)
  291. {
  292. return _MAV_RETURN_uint64_t(msg, 0);
  293. }
  294. /**
  295. * @brief Get field estimator_type from global_position_int_cov message
  296. *
  297. * @return Class id of the estimator this estimate originated from.
  298. */
  299. static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg)
  300. {
  301. return _MAV_RETURN_uint8_t(msg, 180);
  302. }
  303. /**
  304. * @brief Get field lat from global_position_int_cov message
  305. *
  306. * @return [degE7] Latitude
  307. */
  308. static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
  309. {
  310. return _MAV_RETURN_int32_t(msg, 8);
  311. }
  312. /**
  313. * @brief Get field lon from global_position_int_cov message
  314. *
  315. * @return [degE7] Longitude
  316. */
  317. static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
  318. {
  319. return _MAV_RETURN_int32_t(msg, 12);
  320. }
  321. /**
  322. * @brief Get field alt from global_position_int_cov message
  323. *
  324. * @return [mm] Altitude in meters above MSL
  325. */
  326. static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
  327. {
  328. return _MAV_RETURN_int32_t(msg, 16);
  329. }
  330. /**
  331. * @brief Get field relative_alt from global_position_int_cov message
  332. *
  333. * @return [mm] Altitude above ground
  334. */
  335. static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
  336. {
  337. return _MAV_RETURN_int32_t(msg, 20);
  338. }
  339. /**
  340. * @brief Get field vx from global_position_int_cov message
  341. *
  342. * @return [m/s] Ground X Speed (Latitude)
  343. */
  344. static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
  345. {
  346. return _MAV_RETURN_float(msg, 24);
  347. }
  348. /**
  349. * @brief Get field vy from global_position_int_cov message
  350. *
  351. * @return [m/s] Ground Y Speed (Longitude)
  352. */
  353. static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
  354. {
  355. return _MAV_RETURN_float(msg, 28);
  356. }
  357. /**
  358. * @brief Get field vz from global_position_int_cov message
  359. *
  360. * @return [m/s] Ground Z Speed (Altitude)
  361. */
  362. static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
  363. {
  364. return _MAV_RETURN_float(msg, 32);
  365. }
  366. /**
  367. * @brief Get field covariance from global_position_int_cov message
  368. *
  369. * @return Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array.
  370. */
  371. static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
  372. {
  373. return _MAV_RETURN_float_array(msg, covariance, 36, 36);
  374. }
  375. /**
  376. * @brief Decode a global_position_int_cov message into a struct
  377. *
  378. * @param msg The message to decode
  379. * @param global_position_int_cov C-struct to decode the message contents into
  380. */
  381. static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov)
  382. {
  383. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  384. global_position_int_cov->time_usec = mavlink_msg_global_position_int_cov_get_time_usec(msg);
  385. global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg);
  386. global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg);
  387. global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg);
  388. global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg);
  389. global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg);
  390. global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg);
  391. global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg);
  392. mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance);
  393. global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg);
  394. #else
  395. uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN;
  396. memset(global_position_int_cov, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
  397. memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), len);
  398. #endif
  399. }