mavlink_msg_gps_raw_int.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680
  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
  146. * @param system_id ID of this system
  147. * @param component_id ID of this component (e.g. 200 for IMU)
  148. * @param status MAVLink status structure
  149. * @param msg The MAVLink message to compress the data into
  150. *
  151. * @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.
  152. * @param fix_type GPS fix type.
  153. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  154. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  155. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  156. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  157. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  158. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  159. * @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
  160. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  161. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  162. * @param h_acc [mm] Position uncertainty.
  163. * @param v_acc [mm] Altitude uncertainty.
  164. * @param vel_acc [mm] Speed uncertainty.
  165. * @param hdg_acc [degE5] Heading / track uncertainty
  166. * @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.
  167. * @return length of the message in bytes (excluding serial stream start sign)
  168. */
  169. static inline uint16_t mavlink_msg_gps_raw_int_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  213. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
  214. #else
  215. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  216. #endif
  217. }
  218. /**
  219. * @brief Pack a gps_raw_int message on a channel
  220. * @param system_id ID of this system
  221. * @param component_id ID of this component (e.g. 200 for IMU)
  222. * @param chan The MAVLink channel this message will be sent over
  223. * @param msg The MAVLink message to compress the data into
  224. * @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.
  225. * @param fix_type GPS fix type.
  226. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  227. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  228. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  229. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  230. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  231. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  232. * @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
  233. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  234. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  235. * @param h_acc [mm] Position uncertainty.
  236. * @param v_acc [mm] Altitude uncertainty.
  237. * @param vel_acc [mm] Speed uncertainty.
  238. * @param hdg_acc [degE5] Heading / track uncertainty
  239. * @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.
  240. * @return length of the message in bytes (excluding serial stream start sign)
  241. */
  242. static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  243. mavlink_message_t* msg,
  244. 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)
  245. {
  246. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  247. char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
  248. _mav_put_uint64_t(buf, 0, time_usec);
  249. _mav_put_int32_t(buf, 8, lat);
  250. _mav_put_int32_t(buf, 12, lon);
  251. _mav_put_int32_t(buf, 16, alt);
  252. _mav_put_uint16_t(buf, 20, eph);
  253. _mav_put_uint16_t(buf, 22, epv);
  254. _mav_put_uint16_t(buf, 24, vel);
  255. _mav_put_uint16_t(buf, 26, cog);
  256. _mav_put_uint8_t(buf, 28, fix_type);
  257. _mav_put_uint8_t(buf, 29, satellites_visible);
  258. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  259. _mav_put_uint32_t(buf, 34, h_acc);
  260. _mav_put_uint32_t(buf, 38, v_acc);
  261. _mav_put_uint32_t(buf, 42, vel_acc);
  262. _mav_put_uint32_t(buf, 46, hdg_acc);
  263. _mav_put_uint16_t(buf, 50, yaw);
  264. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  265. #else
  266. mavlink_gps_raw_int_t packet;
  267. packet.time_usec = time_usec;
  268. packet.lat = lat;
  269. packet.lon = lon;
  270. packet.alt = alt;
  271. packet.eph = eph;
  272. packet.epv = epv;
  273. packet.vel = vel;
  274. packet.cog = cog;
  275. packet.fix_type = fix_type;
  276. packet.satellites_visible = satellites_visible;
  277. packet.alt_ellipsoid = alt_ellipsoid;
  278. packet.h_acc = h_acc;
  279. packet.v_acc = v_acc;
  280. packet.vel_acc = vel_acc;
  281. packet.hdg_acc = hdg_acc;
  282. packet.yaw = yaw;
  283. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  284. #endif
  285. msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
  286. 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);
  287. }
  288. /**
  289. * @brief Encode a gps_raw_int struct
  290. *
  291. * @param system_id ID of this system
  292. * @param component_id ID of this component (e.g. 200 for IMU)
  293. * @param msg The MAVLink message to compress the data into
  294. * @param gps_raw_int C-struct to read the message contents from
  295. */
  296. 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)
  297. {
  298. 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);
  299. }
  300. /**
  301. * @brief Encode a gps_raw_int struct on a channel
  302. *
  303. * @param system_id ID of this system
  304. * @param component_id ID of this component (e.g. 200 for IMU)
  305. * @param chan The MAVLink channel this message will be sent over
  306. * @param msg The MAVLink message to compress the data into
  307. * @param gps_raw_int C-struct to read the message contents from
  308. */
  309. 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)
  310. {
  311. 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);
  312. }
  313. /**
  314. * @brief Encode a gps_raw_int struct with provided status structure
  315. *
  316. * @param system_id ID of this system
  317. * @param component_id ID of this component (e.g. 200 for IMU)
  318. * @param status MAVLink status structure
  319. * @param msg The MAVLink message to compress the data into
  320. * @param gps_raw_int C-struct to read the message contents from
  321. */
  322. static inline uint16_t mavlink_msg_gps_raw_int_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
  323. {
  324. return mavlink_msg_gps_raw_int_pack_status(system_id, component_id, _status, 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);
  325. }
  326. /**
  327. * @brief Send a gps_raw_int message
  328. * @param chan MAVLink channel to send the message
  329. *
  330. * @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.
  331. * @param fix_type GPS fix type.
  332. * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
  333. * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
  334. * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  335. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  336. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  337. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  338. * @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
  339. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  340. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  341. * @param h_acc [mm] Position uncertainty.
  342. * @param v_acc [mm] Altitude uncertainty.
  343. * @param vel_acc [mm] Speed uncertainty.
  344. * @param hdg_acc [degE5] Heading / track uncertainty
  345. * @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.
  346. */
  347. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  348. 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)
  349. {
  350. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  351. char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
  352. _mav_put_uint64_t(buf, 0, time_usec);
  353. _mav_put_int32_t(buf, 8, lat);
  354. _mav_put_int32_t(buf, 12, lon);
  355. _mav_put_int32_t(buf, 16, alt);
  356. _mav_put_uint16_t(buf, 20, eph);
  357. _mav_put_uint16_t(buf, 22, epv);
  358. _mav_put_uint16_t(buf, 24, vel);
  359. _mav_put_uint16_t(buf, 26, cog);
  360. _mav_put_uint8_t(buf, 28, fix_type);
  361. _mav_put_uint8_t(buf, 29, satellites_visible);
  362. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  363. _mav_put_uint32_t(buf, 34, h_acc);
  364. _mav_put_uint32_t(buf, 38, v_acc);
  365. _mav_put_uint32_t(buf, 42, vel_acc);
  366. _mav_put_uint32_t(buf, 46, hdg_acc);
  367. _mav_put_uint16_t(buf, 50, yaw);
  368. _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);
  369. #else
  370. mavlink_gps_raw_int_t packet;
  371. packet.time_usec = time_usec;
  372. packet.lat = lat;
  373. packet.lon = lon;
  374. packet.alt = alt;
  375. packet.eph = eph;
  376. packet.epv = epv;
  377. packet.vel = vel;
  378. packet.cog = cog;
  379. packet.fix_type = fix_type;
  380. packet.satellites_visible = satellites_visible;
  381. packet.alt_ellipsoid = alt_ellipsoid;
  382. packet.h_acc = h_acc;
  383. packet.v_acc = v_acc;
  384. packet.vel_acc = vel_acc;
  385. packet.hdg_acc = hdg_acc;
  386. packet.yaw = yaw;
  387. _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);
  388. #endif
  389. }
  390. /**
  391. * @brief Send a gps_raw_int message
  392. * @param chan MAVLink channel to send the message
  393. * @param struct The MAVLink struct to serialize
  394. */
  395. static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int)
  396. {
  397. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  398. 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);
  399. #else
  400. _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);
  401. #endif
  402. }
  403. #if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  404. /*
  405. This variant of _send() can be used to save stack space by re-using
  406. memory from the receive buffer. The caller provides a
  407. mavlink_message_t which is the size of a full mavlink message. This
  408. is usually the receive buffer for the channel, and allows a reply to an
  409. incoming message with minimum stack space usage.
  410. */
  411. 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)
  412. {
  413. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  414. char *buf = (char *)msgbuf;
  415. _mav_put_uint64_t(buf, 0, time_usec);
  416. _mav_put_int32_t(buf, 8, lat);
  417. _mav_put_int32_t(buf, 12, lon);
  418. _mav_put_int32_t(buf, 16, alt);
  419. _mav_put_uint16_t(buf, 20, eph);
  420. _mav_put_uint16_t(buf, 22, epv);
  421. _mav_put_uint16_t(buf, 24, vel);
  422. _mav_put_uint16_t(buf, 26, cog);
  423. _mav_put_uint8_t(buf, 28, fix_type);
  424. _mav_put_uint8_t(buf, 29, satellites_visible);
  425. _mav_put_int32_t(buf, 30, alt_ellipsoid);
  426. _mav_put_uint32_t(buf, 34, h_acc);
  427. _mav_put_uint32_t(buf, 38, v_acc);
  428. _mav_put_uint32_t(buf, 42, vel_acc);
  429. _mav_put_uint32_t(buf, 46, hdg_acc);
  430. _mav_put_uint16_t(buf, 50, yaw);
  431. _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);
  432. #else
  433. mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf;
  434. packet->time_usec = time_usec;
  435. packet->lat = lat;
  436. packet->lon = lon;
  437. packet->alt = alt;
  438. packet->eph = eph;
  439. packet->epv = epv;
  440. packet->vel = vel;
  441. packet->cog = cog;
  442. packet->fix_type = fix_type;
  443. packet->satellites_visible = satellites_visible;
  444. packet->alt_ellipsoid = alt_ellipsoid;
  445. packet->h_acc = h_acc;
  446. packet->v_acc = v_acc;
  447. packet->vel_acc = vel_acc;
  448. packet->hdg_acc = hdg_acc;
  449. packet->yaw = yaw;
  450. _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);
  451. #endif
  452. }
  453. #endif
  454. #endif
  455. // MESSAGE GPS_RAW_INT UNPACKING
  456. /**
  457. * @brief Get field time_usec from gps_raw_int message
  458. *
  459. * @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.
  460. */
  461. static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
  462. {
  463. return _MAV_RETURN_uint64_t(msg, 0);
  464. }
  465. /**
  466. * @brief Get field fix_type from gps_raw_int message
  467. *
  468. * @return GPS fix type.
  469. */
  470. static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
  471. {
  472. return _MAV_RETURN_uint8_t(msg, 28);
  473. }
  474. /**
  475. * @brief Get field lat from gps_raw_int message
  476. *
  477. * @return [degE7] Latitude (WGS84, EGM96 ellipsoid)
  478. */
  479. static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_int32_t(msg, 8);
  482. }
  483. /**
  484. * @brief Get field lon from gps_raw_int message
  485. *
  486. * @return [degE7] Longitude (WGS84, EGM96 ellipsoid)
  487. */
  488. static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_int32_t(msg, 12);
  491. }
  492. /**
  493. * @brief Get field alt from gps_raw_int message
  494. *
  495. * @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
  496. */
  497. static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_int32_t(msg, 16);
  500. }
  501. /**
  502. * @brief Get field eph from gps_raw_int message
  503. *
  504. * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  505. */
  506. static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_uint16_t(msg, 20);
  509. }
  510. /**
  511. * @brief Get field epv from gps_raw_int message
  512. *
  513. * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  514. */
  515. static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_uint16_t(msg, 22);
  518. }
  519. /**
  520. * @brief Get field vel from gps_raw_int message
  521. *
  522. * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  523. */
  524. static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_uint16_t(msg, 24);
  527. }
  528. /**
  529. * @brief Get field cog from gps_raw_int message
  530. *
  531. * @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
  532. */
  533. static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_uint16_t(msg, 26);
  536. }
  537. /**
  538. * @brief Get field satellites_visible from gps_raw_int message
  539. *
  540. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  541. */
  542. static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_uint8_t(msg, 29);
  545. }
  546. /**
  547. * @brief Get field alt_ellipsoid from gps_raw_int message
  548. *
  549. * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  550. */
  551. static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_int32_t(msg, 30);
  554. }
  555. /**
  556. * @brief Get field h_acc from gps_raw_int message
  557. *
  558. * @return [mm] Position uncertainty.
  559. */
  560. static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_uint32_t(msg, 34);
  563. }
  564. /**
  565. * @brief Get field v_acc from gps_raw_int message
  566. *
  567. * @return [mm] Altitude uncertainty.
  568. */
  569. static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_uint32_t(msg, 38);
  572. }
  573. /**
  574. * @brief Get field vel_acc from gps_raw_int message
  575. *
  576. * @return [mm] Speed uncertainty.
  577. */
  578. static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_uint32_t(msg, 42);
  581. }
  582. /**
  583. * @brief Get field hdg_acc from gps_raw_int message
  584. *
  585. * @return [degE5] Heading / track uncertainty
  586. */
  587. static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t* msg)
  588. {
  589. return _MAV_RETURN_uint32_t(msg, 46);
  590. }
  591. /**
  592. * @brief Get field yaw from gps_raw_int message
  593. *
  594. * @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.
  595. */
  596. static inline uint16_t mavlink_msg_gps_raw_int_get_yaw(const mavlink_message_t* msg)
  597. {
  598. return _MAV_RETURN_uint16_t(msg, 50);
  599. }
  600. /**
  601. * @brief Decode a gps_raw_int message into a struct
  602. *
  603. * @param msg The message to decode
  604. * @param gps_raw_int C-struct to decode the message contents into
  605. */
  606. static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
  607. {
  608. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  609. gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg);
  610. gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
  611. gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
  612. gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
  613. gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
  614. gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
  615. gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg);
  616. gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
  617. gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
  618. gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
  619. gps_raw_int->alt_ellipsoid = mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg);
  620. gps_raw_int->h_acc = mavlink_msg_gps_raw_int_get_h_acc(msg);
  621. gps_raw_int->v_acc = mavlink_msg_gps_raw_int_get_v_acc(msg);
  622. gps_raw_int->vel_acc = mavlink_msg_gps_raw_int_get_vel_acc(msg);
  623. gps_raw_int->hdg_acc = mavlink_msg_gps_raw_int_get_hdg_acc(msg);
  624. gps_raw_int->yaw = mavlink_msg_gps_raw_int_get_yaw(msg);
  625. #else
  626. uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
  627. memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
  628. memcpy(gps_raw_int, _MAV_PAYLOAD(msg), len);
  629. #endif
  630. }