mavlink_msg_global_position_int.h 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413
  1. #pragma once
  2. // MESSAGE GLOBAL_POSITION_INT PACKING
  3. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
  4. typedef struct __mavlink_global_position_int_t {
  5. uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
  6. int32_t lat; /*< [degE7] Latitude, expressed*/
  7. int32_t lon; /*< [degE7] Longitude, expressed*/
  8. int32_t alt; /*< [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.*/
  9. int32_t relative_alt; /*< [mm] Altitude above ground*/
  10. int16_t vx; /*< [cm/s] Ground X Speed (Latitude, positive north)*/
  11. int16_t vy; /*< [cm/s] Ground Y Speed (Longitude, positive east)*/
  12. int16_t vz; /*< [cm/s] Ground Z Speed (Altitude, positive down)*/
  13. uint16_t hdg; /*< [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
  14. } mavlink_global_position_int_t;
  15. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
  16. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN 28
  17. #define MAVLINK_MSG_ID_33_LEN 28
  18. #define MAVLINK_MSG_ID_33_MIN_LEN 28
  19. #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
  20. #define MAVLINK_MSG_ID_33_CRC 104
  21. #if MAVLINK_COMMAND_24BIT
  22. #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
  23. 33, \
  24. "GLOBAL_POSITION_INT", \
  25. 9, \
  26. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
  27. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
  28. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
  29. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
  30. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
  31. { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
  32. { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
  33. { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
  34. { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
  35. } \
  36. }
  37. #else
  38. #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
  39. "GLOBAL_POSITION_INT", \
  40. 9, \
  41. { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
  42. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
  43. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
  44. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
  45. { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
  46. { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
  47. { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
  48. { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
  49. { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
  50. } \
  51. }
  52. #endif
  53. /**
  54. * @brief Pack a global_position_int message
  55. * @param system_id ID of this system
  56. * @param component_id ID of this component (e.g. 200 for IMU)
  57. * @param msg The MAVLink message to compress the data into
  58. *
  59. * @param time_boot_ms [ms] Timestamp (time since system boot).
  60. * @param lat [degE7] Latitude, expressed
  61. * @param lon [degE7] Longitude, expressed
  62. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  63. * @param relative_alt [mm] Altitude above ground
  64. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  65. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  66. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  67. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  68. * @return length of the message in bytes (excluding serial stream start sign)
  69. */
  70. static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  71. uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
  72. {
  73. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  74. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
  75. _mav_put_uint32_t(buf, 0, time_boot_ms);
  76. _mav_put_int32_t(buf, 4, lat);
  77. _mav_put_int32_t(buf, 8, lon);
  78. _mav_put_int32_t(buf, 12, alt);
  79. _mav_put_int32_t(buf, 16, relative_alt);
  80. _mav_put_int16_t(buf, 20, vx);
  81. _mav_put_int16_t(buf, 22, vy);
  82. _mav_put_int16_t(buf, 24, vz);
  83. _mav_put_uint16_t(buf, 26, hdg);
  84. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  85. #else
  86. mavlink_global_position_int_t packet;
  87. packet.time_boot_ms = time_boot_ms;
  88. packet.lat = lat;
  89. packet.lon = lon;
  90. packet.alt = alt;
  91. packet.relative_alt = relative_alt;
  92. packet.vx = vx;
  93. packet.vy = vy;
  94. packet.vz = vz;
  95. packet.hdg = hdg;
  96. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  97. #endif
  98. msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
  99. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  100. }
  101. /**
  102. * @brief Pack a global_position_int message on a channel
  103. * @param system_id ID of this system
  104. * @param component_id ID of this component (e.g. 200 for IMU)
  105. * @param chan The MAVLink channel this message will be sent over
  106. * @param msg The MAVLink message to compress the data into
  107. * @param time_boot_ms [ms] Timestamp (time since system boot).
  108. * @param lat [degE7] Latitude, expressed
  109. * @param lon [degE7] Longitude, expressed
  110. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  111. * @param relative_alt [mm] Altitude above ground
  112. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  113. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  114. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  115. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  116. * @return length of the message in bytes (excluding serial stream start sign)
  117. */
  118. static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  119. mavlink_message_t* msg,
  120. uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
  121. {
  122. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  123. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
  124. _mav_put_uint32_t(buf, 0, time_boot_ms);
  125. _mav_put_int32_t(buf, 4, lat);
  126. _mav_put_int32_t(buf, 8, lon);
  127. _mav_put_int32_t(buf, 12, alt);
  128. _mav_put_int32_t(buf, 16, relative_alt);
  129. _mav_put_int16_t(buf, 20, vx);
  130. _mav_put_int16_t(buf, 22, vy);
  131. _mav_put_int16_t(buf, 24, vz);
  132. _mav_put_uint16_t(buf, 26, hdg);
  133. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  134. #else
  135. mavlink_global_position_int_t packet;
  136. packet.time_boot_ms = time_boot_ms;
  137. packet.lat = lat;
  138. packet.lon = lon;
  139. packet.alt = alt;
  140. packet.relative_alt = relative_alt;
  141. packet.vx = vx;
  142. packet.vy = vy;
  143. packet.vz = vz;
  144. packet.hdg = hdg;
  145. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  146. #endif
  147. msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
  148. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  149. }
  150. /**
  151. * @brief Encode a global_position_int struct
  152. *
  153. * @param system_id ID of this system
  154. * @param component_id ID of this component (e.g. 200 for IMU)
  155. * @param msg The MAVLink message to compress the data into
  156. * @param global_position_int C-struct to read the message contents from
  157. */
  158. static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
  159. {
  160. return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
  161. }
  162. /**
  163. * @brief Encode a global_position_int struct on a channel
  164. *
  165. * @param system_id ID of this system
  166. * @param component_id ID of this component (e.g. 200 for IMU)
  167. * @param chan The MAVLink channel this message will be sent over
  168. * @param msg The MAVLink message to compress the data into
  169. * @param global_position_int C-struct to read the message contents from
  170. */
  171. static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
  172. {
  173. return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
  174. }
  175. /**
  176. * @brief Send a global_position_int message
  177. * @param chan MAVLink channel to send the message
  178. *
  179. * @param time_boot_ms [ms] Timestamp (time since system boot).
  180. * @param lat [degE7] Latitude, expressed
  181. * @param lon [degE7] Longitude, expressed
  182. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  183. * @param relative_alt [mm] Altitude above ground
  184. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  185. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  186. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  187. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  188. */
  189. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  190. static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
  191. {
  192. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  193. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
  194. _mav_put_uint32_t(buf, 0, time_boot_ms);
  195. _mav_put_int32_t(buf, 4, lat);
  196. _mav_put_int32_t(buf, 8, lon);
  197. _mav_put_int32_t(buf, 12, alt);
  198. _mav_put_int32_t(buf, 16, relative_alt);
  199. _mav_put_int16_t(buf, 20, vx);
  200. _mav_put_int16_t(buf, 22, vy);
  201. _mav_put_int16_t(buf, 24, vz);
  202. _mav_put_uint16_t(buf, 26, hdg);
  203. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  204. #else
  205. mavlink_global_position_int_t packet;
  206. packet.time_boot_ms = time_boot_ms;
  207. packet.lat = lat;
  208. packet.lon = lon;
  209. packet.alt = alt;
  210. packet.relative_alt = relative_alt;
  211. packet.vx = vx;
  212. packet.vy = vy;
  213. packet.vz = vz;
  214. packet.hdg = hdg;
  215. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  216. #endif
  217. }
  218. /**
  219. * @brief Send a global_position_int message
  220. * @param chan MAVLink channel to send the message
  221. * @param struct The MAVLink struct to serialize
  222. */
  223. static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_t* global_position_int)
  224. {
  225. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  226. mavlink_msg_global_position_int_send(chan, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
  227. #else
  228. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)global_position_int, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  229. #endif
  230. }
  231. #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  232. /*
  233. This variant of _send() can be used to save stack space by re-using
  234. memory from the receive buffer. The caller provides a
  235. mavlink_message_t which is the size of a full mavlink message. This
  236. is usually the receive buffer for the channel, and allows a reply to an
  237. incoming message with minimum stack space usage.
  238. */
  239. static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
  240. {
  241. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  242. char *buf = (char *)msgbuf;
  243. _mav_put_uint32_t(buf, 0, time_boot_ms);
  244. _mav_put_int32_t(buf, 4, lat);
  245. _mav_put_int32_t(buf, 8, lon);
  246. _mav_put_int32_t(buf, 12, alt);
  247. _mav_put_int32_t(buf, 16, relative_alt);
  248. _mav_put_int16_t(buf, 20, vx);
  249. _mav_put_int16_t(buf, 22, vy);
  250. _mav_put_int16_t(buf, 24, vz);
  251. _mav_put_uint16_t(buf, 26, hdg);
  252. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  253. #else
  254. mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf;
  255. packet->time_boot_ms = time_boot_ms;
  256. packet->lat = lat;
  257. packet->lon = lon;
  258. packet->alt = alt;
  259. packet->relative_alt = relative_alt;
  260. packet->vx = vx;
  261. packet->vy = vy;
  262. packet->vz = vz;
  263. packet->hdg = hdg;
  264. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  265. #endif
  266. }
  267. #endif
  268. #endif
  269. // MESSAGE GLOBAL_POSITION_INT UNPACKING
  270. /**
  271. * @brief Get field time_boot_ms from global_position_int message
  272. *
  273. * @return [ms] Timestamp (time since system boot).
  274. */
  275. static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
  276. {
  277. return _MAV_RETURN_uint32_t(msg, 0);
  278. }
  279. /**
  280. * @brief Get field lat from global_position_int message
  281. *
  282. * @return [degE7] Latitude, expressed
  283. */
  284. static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
  285. {
  286. return _MAV_RETURN_int32_t(msg, 4);
  287. }
  288. /**
  289. * @brief Get field lon from global_position_int message
  290. *
  291. * @return [degE7] Longitude, expressed
  292. */
  293. static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
  294. {
  295. return _MAV_RETURN_int32_t(msg, 8);
  296. }
  297. /**
  298. * @brief Get field alt from global_position_int message
  299. *
  300. * @return [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  301. */
  302. static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
  303. {
  304. return _MAV_RETURN_int32_t(msg, 12);
  305. }
  306. /**
  307. * @brief Get field relative_alt from global_position_int message
  308. *
  309. * @return [mm] Altitude above ground
  310. */
  311. static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
  312. {
  313. return _MAV_RETURN_int32_t(msg, 16);
  314. }
  315. /**
  316. * @brief Get field vx from global_position_int message
  317. *
  318. * @return [cm/s] Ground X Speed (Latitude, positive north)
  319. */
  320. static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
  321. {
  322. return _MAV_RETURN_int16_t(msg, 20);
  323. }
  324. /**
  325. * @brief Get field vy from global_position_int message
  326. *
  327. * @return [cm/s] Ground Y Speed (Longitude, positive east)
  328. */
  329. static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
  330. {
  331. return _MAV_RETURN_int16_t(msg, 22);
  332. }
  333. /**
  334. * @brief Get field vz from global_position_int message
  335. *
  336. * @return [cm/s] Ground Z Speed (Altitude, positive down)
  337. */
  338. static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
  339. {
  340. return _MAV_RETURN_int16_t(msg, 24);
  341. }
  342. /**
  343. * @brief Get field hdg from global_position_int message
  344. *
  345. * @return [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  346. */
  347. static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
  348. {
  349. return _MAV_RETURN_uint16_t(msg, 26);
  350. }
  351. /**
  352. * @brief Decode a global_position_int message into a struct
  353. *
  354. * @param msg The message to decode
  355. * @param global_position_int C-struct to decode the message contents into
  356. */
  357. static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
  358. {
  359. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  360. global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
  361. global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
  362. global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
  363. global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
  364. global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg);
  365. global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
  366. global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
  367. global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
  368. global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
  369. #else
  370. uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN;
  371. memset(global_position_int, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  372. memcpy(global_position_int, _MAV_PAYLOAD(msg), len);
  373. #endif
  374. }