mavlink_msg_gps_raw_int.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588
  1. #pragma once
  2. // MESSAGE GPS_RAW_INT PACKING
  3. #define MAVLINK_MSG_ID_GPS_RAW_INT 24
  4. MAVPACKED(
  5. typedef struct __mavlink_gps_raw_int_t {
  6. 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.*/
  7. int32_t lat; /*< [degE7] Latitude (WGS84, EGM96 ellipsoid)*/
  8. int32_t lon; /*< [degE7] Longitude (WGS84, EGM96 ellipsoid)*/
  9. int32_t alt; /*< [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.*/
  10. uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/
  11. uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/
  12. uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
  13. uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
  14. uint8_t fix_type; /*< GPS fix type.*/
  15. uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/
  16. int32_t alt_ellipsoid; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/
  17. uint32_t h_acc; /*< [mm] Position uncertainty.*/
  18. uint32_t v_acc; /*< [mm] Altitude uncertainty.*/
  19. uint32_t vel_acc; /*< [mm] Speed uncertainty.*/
  20. uint32_t hdg_acc; /*< [degE5] Heading / track uncertainty*/
  21. uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/
  22. }) mavlink_gps_raw_int_t;
  23. #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 52
  24. #define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
  25. #define MAVLINK_MSG_ID_24_LEN 52
  26. #define MAVLINK_MSG_ID_24_MIN_LEN 30
  27. #define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
  28. #define MAVLINK_MSG_ID_24_CRC 24
  29. #if MAVLINK_COMMAND_24BIT
  30. #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
  31. 24, \
  32. "GPS_RAW_INT", \
  33. 16, \
  34. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
  35. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
  36. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
  37. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
  38. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
  39. { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
  40. { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
  41. { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
  42. { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
  43. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
  44. { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
  45. { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
  46. { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
  47. { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
  48. { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
  49. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
  50. } \
  51. }
  52. #else
  53. #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
  54. "GPS_RAW_INT", \
  55. 16, \
  56. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
  57. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
  58. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
  59. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
  60. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
  61. { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
  62. { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
  63. { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
  64. { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
  65. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
  66. { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
  67. { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
  68. { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
  69. { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
  70. { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
  71. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
  72. } \
  73. }
  74. #endif
  75. /**
  76. * @brief Pack a gps_raw_int message
  77. * @param system_id ID of this system
  78. * @param component_id ID of this component (e.g. 200 for IMU)
  79. * @param msg The MAVLink message to compress the data into
  80. *
  81. * @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.
  82. * @param fix_type GPS fix type.
  83. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  84. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  85. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  86. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  87. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  88. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  89. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  90. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  91. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  92. * @param h_acc [mm] Position uncertainty.
  93. * @param v_acc [mm] Altitude uncertainty.
  94. * @param vel_acc [mm] Speed uncertainty.
  95. * @param hdg_acc [degE5] Heading / track uncertainty
  96. * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
  97. * @return length of the message in bytes (excluding serial stream start sign)
  98. */
  99. static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  100. uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
  101. {
  102. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  103. char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
  104. _mav_put_uint64_t(buf, 0, time_usec);
  105. _mav_put_int32_t(buf, 8, lat);
  106. _mav_put_int32_t(buf, 12, lon);
  107. _mav_put_int32_t(buf, 16, alt);
  108. _mav_put_uint16_t(buf, 20, eph);
  109. _mav_put_uint16_t(buf, 22, epv);
  110. _mav_put_uint16_t(buf, 24, vel);
  111. _mav_put_uint16_t(buf, 26, cog);
  112. _mav_put_uint8_t(buf, 28, fix_type);
  113. _mav_put_uint8_t(buf, 29, satellites_visible);
  114. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  115. _mav_put_uint32_t(buf, 34, h_acc);
  116. _mav_put_uint32_t(buf, 38, v_acc);
  117. _mav_put_uint32_t(buf, 42, vel_acc);
  118. _mav_put_uint32_t(buf, 46, hdg_acc);
  119. _mav_put_uint16_t(buf, 50, yaw);
  120. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  121. #else
  122. mavlink_gps_raw_int_t packet;
  123. packet.time_usec = time_usec;
  124. packet.lat = lat;
  125. packet.lon = lon;
  126. packet.alt = alt;
  127. packet.eph = eph;
  128. packet.epv = epv;
  129. packet.vel = vel;
  130. packet.cog = cog;
  131. packet.fix_type = fix_type;
  132. packet.satellites_visible = satellites_visible;
  133. packet.alt_ellipsoid = alt_ellipsoid;
  134. packet.h_acc = h_acc;
  135. packet.v_acc = v_acc;
  136. packet.vel_acc = vel_acc;
  137. packet.hdg_acc = hdg_acc;
  138. packet.yaw = yaw;
  139. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  140. #endif
  141. msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
  142. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  143. }
  144. /**
  145. * @brief Pack a gps_raw_int message on a channel
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param chan The MAVLink channel this message will be sent over
  149. * @param msg The MAVLink message to compress the data into
  150. * @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.
  151. * @param fix_type GPS fix type.
  152. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  153. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  154. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  155. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  156. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  157. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  158. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  159. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  160. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  161. * @param h_acc [mm] Position uncertainty.
  162. * @param v_acc [mm] Altitude uncertainty.
  163. * @param vel_acc [mm] Speed uncertainty.
  164. * @param hdg_acc [degE5] Heading / track uncertainty
  165. * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
  166. * @return length of the message in bytes (excluding serial stream start sign)
  167. */
  168. static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  169. mavlink_message_t* msg,
  170. uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc,uint16_t yaw)
  171. {
  172. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  173. char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
  174. _mav_put_uint64_t(buf, 0, time_usec);
  175. _mav_put_int32_t(buf, 8, lat);
  176. _mav_put_int32_t(buf, 12, lon);
  177. _mav_put_int32_t(buf, 16, alt);
  178. _mav_put_uint16_t(buf, 20, eph);
  179. _mav_put_uint16_t(buf, 22, epv);
  180. _mav_put_uint16_t(buf, 24, vel);
  181. _mav_put_uint16_t(buf, 26, cog);
  182. _mav_put_uint8_t(buf, 28, fix_type);
  183. _mav_put_uint8_t(buf, 29, satellites_visible);
  184. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  185. _mav_put_uint32_t(buf, 34, h_acc);
  186. _mav_put_uint32_t(buf, 38, v_acc);
  187. _mav_put_uint32_t(buf, 42, vel_acc);
  188. _mav_put_uint32_t(buf, 46, hdg_acc);
  189. _mav_put_uint16_t(buf, 50, yaw);
  190. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  191. #else
  192. mavlink_gps_raw_int_t packet;
  193. packet.time_usec = time_usec;
  194. packet.lat = lat;
  195. packet.lon = lon;
  196. packet.alt = alt;
  197. packet.eph = eph;
  198. packet.epv = epv;
  199. packet.vel = vel;
  200. packet.cog = cog;
  201. packet.fix_type = fix_type;
  202. packet.satellites_visible = satellites_visible;
  203. packet.alt_ellipsoid = alt_ellipsoid;
  204. packet.h_acc = h_acc;
  205. packet.v_acc = v_acc;
  206. packet.vel_acc = vel_acc;
  207. packet.hdg_acc = hdg_acc;
  208. packet.yaw = yaw;
  209. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  210. #endif
  211. msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
  212. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  213. }
  214. /**
  215. * @brief Encode a gps_raw_int struct
  216. *
  217. * @param system_id ID of this system
  218. * @param component_id ID of this component (e.g. 200 for IMU)
  219. * @param msg The MAVLink message to compress the data into
  220. * @param gps_raw_int C-struct to read the message contents from
  221. */
  222. static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
  223. {
  224. return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
  225. }
  226. /**
  227. * @brief Encode a gps_raw_int struct on a channel
  228. *
  229. * @param system_id ID of this system
  230. * @param component_id ID of this component (e.g. 200 for IMU)
  231. * @param chan The MAVLink channel this message will be sent over
  232. * @param msg The MAVLink message to compress the data into
  233. * @param gps_raw_int C-struct to read the message contents from
  234. */
  235. static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
  236. {
  237. return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
  238. }
  239. /**
  240. * @brief Send a gps_raw_int message
  241. * @param chan MAVLink channel to send the message
  242. *
  243. * @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.
  244. * @param fix_type GPS fix type.
  245. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  246. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  247. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  248. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  249. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  250. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  251. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  252. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  253. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  254. * @param h_acc [mm] Position uncertainty.
  255. * @param v_acc [mm] Altitude uncertainty.
  256. * @param vel_acc [mm] Speed uncertainty.
  257. * @param hdg_acc [degE5] Heading / track uncertainty
  258. * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
  259. */
  260. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  261. static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
  262. {
  263. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  264. char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
  265. _mav_put_uint64_t(buf, 0, time_usec);
  266. _mav_put_int32_t(buf, 8, lat);
  267. _mav_put_int32_t(buf, 12, lon);
  268. _mav_put_int32_t(buf, 16, alt);
  269. _mav_put_uint16_t(buf, 20, eph);
  270. _mav_put_uint16_t(buf, 22, epv);
  271. _mav_put_uint16_t(buf, 24, vel);
  272. _mav_put_uint16_t(buf, 26, cog);
  273. _mav_put_uint8_t(buf, 28, fix_type);
  274. _mav_put_uint8_t(buf, 29, satellites_visible);
  275. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  276. _mav_put_uint32_t(buf, 34, h_acc);
  277. _mav_put_uint32_t(buf, 38, v_acc);
  278. _mav_put_uint32_t(buf, 42, vel_acc);
  279. _mav_put_uint32_t(buf, 46, hdg_acc);
  280. _mav_put_uint16_t(buf, 50, yaw);
  281. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  282. #else
  283. mavlink_gps_raw_int_t packet;
  284. packet.time_usec = time_usec;
  285. packet.lat = lat;
  286. packet.lon = lon;
  287. packet.alt = alt;
  288. packet.eph = eph;
  289. packet.epv = epv;
  290. packet.vel = vel;
  291. packet.cog = cog;
  292. packet.fix_type = fix_type;
  293. packet.satellites_visible = satellites_visible;
  294. packet.alt_ellipsoid = alt_ellipsoid;
  295. packet.h_acc = h_acc;
  296. packet.v_acc = v_acc;
  297. packet.vel_acc = vel_acc;
  298. packet.hdg_acc = hdg_acc;
  299. packet.yaw = yaw;
  300. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  301. #endif
  302. }
  303. /**
  304. * @brief Send a gps_raw_int message
  305. * @param chan MAVLink channel to send the message
  306. * @param struct The MAVLink struct to serialize
  307. */
  308. static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int)
  309. {
  310. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  311. mavlink_msg_gps_raw_int_send(chan, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
  312. #else
  313. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  314. #endif
  315. }
  316. #if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  317. /*
  318. This variant of _send() can be used to save stack space by re-using
  319. memory from the receive buffer. The caller provides a
  320. mavlink_message_t which is the size of a full mavlink message. This
  321. is usually the receive buffer for the channel, and allows a reply to an
  322. incoming message with minimum stack space usage.
  323. */
  324. static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
  325. {
  326. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  327. char *buf = (char *)msgbuf;
  328. _mav_put_uint64_t(buf, 0, time_usec);
  329. _mav_put_int32_t(buf, 8, lat);
  330. _mav_put_int32_t(buf, 12, lon);
  331. _mav_put_int32_t(buf, 16, alt);
  332. _mav_put_uint16_t(buf, 20, eph);
  333. _mav_put_uint16_t(buf, 22, epv);
  334. _mav_put_uint16_t(buf, 24, vel);
  335. _mav_put_uint16_t(buf, 26, cog);
  336. _mav_put_uint8_t(buf, 28, fix_type);
  337. _mav_put_uint8_t(buf, 29, satellites_visible);
  338. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  339. _mav_put_uint32_t(buf, 34, h_acc);
  340. _mav_put_uint32_t(buf, 38, v_acc);
  341. _mav_put_uint32_t(buf, 42, vel_acc);
  342. _mav_put_uint32_t(buf, 46, hdg_acc);
  343. _mav_put_uint16_t(buf, 50, yaw);
  344. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  345. #else
  346. mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf;
  347. packet->time_usec = time_usec;
  348. packet->lat = lat;
  349. packet->lon = lon;
  350. packet->alt = alt;
  351. packet->eph = eph;
  352. packet->epv = epv;
  353. packet->vel = vel;
  354. packet->cog = cog;
  355. packet->fix_type = fix_type;
  356. packet->satellites_visible = satellites_visible;
  357. packet->alt_ellipsoid = alt_ellipsoid;
  358. packet->h_acc = h_acc;
  359. packet->v_acc = v_acc;
  360. packet->vel_acc = vel_acc;
  361. packet->hdg_acc = hdg_acc;
  362. packet->yaw = yaw;
  363. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  364. #endif
  365. }
  366. #endif
  367. #endif
  368. // MESSAGE GPS_RAW_INT UNPACKING
  369. /**
  370. * @brief Get field time_usec from gps_raw_int message
  371. *
  372. * @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.
  373. */
  374. static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
  375. {
  376. return _MAV_RETURN_uint64_t(msg, 0);
  377. }
  378. /**
  379. * @brief Get field fix_type from gps_raw_int message
  380. *
  381. * @return GPS fix type.
  382. */
  383. static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
  384. {
  385. return _MAV_RETURN_uint8_t(msg, 28);
  386. }
  387. /**
  388. * @brief Get field lat from gps_raw_int message
  389. *
  390. * @return [degE7] Latitude (WGS84, EGM96 ellipsoid)
  391. */
  392. static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
  393. {
  394. return _MAV_RETURN_int32_t(msg, 8);
  395. }
  396. /**
  397. * @brief Get field lon from gps_raw_int message
  398. *
  399. * @return [degE7] Longitude (WGS84, EGM96 ellipsoid)
  400. */
  401. static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
  402. {
  403. return _MAV_RETURN_int32_t(msg, 12);
  404. }
  405. /**
  406. * @brief Get field alt from gps_raw_int message
  407. *
  408. * @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  409. */
  410. static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
  411. {
  412. return _MAV_RETURN_int32_t(msg, 16);
  413. }
  414. /**
  415. * @brief Get field eph from gps_raw_int message
  416. *
  417. * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  418. */
  419. static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
  420. {
  421. return _MAV_RETURN_uint16_t(msg, 20);
  422. }
  423. /**
  424. * @brief Get field epv from gps_raw_int message
  425. *
  426. * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  427. */
  428. static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
  429. {
  430. return _MAV_RETURN_uint16_t(msg, 22);
  431. }
  432. /**
  433. * @brief Get field vel from gps_raw_int message
  434. *
  435. * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  436. */
  437. static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
  438. {
  439. return _MAV_RETURN_uint16_t(msg, 24);
  440. }
  441. /**
  442. * @brief Get field cog from gps_raw_int message
  443. *
  444. * @return [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  445. */
  446. static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
  447. {
  448. return _MAV_RETURN_uint16_t(msg, 26);
  449. }
  450. /**
  451. * @brief Get field satellites_visible from gps_raw_int message
  452. *
  453. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  454. */
  455. static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
  456. {
  457. return _MAV_RETURN_uint8_t(msg, 29);
  458. }
  459. /**
  460. * @brief Get field alt_ellipsoid from gps_raw_int message
  461. *
  462. * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  463. */
  464. static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t* msg)
  465. {
  466. return _MAV_RETURN_int32_t(msg, 30);
  467. }
  468. /**
  469. * @brief Get field h_acc from gps_raw_int message
  470. *
  471. * @return [mm] Position uncertainty.
  472. */
  473. static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t* msg)
  474. {
  475. return _MAV_RETURN_uint32_t(msg, 34);
  476. }
  477. /**
  478. * @brief Get field v_acc from gps_raw_int message
  479. *
  480. * @return [mm] Altitude uncertainty.
  481. */
  482. static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t* msg)
  483. {
  484. return _MAV_RETURN_uint32_t(msg, 38);
  485. }
  486. /**
  487. * @brief Get field vel_acc from gps_raw_int message
  488. *
  489. * @return [mm] Speed uncertainty.
  490. */
  491. static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t* msg)
  492. {
  493. return _MAV_RETURN_uint32_t(msg, 42);
  494. }
  495. /**
  496. * @brief Get field hdg_acc from gps_raw_int message
  497. *
  498. * @return [degE5] Heading / track uncertainty
  499. */
  500. static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t* msg)
  501. {
  502. return _MAV_RETURN_uint32_t(msg, 46);
  503. }
  504. /**
  505. * @brief Get field yaw from gps_raw_int message
  506. *
  507. * @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
  508. */
  509. static inline uint16_t mavlink_msg_gps_raw_int_get_yaw(const mavlink_message_t* msg)
  510. {
  511. return _MAV_RETURN_uint16_t(msg, 50);
  512. }
  513. /**
  514. * @brief Decode a gps_raw_int message into a struct
  515. *
  516. * @param msg The message to decode
  517. * @param gps_raw_int C-struct to decode the message contents into
  518. */
  519. static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
  520. {
  521. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  522. gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg);
  523. gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
  524. gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
  525. gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
  526. gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
  527. gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
  528. gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg);
  529. gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
  530. gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
  531. gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
  532. gps_raw_int->alt_ellipsoid = mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg);
  533. gps_raw_int->h_acc = mavlink_msg_gps_raw_int_get_h_acc(msg);
  534. gps_raw_int->v_acc = mavlink_msg_gps_raw_int_get_v_acc(msg);
  535. gps_raw_int->vel_acc = mavlink_msg_gps_raw_int_get_vel_acc(msg);
  536. gps_raw_int->hdg_acc = mavlink_msg_gps_raw_int_get_hdg_acc(msg);
  537. gps_raw_int->yaw = mavlink_msg_gps_raw_int_get_yaw(msg);
  538. #else
  539. uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
  540. memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  541. memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len);
  542. #endif
  543. }