mavlink_msg_hil_gps.h 25 KB

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