mavlink_msg_hil_gps.h 29 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652
  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
  140. * @param system_id ID of this system
  141. * @param component_id ID of this component (e.g. 200 for IMU)
  142. * @param status MAVLink status structure
  143. * @param msg The MAVLink message to compress the data into
  144. *
  145. * @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.
  146. * @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.
  147. * @param lat [degE7] Latitude (WGS84)
  148. * @param lon [degE7] Longitude (WGS84)
  149. * @param alt [mm] Altitude (MSL). Positive for up.
  150. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  151. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  152. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  153. * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
  154. * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
  155. * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
  156. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  157. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  158. * @param id GPS ID (zero indexed). Used for multiple GPS inputs
  159. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  160. * @return length of the message in bytes (excluding serial stream start sign)
  161. */
  162. static inline uint16_t mavlink_msg_hil_gps_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  204. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
  205. #else
  206. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN);
  207. #endif
  208. }
  209. /**
  210. * @brief Pack a hil_gps message on a channel
  211. * @param system_id ID of this system
  212. * @param component_id ID of this component (e.g. 200 for IMU)
  213. * @param chan The MAVLink channel this message will be sent over
  214. * @param msg The MAVLink message to compress the data into
  215. * @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.
  216. * @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.
  217. * @param lat [degE7] Latitude (WGS84)
  218. * @param lon [degE7] Longitude (WGS84)
  219. * @param alt [mm] Altitude (MSL). Positive for up.
  220. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  221. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  222. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  223. * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
  224. * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
  225. * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
  226. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  227. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  228. * @param id GPS ID (zero indexed). Used for multiple GPS inputs
  229. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  230. * @return length of the message in bytes (excluding serial stream start sign)
  231. */
  232. static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  233. mavlink_message_t* msg,
  234. 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)
  235. {
  236. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  237. char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
  238. _mav_put_uint64_t(buf, 0, time_usec);
  239. _mav_put_int32_t(buf, 8, lat);
  240. _mav_put_int32_t(buf, 12, lon);
  241. _mav_put_int32_t(buf, 16, alt);
  242. _mav_put_uint16_t(buf, 20, eph);
  243. _mav_put_uint16_t(buf, 22, epv);
  244. _mav_put_uint16_t(buf, 24, vel);
  245. _mav_put_int16_t(buf, 26, vn);
  246. _mav_put_int16_t(buf, 28, ve);
  247. _mav_put_int16_t(buf, 30, vd);
  248. _mav_put_uint16_t(buf, 32, cog);
  249. _mav_put_uint8_t(buf, 34, fix_type);
  250. _mav_put_uint8_t(buf, 35, satellites_visible);
  251. _mav_put_uint8_t(buf, 36, id);
  252. _mav_put_uint16_t(buf, 37, yaw);
  253. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
  254. #else
  255. mavlink_hil_gps_t packet;
  256. packet.time_usec = time_usec;
  257. packet.lat = lat;
  258. packet.lon = lon;
  259. packet.alt = alt;
  260. packet.eph = eph;
  261. packet.epv = epv;
  262. packet.vel = vel;
  263. packet.vn = vn;
  264. packet.ve = ve;
  265. packet.vd = vd;
  266. packet.cog = cog;
  267. packet.fix_type = fix_type;
  268. packet.satellites_visible = satellites_visible;
  269. packet.id = id;
  270. packet.yaw = yaw;
  271. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
  272. #endif
  273. msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
  274. 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);
  275. }
  276. /**
  277. * @brief Encode a hil_gps struct
  278. *
  279. * @param system_id ID of this system
  280. * @param component_id ID of this component (e.g. 200 for IMU)
  281. * @param msg The MAVLink message to compress the data into
  282. * @param hil_gps C-struct to read the message contents from
  283. */
  284. 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)
  285. {
  286. 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);
  287. }
  288. /**
  289. * @brief Encode a hil_gps struct on a channel
  290. *
  291. * @param system_id ID of this system
  292. * @param component_id ID of this component (e.g. 200 for IMU)
  293. * @param chan The MAVLink channel this message will be sent over
  294. * @param msg The MAVLink message to compress the data into
  295. * @param hil_gps C-struct to read the message contents from
  296. */
  297. 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)
  298. {
  299. 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);
  300. }
  301. /**
  302. * @brief Encode a hil_gps struct with provided status structure
  303. *
  304. * @param system_id ID of this system
  305. * @param component_id ID of this component (e.g. 200 for IMU)
  306. * @param status MAVLink status structure
  307. * @param msg The MAVLink message to compress the data into
  308. * @param hil_gps C-struct to read the message contents from
  309. */
  310. static inline uint16_t mavlink_msg_hil_gps_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
  311. {
  312. return mavlink_msg_hil_gps_pack_status(system_id, component_id, _status, 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);
  313. }
  314. /**
  315. * @brief Send a hil_gps message
  316. * @param chan MAVLink channel to send the message
  317. *
  318. * @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.
  319. * @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.
  320. * @param lat [degE7] Latitude (WGS84)
  321. * @param lon [degE7] Longitude (WGS84)
  322. * @param alt [mm] Altitude (MSL). Positive for up.
  323. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  324. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  325. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  326. * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
  327. * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
  328. * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
  329. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  330. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  331. * @param id GPS ID (zero indexed). Used for multiple GPS inputs
  332. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  333. */
  334. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  335. 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)
  336. {
  337. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  338. char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
  339. _mav_put_uint64_t(buf, 0, time_usec);
  340. _mav_put_int32_t(buf, 8, lat);
  341. _mav_put_int32_t(buf, 12, lon);
  342. _mav_put_int32_t(buf, 16, alt);
  343. _mav_put_uint16_t(buf, 20, eph);
  344. _mav_put_uint16_t(buf, 22, epv);
  345. _mav_put_uint16_t(buf, 24, vel);
  346. _mav_put_int16_t(buf, 26, vn);
  347. _mav_put_int16_t(buf, 28, ve);
  348. _mav_put_int16_t(buf, 30, vd);
  349. _mav_put_uint16_t(buf, 32, cog);
  350. _mav_put_uint8_t(buf, 34, fix_type);
  351. _mav_put_uint8_t(buf, 35, satellites_visible);
  352. _mav_put_uint8_t(buf, 36, id);
  353. _mav_put_uint16_t(buf, 37, yaw);
  354. _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);
  355. #else
  356. mavlink_hil_gps_t packet;
  357. packet.time_usec = time_usec;
  358. packet.lat = lat;
  359. packet.lon = lon;
  360. packet.alt = alt;
  361. packet.eph = eph;
  362. packet.epv = epv;
  363. packet.vel = vel;
  364. packet.vn = vn;
  365. packet.ve = ve;
  366. packet.vd = vd;
  367. packet.cog = cog;
  368. packet.fix_type = fix_type;
  369. packet.satellites_visible = satellites_visible;
  370. packet.id = id;
  371. packet.yaw = yaw;
  372. _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);
  373. #endif
  374. }
  375. /**
  376. * @brief Send a hil_gps message
  377. * @param chan MAVLink channel to send the message
  378. * @param struct The MAVLink struct to serialize
  379. */
  380. static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps)
  381. {
  382. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  383. 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);
  384. #else
  385. _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);
  386. #endif
  387. }
  388. #if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  389. /*
  390. This variant of _send() can be used to save stack space by re-using
  391. memory from the receive buffer. The caller provides a
  392. mavlink_message_t which is the size of a full mavlink message. This
  393. is usually the receive buffer for the channel, and allows a reply to an
  394. incoming message with minimum stack space usage.
  395. */
  396. 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)
  397. {
  398. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  399. char *buf = (char *)msgbuf;
  400. _mav_put_uint64_t(buf, 0, time_usec);
  401. _mav_put_int32_t(buf, 8, lat);
  402. _mav_put_int32_t(buf, 12, lon);
  403. _mav_put_int32_t(buf, 16, alt);
  404. _mav_put_uint16_t(buf, 20, eph);
  405. _mav_put_uint16_t(buf, 22, epv);
  406. _mav_put_uint16_t(buf, 24, vel);
  407. _mav_put_int16_t(buf, 26, vn);
  408. _mav_put_int16_t(buf, 28, ve);
  409. _mav_put_int16_t(buf, 30, vd);
  410. _mav_put_uint16_t(buf, 32, cog);
  411. _mav_put_uint8_t(buf, 34, fix_type);
  412. _mav_put_uint8_t(buf, 35, satellites_visible);
  413. _mav_put_uint8_t(buf, 36, id);
  414. _mav_put_uint16_t(buf, 37, yaw);
  415. _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);
  416. #else
  417. mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
  418. packet->time_usec = time_usec;
  419. packet->lat = lat;
  420. packet->lon = lon;
  421. packet->alt = alt;
  422. packet->eph = eph;
  423. packet->epv = epv;
  424. packet->vel = vel;
  425. packet->vn = vn;
  426. packet->ve = ve;
  427. packet->vd = vd;
  428. packet->cog = cog;
  429. packet->fix_type = fix_type;
  430. packet->satellites_visible = satellites_visible;
  431. packet->id = id;
  432. packet->yaw = yaw;
  433. _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);
  434. #endif
  435. }
  436. #endif
  437. #endif
  438. // MESSAGE HIL_GPS UNPACKING
  439. /**
  440. * @brief Get field time_usec from hil_gps message
  441. *
  442. * @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.
  443. */
  444. static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
  445. {
  446. return _MAV_RETURN_uint64_t(msg, 0);
  447. }
  448. /**
  449. * @brief Get field fix_type from hil_gps message
  450. *
  451. * @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.
  452. */
  453. static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg)
  454. {
  455. return _MAV_RETURN_uint8_t(msg, 34);
  456. }
  457. /**
  458. * @brief Get field lat from hil_gps message
  459. *
  460. * @return [degE7] Latitude (WGS84)
  461. */
  462. static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
  463. {
  464. return _MAV_RETURN_int32_t(msg, 8);
  465. }
  466. /**
  467. * @brief Get field lon from hil_gps message
  468. *
  469. * @return [degE7] Longitude (WGS84)
  470. */
  471. static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
  472. {
  473. return _MAV_RETURN_int32_t(msg, 12);
  474. }
  475. /**
  476. * @brief Get field alt from hil_gps message
  477. *
  478. * @return [mm] Altitude (MSL). Positive for up.
  479. */
  480. static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
  481. {
  482. return _MAV_RETURN_int32_t(msg, 16);
  483. }
  484. /**
  485. * @brief Get field eph from hil_gps message
  486. *
  487. * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  488. */
  489. static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
  490. {
  491. return _MAV_RETURN_uint16_t(msg, 20);
  492. }
  493. /**
  494. * @brief Get field epv from hil_gps message
  495. *
  496. * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  497. */
  498. static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
  499. {
  500. return _MAV_RETURN_uint16_t(msg, 22);
  501. }
  502. /**
  503. * @brief Get field vel from hil_gps message
  504. *
  505. * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  506. */
  507. static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
  508. {
  509. return _MAV_RETURN_uint16_t(msg, 24);
  510. }
  511. /**
  512. * @brief Get field vn from hil_gps message
  513. *
  514. * @return [cm/s] GPS velocity in north direction in earth-fixed NED frame
  515. */
  516. static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
  517. {
  518. return _MAV_RETURN_int16_t(msg, 26);
  519. }
  520. /**
  521. * @brief Get field ve from hil_gps message
  522. *
  523. * @return [cm/s] GPS velocity in east direction in earth-fixed NED frame
  524. */
  525. static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
  526. {
  527. return _MAV_RETURN_int16_t(msg, 28);
  528. }
  529. /**
  530. * @brief Get field vd from hil_gps message
  531. *
  532. * @return [cm/s] GPS velocity in down direction in earth-fixed NED frame
  533. */
  534. static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
  535. {
  536. return _MAV_RETURN_int16_t(msg, 30);
  537. }
  538. /**
  539. * @brief Get field cog from hil_gps message
  540. *
  541. * @return [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  542. */
  543. static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg)
  544. {
  545. return _MAV_RETURN_uint16_t(msg, 32);
  546. }
  547. /**
  548. * @brief Get field satellites_visible from hil_gps message
  549. *
  550. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  551. */
  552. static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg)
  553. {
  554. return _MAV_RETURN_uint8_t(msg, 35);
  555. }
  556. /**
  557. * @brief Get field id from hil_gps message
  558. *
  559. * @return GPS ID (zero indexed). Used for multiple GPS inputs
  560. */
  561. static inline uint8_t mavlink_msg_hil_gps_get_id(const mavlink_message_t* msg)
  562. {
  563. return _MAV_RETURN_uint8_t(msg, 36);
  564. }
  565. /**
  566. * @brief Get field yaw from hil_gps message
  567. *
  568. * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  569. */
  570. static inline uint16_t mavlink_msg_hil_gps_get_yaw(const mavlink_message_t* msg)
  571. {
  572. return _MAV_RETURN_uint16_t(msg, 37);
  573. }
  574. /**
  575. * @brief Decode a hil_gps message into a struct
  576. *
  577. * @param msg The message to decode
  578. * @param hil_gps C-struct to decode the message contents into
  579. */
  580. static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps)
  581. {
  582. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  583. hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg);
  584. hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg);
  585. hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg);
  586. hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg);
  587. hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg);
  588. hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg);
  589. hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg);
  590. hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg);
  591. hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg);
  592. hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg);
  593. hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg);
  594. hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg);
  595. hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg);
  596. hil_gps->id = mavlink_msg_hil_gps_get_id(msg);
  597. hil_gps->yaw = mavlink_msg_hil_gps_get_yaw(msg);
  598. #else
  599. uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN;
  600. memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN);
  601. memcpy(hil_gps, _MAV_PAYLOAD(msg), len);
  602. #endif
  603. }