mavlink_msg_gps2_raw.h 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736
  1. #pragma once
  2. // MESSAGE GPS2_RAW PACKING
  3. #define MAVLINK_MSG_ID_GPS2_RAW 124
  4. MAVPACKED(
  5. typedef struct __mavlink_gps2_raw_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. uint32_t dgps_age; /*< [ms] Age of DGPS info*/
  11. uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/
  12. uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX*/
  13. uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
  14. uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
  15. uint8_t fix_type; /*< GPS fix type.*/
  16. uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to UINT8_MAX*/
  17. uint8_t dgps_numch; /*< Number of DGPS satellites*/
  18. 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.*/
  19. int32_t alt_ellipsoid; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/
  20. uint32_t h_acc; /*< [mm] Position uncertainty.*/
  21. uint32_t v_acc; /*< [mm] Altitude uncertainty.*/
  22. uint32_t vel_acc; /*< [mm] Speed uncertainty.*/
  23. uint32_t hdg_acc; /*< [degE5] Heading / track uncertainty*/
  24. }) mavlink_gps2_raw_t;
  25. #define MAVLINK_MSG_ID_GPS2_RAW_LEN 57
  26. #define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35
  27. #define MAVLINK_MSG_ID_124_LEN 57
  28. #define MAVLINK_MSG_ID_124_MIN_LEN 35
  29. #define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
  30. #define MAVLINK_MSG_ID_124_CRC 87
  31. #if MAVLINK_COMMAND_24BIT
  32. #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
  33. 124, \
  34. "GPS2_RAW", \
  35. 18, \
  36. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
  37. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
  38. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
  39. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
  40. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
  41. { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
  42. { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
  43. { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
  44. { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
  45. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
  46. { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
  47. { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
  48. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
  49. { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 37, offsetof(mavlink_gps2_raw_t, alt_ellipsoid) }, \
  50. { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 41, offsetof(mavlink_gps2_raw_t, h_acc) }, \
  51. { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 45, offsetof(mavlink_gps2_raw_t, v_acc) }, \
  52. { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 49, offsetof(mavlink_gps2_raw_t, vel_acc) }, \
  53. { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 53, offsetof(mavlink_gps2_raw_t, hdg_acc) }, \
  54. } \
  55. }
  56. #else
  57. #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
  58. "GPS2_RAW", \
  59. 18, \
  60. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
  61. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
  62. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
  63. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
  64. { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
  65. { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
  66. { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
  67. { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
  68. { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
  69. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
  70. { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
  71. { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
  72. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
  73. { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 37, offsetof(mavlink_gps2_raw_t, alt_ellipsoid) }, \
  74. { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 41, offsetof(mavlink_gps2_raw_t, h_acc) }, \
  75. { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 45, offsetof(mavlink_gps2_raw_t, v_acc) }, \
  76. { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 49, offsetof(mavlink_gps2_raw_t, vel_acc) }, \
  77. { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 53, offsetof(mavlink_gps2_raw_t, hdg_acc) }, \
  78. } \
  79. }
  80. #endif
  81. /**
  82. * @brief Pack a gps2_raw message
  83. * @param system_id ID of this system
  84. * @param component_id ID of this component (e.g. 200 for IMU)
  85. * @param msg The MAVLink message to compress the data into
  86. *
  87. * @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.
  88. * @param fix_type GPS fix type.
  89. * @param lat [degE7] Latitude (WGS84)
  90. * @param lon [degE7] Longitude (WGS84)
  91. * @param alt [mm] Altitude (MSL). Positive for up.
  92. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  93. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  94. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  95. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  96. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  97. * @param dgps_numch Number of DGPS satellites
  98. * @param dgps_age [ms] Age of DGPS info
  99. * @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.
  100. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  101. * @param h_acc [mm] Position uncertainty.
  102. * @param v_acc [mm] Altitude uncertainty.
  103. * @param vel_acc [mm] Speed uncertainty.
  104. * @param hdg_acc [degE5] Heading / track uncertainty
  105. * @return length of the message in bytes (excluding serial stream start sign)
  106. */
  107. static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  108. 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, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
  109. {
  110. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  111. char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
  112. _mav_put_uint64_t(buf, 0, time_usec);
  113. _mav_put_int32_t(buf, 8, lat);
  114. _mav_put_int32_t(buf, 12, lon);
  115. _mav_put_int32_t(buf, 16, alt);
  116. _mav_put_uint32_t(buf, 20, dgps_age);
  117. _mav_put_uint16_t(buf, 24, eph);
  118. _mav_put_uint16_t(buf, 26, epv);
  119. _mav_put_uint16_t(buf, 28, vel);
  120. _mav_put_uint16_t(buf, 30, cog);
  121. _mav_put_uint8_t(buf, 32, fix_type);
  122. _mav_put_uint8_t(buf, 33, satellites_visible);
  123. _mav_put_uint8_t(buf, 34, dgps_numch);
  124. _mav_put_uint16_t(buf, 35, yaw);
  125. _mav_put_int32_t(buf, 37, alt_ellipsoid);
  126. _mav_put_uint32_t(buf, 41, h_acc);
  127. _mav_put_uint32_t(buf, 45, v_acc);
  128. _mav_put_uint32_t(buf, 49, vel_acc);
  129. _mav_put_uint32_t(buf, 53, hdg_acc);
  130. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  131. #else
  132. mavlink_gps2_raw_t packet;
  133. packet.time_usec = time_usec;
  134. packet.lat = lat;
  135. packet.lon = lon;
  136. packet.alt = alt;
  137. packet.dgps_age = dgps_age;
  138. packet.eph = eph;
  139. packet.epv = epv;
  140. packet.vel = vel;
  141. packet.cog = cog;
  142. packet.fix_type = fix_type;
  143. packet.satellites_visible = satellites_visible;
  144. packet.dgps_numch = dgps_numch;
  145. packet.yaw = yaw;
  146. packet.alt_ellipsoid = alt_ellipsoid;
  147. packet.h_acc = h_acc;
  148. packet.v_acc = v_acc;
  149. packet.vel_acc = vel_acc;
  150. packet.hdg_acc = hdg_acc;
  151. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  152. #endif
  153. msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
  154. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  155. }
  156. /**
  157. * @brief Pack a gps2_raw message
  158. * @param system_id ID of this system
  159. * @param component_id ID of this component (e.g. 200 for IMU)
  160. * @param status MAVLink status structure
  161. * @param msg The MAVLink message to compress the data into
  162. *
  163. * @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.
  164. * @param fix_type GPS fix type.
  165. * @param lat [degE7] Latitude (WGS84)
  166. * @param lon [degE7] Longitude (WGS84)
  167. * @param alt [mm] Altitude (MSL). Positive for up.
  168. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  169. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  170. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  171. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  172. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  173. * @param dgps_numch Number of DGPS satellites
  174. * @param dgps_age [ms] Age of DGPS info
  175. * @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.
  176. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  177. * @param h_acc [mm] Position uncertainty.
  178. * @param v_acc [mm] Altitude uncertainty.
  179. * @param vel_acc [mm] Speed uncertainty.
  180. * @param hdg_acc [degE5] Heading / track uncertainty
  181. * @return length of the message in bytes (excluding serial stream start sign)
  182. */
  183. static inline uint16_t mavlink_msg_gps2_raw_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  184. 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, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
  185. {
  186. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  187. char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
  188. _mav_put_uint64_t(buf, 0, time_usec);
  189. _mav_put_int32_t(buf, 8, lat);
  190. _mav_put_int32_t(buf, 12, lon);
  191. _mav_put_int32_t(buf, 16, alt);
  192. _mav_put_uint32_t(buf, 20, dgps_age);
  193. _mav_put_uint16_t(buf, 24, eph);
  194. _mav_put_uint16_t(buf, 26, epv);
  195. _mav_put_uint16_t(buf, 28, vel);
  196. _mav_put_uint16_t(buf, 30, cog);
  197. _mav_put_uint8_t(buf, 32, fix_type);
  198. _mav_put_uint8_t(buf, 33, satellites_visible);
  199. _mav_put_uint8_t(buf, 34, dgps_numch);
  200. _mav_put_uint16_t(buf, 35, yaw);
  201. _mav_put_int32_t(buf, 37, alt_ellipsoid);
  202. _mav_put_uint32_t(buf, 41, h_acc);
  203. _mav_put_uint32_t(buf, 45, v_acc);
  204. _mav_put_uint32_t(buf, 49, vel_acc);
  205. _mav_put_uint32_t(buf, 53, hdg_acc);
  206. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  207. #else
  208. mavlink_gps2_raw_t packet;
  209. packet.time_usec = time_usec;
  210. packet.lat = lat;
  211. packet.lon = lon;
  212. packet.alt = alt;
  213. packet.dgps_age = dgps_age;
  214. packet.eph = eph;
  215. packet.epv = epv;
  216. packet.vel = vel;
  217. packet.cog = cog;
  218. packet.fix_type = fix_type;
  219. packet.satellites_visible = satellites_visible;
  220. packet.dgps_numch = dgps_numch;
  221. packet.yaw = yaw;
  222. packet.alt_ellipsoid = alt_ellipsoid;
  223. packet.h_acc = h_acc;
  224. packet.v_acc = v_acc;
  225. packet.vel_acc = vel_acc;
  226. packet.hdg_acc = hdg_acc;
  227. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  228. #endif
  229. msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
  230. #if MAVLINK_CRC_EXTRA
  231. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  232. #else
  233. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  234. #endif
  235. }
  236. /**
  237. * @brief Pack a gps2_raw message on a channel
  238. * @param system_id ID of this system
  239. * @param component_id ID of this component (e.g. 200 for IMU)
  240. * @param chan The MAVLink channel this message will be sent over
  241. * @param msg The MAVLink message to compress the data into
  242. * @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.
  243. * @param fix_type GPS fix type.
  244. * @param lat [degE7] Latitude (WGS84)
  245. * @param lon [degE7] Longitude (WGS84)
  246. * @param alt [mm] Altitude (MSL). Positive for up.
  247. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  248. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  249. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  250. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  251. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  252. * @param dgps_numch Number of DGPS satellites
  253. * @param dgps_age [ms] Age of DGPS info
  254. * @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.
  255. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  256. * @param h_acc [mm] Position uncertainty.
  257. * @param v_acc [mm] Altitude uncertainty.
  258. * @param vel_acc [mm] Speed uncertainty.
  259. * @param hdg_acc [degE5] Heading / track uncertainty
  260. * @return length of the message in bytes (excluding serial stream start sign)
  261. */
  262. static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  263. mavlink_message_t* msg,
  264. 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,uint8_t dgps_numch,uint32_t dgps_age,uint16_t yaw,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc)
  265. {
  266. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  267. char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
  268. _mav_put_uint64_t(buf, 0, time_usec);
  269. _mav_put_int32_t(buf, 8, lat);
  270. _mav_put_int32_t(buf, 12, lon);
  271. _mav_put_int32_t(buf, 16, alt);
  272. _mav_put_uint32_t(buf, 20, dgps_age);
  273. _mav_put_uint16_t(buf, 24, eph);
  274. _mav_put_uint16_t(buf, 26, epv);
  275. _mav_put_uint16_t(buf, 28, vel);
  276. _mav_put_uint16_t(buf, 30, cog);
  277. _mav_put_uint8_t(buf, 32, fix_type);
  278. _mav_put_uint8_t(buf, 33, satellites_visible);
  279. _mav_put_uint8_t(buf, 34, dgps_numch);
  280. _mav_put_uint16_t(buf, 35, yaw);
  281. _mav_put_int32_t(buf, 37, alt_ellipsoid);
  282. _mav_put_uint32_t(buf, 41, h_acc);
  283. _mav_put_uint32_t(buf, 45, v_acc);
  284. _mav_put_uint32_t(buf, 49, vel_acc);
  285. _mav_put_uint32_t(buf, 53, hdg_acc);
  286. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  287. #else
  288. mavlink_gps2_raw_t packet;
  289. packet.time_usec = time_usec;
  290. packet.lat = lat;
  291. packet.lon = lon;
  292. packet.alt = alt;
  293. packet.dgps_age = dgps_age;
  294. packet.eph = eph;
  295. packet.epv = epv;
  296. packet.vel = vel;
  297. packet.cog = cog;
  298. packet.fix_type = fix_type;
  299. packet.satellites_visible = satellites_visible;
  300. packet.dgps_numch = dgps_numch;
  301. packet.yaw = yaw;
  302. packet.alt_ellipsoid = alt_ellipsoid;
  303. packet.h_acc = h_acc;
  304. packet.v_acc = v_acc;
  305. packet.vel_acc = vel_acc;
  306. packet.hdg_acc = hdg_acc;
  307. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  308. #endif
  309. msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
  310. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  311. }
  312. /**
  313. * @brief Encode a gps2_raw struct
  314. *
  315. * @param system_id ID of this system
  316. * @param component_id ID of this component (e.g. 200 for IMU)
  317. * @param msg The MAVLink message to compress the data into
  318. * @param gps2_raw C-struct to read the message contents from
  319. */
  320. static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
  321. {
  322. return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc);
  323. }
  324. /**
  325. * @brief Encode a gps2_raw struct on a channel
  326. *
  327. * @param system_id ID of this system
  328. * @param component_id ID of this component (e.g. 200 for IMU)
  329. * @param chan The MAVLink channel this message will be sent over
  330. * @param msg The MAVLink message to compress the data into
  331. * @param gps2_raw C-struct to read the message contents from
  332. */
  333. static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
  334. {
  335. return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc);
  336. }
  337. /**
  338. * @brief Encode a gps2_raw struct with provided status structure
  339. *
  340. * @param system_id ID of this system
  341. * @param component_id ID of this component (e.g. 200 for IMU)
  342. * @param status MAVLink status structure
  343. * @param msg The MAVLink message to compress the data into
  344. * @param gps2_raw C-struct to read the message contents from
  345. */
  346. static inline uint16_t mavlink_msg_gps2_raw_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
  347. {
  348. return mavlink_msg_gps2_raw_pack_status(system_id, component_id, _status, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc);
  349. }
  350. /**
  351. * @brief Send a gps2_raw message
  352. * @param chan MAVLink channel to send the message
  353. *
  354. * @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.
  355. * @param fix_type GPS fix type.
  356. * @param lat [degE7] Latitude (WGS84)
  357. * @param lon [degE7] Longitude (WGS84)
  358. * @param alt [mm] Altitude (MSL). Positive for up.
  359. * @param eph GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  360. * @param epv GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  361. * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  362. * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  363. * @param satellites_visible Number of satellites visible. If unknown, set to UINT8_MAX
  364. * @param dgps_numch Number of DGPS satellites
  365. * @param dgps_age [ms] Age of DGPS info
  366. * @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.
  367. * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  368. * @param h_acc [mm] Position uncertainty.
  369. * @param v_acc [mm] Altitude uncertainty.
  370. * @param vel_acc [mm] Speed uncertainty.
  371. * @param hdg_acc [degE5] Heading / track uncertainty
  372. */
  373. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  374. static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
  375. {
  376. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  377. char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
  378. _mav_put_uint64_t(buf, 0, time_usec);
  379. _mav_put_int32_t(buf, 8, lat);
  380. _mav_put_int32_t(buf, 12, lon);
  381. _mav_put_int32_t(buf, 16, alt);
  382. _mav_put_uint32_t(buf, 20, dgps_age);
  383. _mav_put_uint16_t(buf, 24, eph);
  384. _mav_put_uint16_t(buf, 26, epv);
  385. _mav_put_uint16_t(buf, 28, vel);
  386. _mav_put_uint16_t(buf, 30, cog);
  387. _mav_put_uint8_t(buf, 32, fix_type);
  388. _mav_put_uint8_t(buf, 33, satellites_visible);
  389. _mav_put_uint8_t(buf, 34, dgps_numch);
  390. _mav_put_uint16_t(buf, 35, yaw);
  391. _mav_put_int32_t(buf, 37, alt_ellipsoid);
  392. _mav_put_uint32_t(buf, 41, h_acc);
  393. _mav_put_uint32_t(buf, 45, v_acc);
  394. _mav_put_uint32_t(buf, 49, vel_acc);
  395. _mav_put_uint32_t(buf, 53, hdg_acc);
  396. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  397. #else
  398. mavlink_gps2_raw_t packet;
  399. packet.time_usec = time_usec;
  400. packet.lat = lat;
  401. packet.lon = lon;
  402. packet.alt = alt;
  403. packet.dgps_age = dgps_age;
  404. packet.eph = eph;
  405. packet.epv = epv;
  406. packet.vel = vel;
  407. packet.cog = cog;
  408. packet.fix_type = fix_type;
  409. packet.satellites_visible = satellites_visible;
  410. packet.dgps_numch = dgps_numch;
  411. packet.yaw = yaw;
  412. packet.alt_ellipsoid = alt_ellipsoid;
  413. packet.h_acc = h_acc;
  414. packet.v_acc = v_acc;
  415. packet.vel_acc = vel_acc;
  416. packet.hdg_acc = hdg_acc;
  417. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  418. #endif
  419. }
  420. /**
  421. * @brief Send a gps2_raw message
  422. * @param chan MAVLink channel to send the message
  423. * @param struct The MAVLink struct to serialize
  424. */
  425. static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw)
  426. {
  427. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  428. mavlink_msg_gps2_raw_send(chan, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw, gps2_raw->alt_ellipsoid, gps2_raw->h_acc, gps2_raw->v_acc, gps2_raw->vel_acc, gps2_raw->hdg_acc);
  429. #else
  430. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  431. #endif
  432. }
  433. #if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  434. /*
  435. This variant of _send() can be used to save stack space by re-using
  436. memory from the receive buffer. The caller provides a
  437. mavlink_message_t which is the size of a full mavlink message. This
  438. is usually the receive buffer for the channel, and allows a reply to an
  439. incoming message with minimum stack space usage.
  440. */
  441. static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc)
  442. {
  443. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  444. char *buf = (char *)msgbuf;
  445. _mav_put_uint64_t(buf, 0, time_usec);
  446. _mav_put_int32_t(buf, 8, lat);
  447. _mav_put_int32_t(buf, 12, lon);
  448. _mav_put_int32_t(buf, 16, alt);
  449. _mav_put_uint32_t(buf, 20, dgps_age);
  450. _mav_put_uint16_t(buf, 24, eph);
  451. _mav_put_uint16_t(buf, 26, epv);
  452. _mav_put_uint16_t(buf, 28, vel);
  453. _mav_put_uint16_t(buf, 30, cog);
  454. _mav_put_uint8_t(buf, 32, fix_type);
  455. _mav_put_uint8_t(buf, 33, satellites_visible);
  456. _mav_put_uint8_t(buf, 34, dgps_numch);
  457. _mav_put_uint16_t(buf, 35, yaw);
  458. _mav_put_int32_t(buf, 37, alt_ellipsoid);
  459. _mav_put_uint32_t(buf, 41, h_acc);
  460. _mav_put_uint32_t(buf, 45, v_acc);
  461. _mav_put_uint32_t(buf, 49, vel_acc);
  462. _mav_put_uint32_t(buf, 53, hdg_acc);
  463. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  464. #else
  465. mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
  466. packet->time_usec = time_usec;
  467. packet->lat = lat;
  468. packet->lon = lon;
  469. packet->alt = alt;
  470. packet->dgps_age = dgps_age;
  471. packet->eph = eph;
  472. packet->epv = epv;
  473. packet->vel = vel;
  474. packet->cog = cog;
  475. packet->fix_type = fix_type;
  476. packet->satellites_visible = satellites_visible;
  477. packet->dgps_numch = dgps_numch;
  478. packet->yaw = yaw;
  479. packet->alt_ellipsoid = alt_ellipsoid;
  480. packet->h_acc = h_acc;
  481. packet->v_acc = v_acc;
  482. packet->vel_acc = vel_acc;
  483. packet->hdg_acc = hdg_acc;
  484. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
  485. #endif
  486. }
  487. #endif
  488. #endif
  489. // MESSAGE GPS2_RAW UNPACKING
  490. /**
  491. * @brief Get field time_usec from gps2_raw message
  492. *
  493. * @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.
  494. */
  495. static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
  496. {
  497. return _MAV_RETURN_uint64_t(msg, 0);
  498. }
  499. /**
  500. * @brief Get field fix_type from gps2_raw message
  501. *
  502. * @return GPS fix type.
  503. */
  504. static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
  505. {
  506. return _MAV_RETURN_uint8_t(msg, 32);
  507. }
  508. /**
  509. * @brief Get field lat from gps2_raw message
  510. *
  511. * @return [degE7] Latitude (WGS84)
  512. */
  513. static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
  514. {
  515. return _MAV_RETURN_int32_t(msg, 8);
  516. }
  517. /**
  518. * @brief Get field lon from gps2_raw message
  519. *
  520. * @return [degE7] Longitude (WGS84)
  521. */
  522. static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
  523. {
  524. return _MAV_RETURN_int32_t(msg, 12);
  525. }
  526. /**
  527. * @brief Get field alt from gps2_raw message
  528. *
  529. * @return [mm] Altitude (MSL). Positive for up.
  530. */
  531. static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
  532. {
  533. return _MAV_RETURN_int32_t(msg, 16);
  534. }
  535. /**
  536. * @brief Get field eph from gps2_raw message
  537. *
  538. * @return GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  539. */
  540. static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
  541. {
  542. return _MAV_RETURN_uint16_t(msg, 24);
  543. }
  544. /**
  545. * @brief Get field epv from gps2_raw message
  546. *
  547. * @return GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX
  548. */
  549. static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
  550. {
  551. return _MAV_RETURN_uint16_t(msg, 26);
  552. }
  553. /**
  554. * @brief Get field vel from gps2_raw message
  555. *
  556. * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
  557. */
  558. static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
  559. {
  560. return _MAV_RETURN_uint16_t(msg, 28);
  561. }
  562. /**
  563. * @brief Get field cog from gps2_raw message
  564. *
  565. * @return [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
  566. */
  567. static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
  568. {
  569. return _MAV_RETURN_uint16_t(msg, 30);
  570. }
  571. /**
  572. * @brief Get field satellites_visible from gps2_raw message
  573. *
  574. * @return Number of satellites visible. If unknown, set to UINT8_MAX
  575. */
  576. static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
  577. {
  578. return _MAV_RETURN_uint8_t(msg, 33);
  579. }
  580. /**
  581. * @brief Get field dgps_numch from gps2_raw message
  582. *
  583. * @return Number of DGPS satellites
  584. */
  585. static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
  586. {
  587. return _MAV_RETURN_uint8_t(msg, 34);
  588. }
  589. /**
  590. * @brief Get field dgps_age from gps2_raw message
  591. *
  592. * @return [ms] Age of DGPS info
  593. */
  594. static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
  595. {
  596. return _MAV_RETURN_uint32_t(msg, 20);
  597. }
  598. /**
  599. * @brief Get field yaw from gps2_raw message
  600. *
  601. * @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.
  602. */
  603. static inline uint16_t mavlink_msg_gps2_raw_get_yaw(const mavlink_message_t* msg)
  604. {
  605. return _MAV_RETURN_uint16_t(msg, 35);
  606. }
  607. /**
  608. * @brief Get field alt_ellipsoid from gps2_raw message
  609. *
  610. * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
  611. */
  612. static inline int32_t mavlink_msg_gps2_raw_get_alt_ellipsoid(const mavlink_message_t* msg)
  613. {
  614. return _MAV_RETURN_int32_t(msg, 37);
  615. }
  616. /**
  617. * @brief Get field h_acc from gps2_raw message
  618. *
  619. * @return [mm] Position uncertainty.
  620. */
  621. static inline uint32_t mavlink_msg_gps2_raw_get_h_acc(const mavlink_message_t* msg)
  622. {
  623. return _MAV_RETURN_uint32_t(msg, 41);
  624. }
  625. /**
  626. * @brief Get field v_acc from gps2_raw message
  627. *
  628. * @return [mm] Altitude uncertainty.
  629. */
  630. static inline uint32_t mavlink_msg_gps2_raw_get_v_acc(const mavlink_message_t* msg)
  631. {
  632. return _MAV_RETURN_uint32_t(msg, 45);
  633. }
  634. /**
  635. * @brief Get field vel_acc from gps2_raw message
  636. *
  637. * @return [mm] Speed uncertainty.
  638. */
  639. static inline uint32_t mavlink_msg_gps2_raw_get_vel_acc(const mavlink_message_t* msg)
  640. {
  641. return _MAV_RETURN_uint32_t(msg, 49);
  642. }
  643. /**
  644. * @brief Get field hdg_acc from gps2_raw message
  645. *
  646. * @return [degE5] Heading / track uncertainty
  647. */
  648. static inline uint32_t mavlink_msg_gps2_raw_get_hdg_acc(const mavlink_message_t* msg)
  649. {
  650. return _MAV_RETURN_uint32_t(msg, 53);
  651. }
  652. /**
  653. * @brief Decode a gps2_raw message into a struct
  654. *
  655. * @param msg The message to decode
  656. * @param gps2_raw C-struct to decode the message contents into
  657. */
  658. static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
  659. {
  660. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  661. gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
  662. gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg);
  663. gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg);
  664. gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg);
  665. gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
  666. gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg);
  667. gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg);
  668. gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg);
  669. gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg);
  670. gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
  671. gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg);
  672. gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
  673. gps2_raw->yaw = mavlink_msg_gps2_raw_get_yaw(msg);
  674. gps2_raw->alt_ellipsoid = mavlink_msg_gps2_raw_get_alt_ellipsoid(msg);
  675. gps2_raw->h_acc = mavlink_msg_gps2_raw_get_h_acc(msg);
  676. gps2_raw->v_acc = mavlink_msg_gps2_raw_get_v_acc(msg);
  677. gps2_raw->vel_acc = mavlink_msg_gps2_raw_get_vel_acc(msg);
  678. gps2_raw->hdg_acc = mavlink_msg_gps2_raw_get_hdg_acc(msg);
  679. #else
  680. uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN;
  681. memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN);
  682. memcpy(gps2_raw, _MAV_PAYLOAD(msg), len);
  683. #endif
  684. }