mavlink_msg_gps_input.h 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663
  1. #pragma once
  2. // MESSAGE GPS_INPUT PACKING
  3. #define MAVLINK_MSG_ID_GPS_INPUT 232
  4. MAVPACKED(
  5. typedef struct __mavlink_gps_input_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. uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/
  8. int32_t lat; /*< [degE7] Latitude (WGS84)*/
  9. int32_t lon; /*< [degE7] Longitude (WGS84)*/
  10. float alt; /*< [m] Altitude (MSL). Positive for up.*/
  11. float hdop; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
  12. float vdop; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
  13. float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/
  14. float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/
  15. float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/
  16. float speed_accuracy; /*< [m/s] GPS speed accuracy*/
  17. float horiz_accuracy; /*< [m] GPS horizontal accuracy*/
  18. float vert_accuracy; /*< [m] GPS vertical accuracy*/
  19. uint16_t ignore_flags; /*< Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.*/
  20. uint16_t time_week; /*< GPS week number*/
  21. uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/
  22. uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/
  23. uint8_t satellites_visible; /*< Number of satellites visible.*/
  24. uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/
  25. }) mavlink_gps_input_t;
  26. #define MAVLINK_MSG_ID_GPS_INPUT_LEN 65
  27. #define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63
  28. #define MAVLINK_MSG_ID_232_LEN 65
  29. #define MAVLINK_MSG_ID_232_MIN_LEN 63
  30. #define MAVLINK_MSG_ID_GPS_INPUT_CRC 151
  31. #define MAVLINK_MSG_ID_232_CRC 151
  32. #if MAVLINK_COMMAND_24BIT
  33. #define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
  34. 232, \
  35. "GPS_INPUT", \
  36. 19, \
  37. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
  38. { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
  39. { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
  40. { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
  41. { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
  42. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
  43. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
  44. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
  45. { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
  46. { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \
  47. { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \
  48. { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \
  49. { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \
  50. { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \
  51. { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
  52. { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
  53. { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
  54. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
  55. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
  56. } \
  57. }
  58. #else
  59. #define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
  60. "GPS_INPUT", \
  61. 19, \
  62. { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
  63. { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
  64. { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
  65. { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
  66. { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
  67. { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
  68. { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
  69. { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
  70. { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
  71. { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \
  72. { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \
  73. { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \
  74. { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \
  75. { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \
  76. { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
  77. { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
  78. { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
  79. { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
  80. { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
  81. } \
  82. }
  83. #endif
  84. /**
  85. * @brief Pack a gps_input message
  86. * @param system_id ID of this system
  87. * @param component_id ID of this component (e.g. 200 for IMU)
  88. * @param msg The MAVLink message to compress the data into
  89. *
  90. * @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.
  91. * @param gps_id ID of the GPS for multiple GPS inputs
  92. * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
  93. * @param time_week_ms [ms] GPS time (from start of GPS week)
  94. * @param time_week GPS week number
  95. * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
  96. * @param lat [degE7] Latitude (WGS84)
  97. * @param lon [degE7] Longitude (WGS84)
  98. * @param alt [m] Altitude (MSL). Positive for up.
  99. * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
  100. * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
  101. * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
  102. * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
  103. * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
  104. * @param speed_accuracy [m/s] GPS speed accuracy
  105. * @param horiz_accuracy [m] GPS horizontal accuracy
  106. * @param vert_accuracy [m] GPS vertical accuracy
  107. * @param satellites_visible Number of satellites visible.
  108. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  109. * @return length of the message in bytes (excluding serial stream start sign)
  110. */
  111. static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  112. uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
  113. {
  114. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  115. char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
  116. _mav_put_uint64_t(buf, 0, time_usec);
  117. _mav_put_uint32_t(buf, 8, time_week_ms);
  118. _mav_put_int32_t(buf, 12, lat);
  119. _mav_put_int32_t(buf, 16, lon);
  120. _mav_put_float(buf, 20, alt);
  121. _mav_put_float(buf, 24, hdop);
  122. _mav_put_float(buf, 28, vdop);
  123. _mav_put_float(buf, 32, vn);
  124. _mav_put_float(buf, 36, ve);
  125. _mav_put_float(buf, 40, vd);
  126. _mav_put_float(buf, 44, speed_accuracy);
  127. _mav_put_float(buf, 48, horiz_accuracy);
  128. _mav_put_float(buf, 52, vert_accuracy);
  129. _mav_put_uint16_t(buf, 56, ignore_flags);
  130. _mav_put_uint16_t(buf, 58, time_week);
  131. _mav_put_uint8_t(buf, 60, gps_id);
  132. _mav_put_uint8_t(buf, 61, fix_type);
  133. _mav_put_uint8_t(buf, 62, satellites_visible);
  134. _mav_put_uint16_t(buf, 63, yaw);
  135. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
  136. #else
  137. mavlink_gps_input_t packet;
  138. packet.time_usec = time_usec;
  139. packet.time_week_ms = time_week_ms;
  140. packet.lat = lat;
  141. packet.lon = lon;
  142. packet.alt = alt;
  143. packet.hdop = hdop;
  144. packet.vdop = vdop;
  145. packet.vn = vn;
  146. packet.ve = ve;
  147. packet.vd = vd;
  148. packet.speed_accuracy = speed_accuracy;
  149. packet.horiz_accuracy = horiz_accuracy;
  150. packet.vert_accuracy = vert_accuracy;
  151. packet.ignore_flags = ignore_flags;
  152. packet.time_week = time_week;
  153. packet.gps_id = gps_id;
  154. packet.fix_type = fix_type;
  155. packet.satellites_visible = satellites_visible;
  156. packet.yaw = yaw;
  157. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
  158. #endif
  159. msg->msgid = MAVLINK_MSG_ID_GPS_INPUT;
  160. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  161. }
  162. /**
  163. * @brief Pack a gps_input message on a channel
  164. * @param system_id ID of this system
  165. * @param component_id ID of this component (e.g. 200 for IMU)
  166. * @param chan The MAVLink channel this message will be sent over
  167. * @param msg The MAVLink message to compress the data into
  168. * @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.
  169. * @param gps_id ID of the GPS for multiple GPS inputs
  170. * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
  171. * @param time_week_ms [ms] GPS time (from start of GPS week)
  172. * @param time_week GPS week number
  173. * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
  174. * @param lat [degE7] Latitude (WGS84)
  175. * @param lon [degE7] Longitude (WGS84)
  176. * @param alt [m] Altitude (MSL). Positive for up.
  177. * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
  178. * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
  179. * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
  180. * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
  181. * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
  182. * @param speed_accuracy [m/s] GPS speed accuracy
  183. * @param horiz_accuracy [m] GPS horizontal accuracy
  184. * @param vert_accuracy [m] GPS vertical accuracy
  185. * @param satellites_visible Number of satellites visible.
  186. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  187. * @return length of the message in bytes (excluding serial stream start sign)
  188. */
  189. static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  190. mavlink_message_t* msg,
  191. uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible,uint16_t yaw)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
  195. _mav_put_uint64_t(buf, 0, time_usec);
  196. _mav_put_uint32_t(buf, 8, time_week_ms);
  197. _mav_put_int32_t(buf, 12, lat);
  198. _mav_put_int32_t(buf, 16, lon);
  199. _mav_put_float(buf, 20, alt);
  200. _mav_put_float(buf, 24, hdop);
  201. _mav_put_float(buf, 28, vdop);
  202. _mav_put_float(buf, 32, vn);
  203. _mav_put_float(buf, 36, ve);
  204. _mav_put_float(buf, 40, vd);
  205. _mav_put_float(buf, 44, speed_accuracy);
  206. _mav_put_float(buf, 48, horiz_accuracy);
  207. _mav_put_float(buf, 52, vert_accuracy);
  208. _mav_put_uint16_t(buf, 56, ignore_flags);
  209. _mav_put_uint16_t(buf, 58, time_week);
  210. _mav_put_uint8_t(buf, 60, gps_id);
  211. _mav_put_uint8_t(buf, 61, fix_type);
  212. _mav_put_uint8_t(buf, 62, satellites_visible);
  213. _mav_put_uint16_t(buf, 63, yaw);
  214. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
  215. #else
  216. mavlink_gps_input_t packet;
  217. packet.time_usec = time_usec;
  218. packet.time_week_ms = time_week_ms;
  219. packet.lat = lat;
  220. packet.lon = lon;
  221. packet.alt = alt;
  222. packet.hdop = hdop;
  223. packet.vdop = vdop;
  224. packet.vn = vn;
  225. packet.ve = ve;
  226. packet.vd = vd;
  227. packet.speed_accuracy = speed_accuracy;
  228. packet.horiz_accuracy = horiz_accuracy;
  229. packet.vert_accuracy = vert_accuracy;
  230. packet.ignore_flags = ignore_flags;
  231. packet.time_week = time_week;
  232. packet.gps_id = gps_id;
  233. packet.fix_type = fix_type;
  234. packet.satellites_visible = satellites_visible;
  235. packet.yaw = yaw;
  236. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
  237. #endif
  238. msg->msgid = MAVLINK_MSG_ID_GPS_INPUT;
  239. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  240. }
  241. /**
  242. * @brief Encode a gps_input struct
  243. *
  244. * @param system_id ID of this system
  245. * @param component_id ID of this component (e.g. 200 for IMU)
  246. * @param msg The MAVLink message to compress the data into
  247. * @param gps_input C-struct to read the message contents from
  248. */
  249. static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
  250. {
  251. return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
  252. }
  253. /**
  254. * @brief Encode a gps_input struct on a channel
  255. *
  256. * @param system_id ID of this system
  257. * @param component_id ID of this component (e.g. 200 for IMU)
  258. * @param chan The MAVLink channel this message will be sent over
  259. * @param msg The MAVLink message to compress the data into
  260. * @param gps_input C-struct to read the message contents from
  261. */
  262. static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
  263. {
  264. return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
  265. }
  266. /**
  267. * @brief Send a gps_input message
  268. * @param chan MAVLink channel to send the message
  269. *
  270. * @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.
  271. * @param gps_id ID of the GPS for multiple GPS inputs
  272. * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
  273. * @param time_week_ms [ms] GPS time (from start of GPS week)
  274. * @param time_week GPS week number
  275. * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
  276. * @param lat [degE7] Latitude (WGS84)
  277. * @param lon [degE7] Longitude (WGS84)
  278. * @param alt [m] Altitude (MSL). Positive for up.
  279. * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
  280. * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
  281. * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
  282. * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
  283. * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
  284. * @param speed_accuracy [m/s] GPS speed accuracy
  285. * @param horiz_accuracy [m] GPS horizontal accuracy
  286. * @param vert_accuracy [m] GPS vertical accuracy
  287. * @param satellites_visible Number of satellites visible.
  288. * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  289. */
  290. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  291. static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
  292. {
  293. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  294. char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
  295. _mav_put_uint64_t(buf, 0, time_usec);
  296. _mav_put_uint32_t(buf, 8, time_week_ms);
  297. _mav_put_int32_t(buf, 12, lat);
  298. _mav_put_int32_t(buf, 16, lon);
  299. _mav_put_float(buf, 20, alt);
  300. _mav_put_float(buf, 24, hdop);
  301. _mav_put_float(buf, 28, vdop);
  302. _mav_put_float(buf, 32, vn);
  303. _mav_put_float(buf, 36, ve);
  304. _mav_put_float(buf, 40, vd);
  305. _mav_put_float(buf, 44, speed_accuracy);
  306. _mav_put_float(buf, 48, horiz_accuracy);
  307. _mav_put_float(buf, 52, vert_accuracy);
  308. _mav_put_uint16_t(buf, 56, ignore_flags);
  309. _mav_put_uint16_t(buf, 58, time_week);
  310. _mav_put_uint8_t(buf, 60, gps_id);
  311. _mav_put_uint8_t(buf, 61, fix_type);
  312. _mav_put_uint8_t(buf, 62, satellites_visible);
  313. _mav_put_uint16_t(buf, 63, yaw);
  314. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  315. #else
  316. mavlink_gps_input_t packet;
  317. packet.time_usec = time_usec;
  318. packet.time_week_ms = time_week_ms;
  319. packet.lat = lat;
  320. packet.lon = lon;
  321. packet.alt = alt;
  322. packet.hdop = hdop;
  323. packet.vdop = vdop;
  324. packet.vn = vn;
  325. packet.ve = ve;
  326. packet.vd = vd;
  327. packet.speed_accuracy = speed_accuracy;
  328. packet.horiz_accuracy = horiz_accuracy;
  329. packet.vert_accuracy = vert_accuracy;
  330. packet.ignore_flags = ignore_flags;
  331. packet.time_week = time_week;
  332. packet.gps_id = gps_id;
  333. packet.fix_type = fix_type;
  334. packet.satellites_visible = satellites_visible;
  335. packet.yaw = yaw;
  336. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  337. #endif
  338. }
  339. /**
  340. * @brief Send a gps_input message
  341. * @param chan MAVLink channel to send the message
  342. * @param struct The MAVLink struct to serialize
  343. */
  344. static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input)
  345. {
  346. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  347. mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
  348. #else
  349. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  350. #endif
  351. }
  352. #if MAVLINK_MSG_ID_GPS_INPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  353. /*
  354. This variant of _send() can be used to save stack space by re-using
  355. memory from the receive buffer. The caller provides a
  356. mavlink_message_t which is the size of a full mavlink message. This
  357. is usually the receive buffer for the channel, and allows a reply to an
  358. incoming message with minimum stack space usage.
  359. */
  360. static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
  361. {
  362. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  363. char *buf = (char *)msgbuf;
  364. _mav_put_uint64_t(buf, 0, time_usec);
  365. _mav_put_uint32_t(buf, 8, time_week_ms);
  366. _mav_put_int32_t(buf, 12, lat);
  367. _mav_put_int32_t(buf, 16, lon);
  368. _mav_put_float(buf, 20, alt);
  369. _mav_put_float(buf, 24, hdop);
  370. _mav_put_float(buf, 28, vdop);
  371. _mav_put_float(buf, 32, vn);
  372. _mav_put_float(buf, 36, ve);
  373. _mav_put_float(buf, 40, vd);
  374. _mav_put_float(buf, 44, speed_accuracy);
  375. _mav_put_float(buf, 48, horiz_accuracy);
  376. _mav_put_float(buf, 52, vert_accuracy);
  377. _mav_put_uint16_t(buf, 56, ignore_flags);
  378. _mav_put_uint16_t(buf, 58, time_week);
  379. _mav_put_uint8_t(buf, 60, gps_id);
  380. _mav_put_uint8_t(buf, 61, fix_type);
  381. _mav_put_uint8_t(buf, 62, satellites_visible);
  382. _mav_put_uint16_t(buf, 63, yaw);
  383. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  384. #else
  385. mavlink_gps_input_t *packet = (mavlink_gps_input_t *)msgbuf;
  386. packet->time_usec = time_usec;
  387. packet->time_week_ms = time_week_ms;
  388. packet->lat = lat;
  389. packet->lon = lon;
  390. packet->alt = alt;
  391. packet->hdop = hdop;
  392. packet->vdop = vdop;
  393. packet->vn = vn;
  394. packet->ve = ve;
  395. packet->vd = vd;
  396. packet->speed_accuracy = speed_accuracy;
  397. packet->horiz_accuracy = horiz_accuracy;
  398. packet->vert_accuracy = vert_accuracy;
  399. packet->ignore_flags = ignore_flags;
  400. packet->time_week = time_week;
  401. packet->gps_id = gps_id;
  402. packet->fix_type = fix_type;
  403. packet->satellites_visible = satellites_visible;
  404. packet->yaw = yaw;
  405. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
  406. #endif
  407. }
  408. #endif
  409. #endif
  410. // MESSAGE GPS_INPUT UNPACKING
  411. /**
  412. * @brief Get field time_usec from gps_input message
  413. *
  414. * @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.
  415. */
  416. static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg)
  417. {
  418. return _MAV_RETURN_uint64_t(msg, 0);
  419. }
  420. /**
  421. * @brief Get field gps_id from gps_input message
  422. *
  423. * @return ID of the GPS for multiple GPS inputs
  424. */
  425. static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg)
  426. {
  427. return _MAV_RETURN_uint8_t(msg, 60);
  428. }
  429. /**
  430. * @brief Get field ignore_flags from gps_input message
  431. *
  432. * @return Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
  433. */
  434. static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg)
  435. {
  436. return _MAV_RETURN_uint16_t(msg, 56);
  437. }
  438. /**
  439. * @brief Get field time_week_ms from gps_input message
  440. *
  441. * @return [ms] GPS time (from start of GPS week)
  442. */
  443. static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg)
  444. {
  445. return _MAV_RETURN_uint32_t(msg, 8);
  446. }
  447. /**
  448. * @brief Get field time_week from gps_input message
  449. *
  450. * @return GPS week number
  451. */
  452. static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg)
  453. {
  454. return _MAV_RETURN_uint16_t(msg, 58);
  455. }
  456. /**
  457. * @brief Get field fix_type from gps_input message
  458. *
  459. * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
  460. */
  461. static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg)
  462. {
  463. return _MAV_RETURN_uint8_t(msg, 61);
  464. }
  465. /**
  466. * @brief Get field lat from gps_input message
  467. *
  468. * @return [degE7] Latitude (WGS84)
  469. */
  470. static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg)
  471. {
  472. return _MAV_RETURN_int32_t(msg, 12);
  473. }
  474. /**
  475. * @brief Get field lon from gps_input message
  476. *
  477. * @return [degE7] Longitude (WGS84)
  478. */
  479. static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_int32_t(msg, 16);
  482. }
  483. /**
  484. * @brief Get field alt from gps_input message
  485. *
  486. * @return [m] Altitude (MSL). Positive for up.
  487. */
  488. static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_float(msg, 20);
  491. }
  492. /**
  493. * @brief Get field hdop from gps_input message
  494. *
  495. * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
  496. */
  497. static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_float(msg, 24);
  500. }
  501. /**
  502. * @brief Get field vdop from gps_input message
  503. *
  504. * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
  505. */
  506. static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_float(msg, 28);
  509. }
  510. /**
  511. * @brief Get field vn from gps_input message
  512. *
  513. * @return [m/s] GPS velocity in north direction in earth-fixed NED frame
  514. */
  515. static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_float(msg, 32);
  518. }
  519. /**
  520. * @brief Get field ve from gps_input message
  521. *
  522. * @return [m/s] GPS velocity in east direction in earth-fixed NED frame
  523. */
  524. static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_float(msg, 36);
  527. }
  528. /**
  529. * @brief Get field vd from gps_input message
  530. *
  531. * @return [m/s] GPS velocity in down direction in earth-fixed NED frame
  532. */
  533. static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_float(msg, 40);
  536. }
  537. /**
  538. * @brief Get field speed_accuracy from gps_input message
  539. *
  540. * @return [m/s] GPS speed accuracy
  541. */
  542. static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_float(msg, 44);
  545. }
  546. /**
  547. * @brief Get field horiz_accuracy from gps_input message
  548. *
  549. * @return [m] GPS horizontal accuracy
  550. */
  551. static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_float(msg, 48);
  554. }
  555. /**
  556. * @brief Get field vert_accuracy from gps_input message
  557. *
  558. * @return [m] GPS vertical accuracy
  559. */
  560. static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_float(msg, 52);
  563. }
  564. /**
  565. * @brief Get field satellites_visible from gps_input message
  566. *
  567. * @return Number of satellites visible.
  568. */
  569. static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_uint8_t(msg, 62);
  572. }
  573. /**
  574. * @brief Get field yaw from gps_input message
  575. *
  576. * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
  577. */
  578. static inline uint16_t mavlink_msg_gps_input_get_yaw(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_uint16_t(msg, 63);
  581. }
  582. /**
  583. * @brief Decode a gps_input message into a struct
  584. *
  585. * @param msg The message to decode
  586. * @param gps_input C-struct to decode the message contents into
  587. */
  588. static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, mavlink_gps_input_t* gps_input)
  589. {
  590. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  591. gps_input->time_usec = mavlink_msg_gps_input_get_time_usec(msg);
  592. gps_input->time_week_ms = mavlink_msg_gps_input_get_time_week_ms(msg);
  593. gps_input->lat = mavlink_msg_gps_input_get_lat(msg);
  594. gps_input->lon = mavlink_msg_gps_input_get_lon(msg);
  595. gps_input->alt = mavlink_msg_gps_input_get_alt(msg);
  596. gps_input->hdop = mavlink_msg_gps_input_get_hdop(msg);
  597. gps_input->vdop = mavlink_msg_gps_input_get_vdop(msg);
  598. gps_input->vn = mavlink_msg_gps_input_get_vn(msg);
  599. gps_input->ve = mavlink_msg_gps_input_get_ve(msg);
  600. gps_input->vd = mavlink_msg_gps_input_get_vd(msg);
  601. gps_input->speed_accuracy = mavlink_msg_gps_input_get_speed_accuracy(msg);
  602. gps_input->horiz_accuracy = mavlink_msg_gps_input_get_horiz_accuracy(msg);
  603. gps_input->vert_accuracy = mavlink_msg_gps_input_get_vert_accuracy(msg);
  604. gps_input->ignore_flags = mavlink_msg_gps_input_get_ignore_flags(msg);
  605. gps_input->time_week = mavlink_msg_gps_input_get_time_week(msg);
  606. gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg);
  607. gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg);
  608. gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg);
  609. gps_input->yaw = mavlink_msg_gps_input_get_yaw(msg);
  610. #else
  611. uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN;
  612. memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN);
  613. memcpy(gps_input, _MAV_PAYLOAD(msg), len);
  614. #endif
  615. }