mavlink_msg_global_position_int.h 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484
  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
  103. * @param system_id ID of this system
  104. * @param component_id ID of this component (e.g. 200 for IMU)
  105. * @param status MAVLink status structure
  106. * @param msg The MAVLink message to compress the data into
  107. *
  108. * @param time_boot_ms [ms] Timestamp (time since system boot).
  109. * @param lat [degE7] Latitude, expressed
  110. * @param lon [degE7] Longitude, expressed
  111. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  112. * @param relative_alt [mm] Altitude above ground
  113. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  114. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  115. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  116. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  117. * @return length of the message in bytes (excluding serial stream start sign)
  118. */
  119. static inline uint16_t mavlink_msg_global_position_int_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  149. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
  150. #else
  151. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  152. #endif
  153. }
  154. /**
  155. * @brief Pack a global_position_int message on a channel
  156. * @param system_id ID of this system
  157. * @param component_id ID of this component (e.g. 200 for IMU)
  158. * @param chan The MAVLink channel this message will be sent over
  159. * @param msg The MAVLink message to compress the data into
  160. * @param time_boot_ms [ms] Timestamp (time since system boot).
  161. * @param lat [degE7] Latitude, expressed
  162. * @param lon [degE7] Longitude, expressed
  163. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  164. * @param relative_alt [mm] Altitude above ground
  165. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  166. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  167. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  168. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  169. * @return length of the message in bytes (excluding serial stream start sign)
  170. */
  171. static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  172. mavlink_message_t* msg,
  173. 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)
  174. {
  175. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  176. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
  177. _mav_put_uint32_t(buf, 0, time_boot_ms);
  178. _mav_put_int32_t(buf, 4, lat);
  179. _mav_put_int32_t(buf, 8, lon);
  180. _mav_put_int32_t(buf, 12, alt);
  181. _mav_put_int32_t(buf, 16, relative_alt);
  182. _mav_put_int16_t(buf, 20, vx);
  183. _mav_put_int16_t(buf, 22, vy);
  184. _mav_put_int16_t(buf, 24, vz);
  185. _mav_put_uint16_t(buf, 26, hdg);
  186. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  187. #else
  188. mavlink_global_position_int_t packet;
  189. packet.time_boot_ms = time_boot_ms;
  190. packet.lat = lat;
  191. packet.lon = lon;
  192. packet.alt = alt;
  193. packet.relative_alt = relative_alt;
  194. packet.vx = vx;
  195. packet.vy = vy;
  196. packet.vz = vz;
  197. packet.hdg = hdg;
  198. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  199. #endif
  200. msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
  201. 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);
  202. }
  203. /**
  204. * @brief Encode a global_position_int struct
  205. *
  206. * @param system_id ID of this system
  207. * @param component_id ID of this component (e.g. 200 for IMU)
  208. * @param msg The MAVLink message to compress the data into
  209. * @param global_position_int C-struct to read the message contents from
  210. */
  211. 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)
  212. {
  213. 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);
  214. }
  215. /**
  216. * @brief Encode a global_position_int struct on a channel
  217. *
  218. * @param system_id ID of this system
  219. * @param component_id ID of this component (e.g. 200 for IMU)
  220. * @param chan The MAVLink channel this message will be sent over
  221. * @param msg The MAVLink message to compress the data into
  222. * @param global_position_int C-struct to read the message contents from
  223. */
  224. 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)
  225. {
  226. 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);
  227. }
  228. /**
  229. * @brief Encode a global_position_int struct with provided status structure
  230. *
  231. * @param system_id ID of this system
  232. * @param component_id ID of this component (e.g. 200 for IMU)
  233. * @param status MAVLink status structure
  234. * @param msg The MAVLink message to compress the data into
  235. * @param global_position_int C-struct to read the message contents from
  236. */
  237. static inline uint16_t mavlink_msg_global_position_int_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
  238. {
  239. return mavlink_msg_global_position_int_pack_status(system_id, component_id, _status, 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);
  240. }
  241. /**
  242. * @brief Send a global_position_int message
  243. * @param chan MAVLink channel to send the message
  244. *
  245. * @param time_boot_ms [ms] Timestamp (time since system boot).
  246. * @param lat [degE7] Latitude, expressed
  247. * @param lon [degE7] Longitude, expressed
  248. * @param alt [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  249. * @param relative_alt [mm] Altitude above ground
  250. * @param vx [cm/s] Ground X Speed (Latitude, positive north)
  251. * @param vy [cm/s] Ground Y Speed (Longitude, positive east)
  252. * @param vz [cm/s] Ground Z Speed (Altitude, positive down)
  253. * @param hdg [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  254. */
  255. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  256. 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)
  257. {
  258. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  259. char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
  260. _mav_put_uint32_t(buf, 0, time_boot_ms);
  261. _mav_put_int32_t(buf, 4, lat);
  262. _mav_put_int32_t(buf, 8, lon);
  263. _mav_put_int32_t(buf, 12, alt);
  264. _mav_put_int32_t(buf, 16, relative_alt);
  265. _mav_put_int16_t(buf, 20, vx);
  266. _mav_put_int16_t(buf, 22, vy);
  267. _mav_put_int16_t(buf, 24, vz);
  268. _mav_put_uint16_t(buf, 26, hdg);
  269. _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);
  270. #else
  271. mavlink_global_position_int_t packet;
  272. packet.time_boot_ms = time_boot_ms;
  273. packet.lat = lat;
  274. packet.lon = lon;
  275. packet.alt = alt;
  276. packet.relative_alt = relative_alt;
  277. packet.vx = vx;
  278. packet.vy = vy;
  279. packet.vz = vz;
  280. packet.hdg = hdg;
  281. _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);
  282. #endif
  283. }
  284. /**
  285. * @brief Send a global_position_int message
  286. * @param chan MAVLink channel to send the message
  287. * @param struct The MAVLink struct to serialize
  288. */
  289. static inline void mavlink_msg_global_position_int_send_struct(mavlink_channel_t chan, const mavlink_global_position_int_t* global_position_int)
  290. {
  291. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  292. 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);
  293. #else
  294. _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);
  295. #endif
  296. }
  297. #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  298. /*
  299. This variant of _send() can be used to save stack space by re-using
  300. memory from the receive buffer. The caller provides a
  301. mavlink_message_t which is the size of a full mavlink message. This
  302. is usually the receive buffer for the channel, and allows a reply to an
  303. incoming message with minimum stack space usage.
  304. */
  305. 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)
  306. {
  307. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  308. char *buf = (char *)msgbuf;
  309. _mav_put_uint32_t(buf, 0, time_boot_ms);
  310. _mav_put_int32_t(buf, 4, lat);
  311. _mav_put_int32_t(buf, 8, lon);
  312. _mav_put_int32_t(buf, 12, alt);
  313. _mav_put_int32_t(buf, 16, relative_alt);
  314. _mav_put_int16_t(buf, 20, vx);
  315. _mav_put_int16_t(buf, 22, vy);
  316. _mav_put_int16_t(buf, 24, vz);
  317. _mav_put_uint16_t(buf, 26, hdg);
  318. _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);
  319. #else
  320. mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf;
  321. packet->time_boot_ms = time_boot_ms;
  322. packet->lat = lat;
  323. packet->lon = lon;
  324. packet->alt = alt;
  325. packet->relative_alt = relative_alt;
  326. packet->vx = vx;
  327. packet->vy = vy;
  328. packet->vz = vz;
  329. packet->hdg = hdg;
  330. _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);
  331. #endif
  332. }
  333. #endif
  334. #endif
  335. // MESSAGE GLOBAL_POSITION_INT UNPACKING
  336. /**
  337. * @brief Get field time_boot_ms from global_position_int message
  338. *
  339. * @return [ms] Timestamp (time since system boot).
  340. */
  341. static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
  342. {
  343. return _MAV_RETURN_uint32_t(msg, 0);
  344. }
  345. /**
  346. * @brief Get field lat from global_position_int message
  347. *
  348. * @return [degE7] Latitude, expressed
  349. */
  350. static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
  351. {
  352. return _MAV_RETURN_int32_t(msg, 4);
  353. }
  354. /**
  355. * @brief Get field lon from global_position_int message
  356. *
  357. * @return [degE7] Longitude, expressed
  358. */
  359. static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
  360. {
  361. return _MAV_RETURN_int32_t(msg, 8);
  362. }
  363. /**
  364. * @brief Get field alt from global_position_int message
  365. *
  366. * @return [mm] Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.
  367. */
  368. static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
  369. {
  370. return _MAV_RETURN_int32_t(msg, 12);
  371. }
  372. /**
  373. * @brief Get field relative_alt from global_position_int message
  374. *
  375. * @return [mm] Altitude above ground
  376. */
  377. static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
  378. {
  379. return _MAV_RETURN_int32_t(msg, 16);
  380. }
  381. /**
  382. * @brief Get field vx from global_position_int message
  383. *
  384. * @return [cm/s] Ground X Speed (Latitude, positive north)
  385. */
  386. static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
  387. {
  388. return _MAV_RETURN_int16_t(msg, 20);
  389. }
  390. /**
  391. * @brief Get field vy from global_position_int message
  392. *
  393. * @return [cm/s] Ground Y Speed (Longitude, positive east)
  394. */
  395. static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
  396. {
  397. return _MAV_RETURN_int16_t(msg, 22);
  398. }
  399. /**
  400. * @brief Get field vz from global_position_int message
  401. *
  402. * @return [cm/s] Ground Z Speed (Altitude, positive down)
  403. */
  404. static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
  405. {
  406. return _MAV_RETURN_int16_t(msg, 24);
  407. }
  408. /**
  409. * @brief Get field hdg from global_position_int message
  410. *
  411. * @return [cdeg] Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  412. */
  413. static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
  414. {
  415. return _MAV_RETURN_uint16_t(msg, 26);
  416. }
  417. /**
  418. * @brief Decode a global_position_int message into a struct
  419. *
  420. * @param msg The message to decode
  421. * @param global_position_int C-struct to decode the message contents into
  422. */
  423. static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
  424. {
  425. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  426. global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
  427. global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
  428. global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
  429. global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
  430. global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg);
  431. global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
  432. global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
  433. global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
  434. global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
  435. #else
  436. uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN;
  437. memset(global_position_int, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
  438. memcpy(global_position_int, _MAV_PAYLOAD(msg), len);
  439. #endif
  440. }