mavlink_msg_gps_status.h 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394
  1. #pragma once
  2. // MESSAGE GPS_STATUS PACKING
  3. #define MAVLINK_MSG_ID_GPS_STATUS 25
  4. typedef struct __mavlink_gps_status_t {
  5. uint8_t satellites_visible; /*< Number of satellites visible*/
  6. uint8_t satellite_prn[20]; /*< Global satellite ID*/
  7. uint8_t satellite_used[20]; /*< 0: Satellite not used, 1: used for localization*/
  8. uint8_t satellite_elevation[20]; /*< [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite*/
  9. uint8_t satellite_azimuth[20]; /*< [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.*/
  10. uint8_t satellite_snr[20]; /*< [dB] Signal to noise ratio of satellite*/
  11. } mavlink_gps_status_t;
  12. #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
  13. #define MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN 101
  14. #define MAVLINK_MSG_ID_25_LEN 101
  15. #define MAVLINK_MSG_ID_25_MIN_LEN 101
  16. #define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
  17. #define MAVLINK_MSG_ID_25_CRC 23
  18. #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
  19. #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
  20. #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
  21. #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
  22. #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
  23. #if MAVLINK_COMMAND_24BIT
  24. #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
  25. 25, \
  26. "GPS_STATUS", \
  27. 6, \
  28. { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
  29. { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
  30. { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
  31. { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
  32. { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
  33. { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
  34. } \
  35. }
  36. #else
  37. #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
  38. "GPS_STATUS", \
  39. 6, \
  40. { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
  41. { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
  42. { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
  43. { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
  44. { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
  45. { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
  46. } \
  47. }
  48. #endif
  49. /**
  50. * @brief Pack a gps_status message
  51. * @param system_id ID of this system
  52. * @param component_id ID of this component (e.g. 200 for IMU)
  53. * @param msg The MAVLink message to compress the data into
  54. *
  55. * @param satellites_visible Number of satellites visible
  56. * @param satellite_prn Global satellite ID
  57. * @param satellite_used 0: Satellite not used, 1: used for localization
  58. * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
  59. * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
  60. * @param satellite_snr [dB] Signal to noise ratio of satellite
  61. * @return length of the message in bytes (excluding serial stream start sign)
  62. */
  63. static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  64. uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
  65. {
  66. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  67. char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
  68. _mav_put_uint8_t(buf, 0, satellites_visible);
  69. _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
  70. _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
  71. _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
  72. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
  73. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
  74. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  75. #else
  76. mavlink_gps_status_t packet;
  77. packet.satellites_visible = satellites_visible;
  78. mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
  79. mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
  80. mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
  81. mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
  82. mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
  83. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  84. #endif
  85. msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
  86. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  87. }
  88. /**
  89. * @brief Pack a gps_status message
  90. * @param system_id ID of this system
  91. * @param component_id ID of this component (e.g. 200 for IMU)
  92. * @param status MAVLink status structure
  93. * @param msg The MAVLink message to compress the data into
  94. *
  95. * @param satellites_visible Number of satellites visible
  96. * @param satellite_prn Global satellite ID
  97. * @param satellite_used 0: Satellite not used, 1: used for localization
  98. * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
  99. * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
  100. * @param satellite_snr [dB] Signal to noise ratio of satellite
  101. * @return length of the message in bytes (excluding serial stream start sign)
  102. */
  103. static inline uint16_t mavlink_msg_gps_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
  104. uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
  105. {
  106. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  107. char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
  108. _mav_put_uint8_t(buf, 0, satellites_visible);
  109. _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
  110. _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
  111. _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
  112. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
  113. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
  114. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  115. #else
  116. mavlink_gps_status_t packet;
  117. packet.satellites_visible = satellites_visible;
  118. mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
  119. mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
  120. mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
  121. mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
  122. mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
  123. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  124. #endif
  125. msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
  126. #if MAVLINK_CRC_EXTRA
  127. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  128. #else
  129. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  130. #endif
  131. }
  132. /**
  133. * @brief Pack a gps_status message on a channel
  134. * @param system_id ID of this system
  135. * @param component_id ID of this component (e.g. 200 for IMU)
  136. * @param chan The MAVLink channel this message will be sent over
  137. * @param msg The MAVLink message to compress the data into
  138. * @param satellites_visible Number of satellites visible
  139. * @param satellite_prn Global satellite ID
  140. * @param satellite_used 0: Satellite not used, 1: used for localization
  141. * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
  142. * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
  143. * @param satellite_snr [dB] Signal to noise ratio of satellite
  144. * @return length of the message in bytes (excluding serial stream start sign)
  145. */
  146. static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  147. mavlink_message_t* msg,
  148. uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr)
  149. {
  150. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  151. char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
  152. _mav_put_uint8_t(buf, 0, satellites_visible);
  153. _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
  154. _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
  155. _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
  156. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
  157. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
  158. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  159. #else
  160. mavlink_gps_status_t packet;
  161. packet.satellites_visible = satellites_visible;
  162. mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
  163. mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
  164. mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
  165. mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
  166. mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
  167. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  168. #endif
  169. msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
  170. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  171. }
  172. /**
  173. * @brief Encode a gps_status struct
  174. *
  175. * @param system_id ID of this system
  176. * @param component_id ID of this component (e.g. 200 for IMU)
  177. * @param msg The MAVLink message to compress the data into
  178. * @param gps_status C-struct to read the message contents from
  179. */
  180. static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
  181. {
  182. return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
  183. }
  184. /**
  185. * @brief Encode a gps_status struct on a channel
  186. *
  187. * @param system_id ID of this system
  188. * @param component_id ID of this component (e.g. 200 for IMU)
  189. * @param chan The MAVLink channel this message will be sent over
  190. * @param msg The MAVLink message to compress the data into
  191. * @param gps_status C-struct to read the message contents from
  192. */
  193. static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
  194. {
  195. return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
  196. }
  197. /**
  198. * @brief Encode a gps_status struct with provided status structure
  199. *
  200. * @param system_id ID of this system
  201. * @param component_id ID of this component (e.g. 200 for IMU)
  202. * @param status MAVLink status structure
  203. * @param msg The MAVLink message to compress the data into
  204. * @param gps_status C-struct to read the message contents from
  205. */
  206. static inline uint16_t mavlink_msg_gps_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
  207. {
  208. return mavlink_msg_gps_status_pack_status(system_id, component_id, _status, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
  209. }
  210. /**
  211. * @brief Send a gps_status message
  212. * @param chan MAVLink channel to send the message
  213. *
  214. * @param satellites_visible Number of satellites visible
  215. * @param satellite_prn Global satellite ID
  216. * @param satellite_used 0: Satellite not used, 1: used for localization
  217. * @param satellite_elevation [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
  218. * @param satellite_azimuth [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
  219. * @param satellite_snr [dB] Signal to noise ratio of satellite
  220. */
  221. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  222. static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
  223. {
  224. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  225. char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN];
  226. _mav_put_uint8_t(buf, 0, satellites_visible);
  227. _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
  228. _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
  229. _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
  230. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
  231. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
  232. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  233. #else
  234. mavlink_gps_status_t packet;
  235. packet.satellites_visible = satellites_visible;
  236. mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
  237. mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
  238. mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
  239. mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
  240. mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
  241. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  242. #endif
  243. }
  244. /**
  245. * @brief Send a gps_status message
  246. * @param chan MAVLink channel to send the message
  247. * @param struct The MAVLink struct to serialize
  248. */
  249. static inline void mavlink_msg_gps_status_send_struct(mavlink_channel_t chan, const mavlink_gps_status_t* gps_status)
  250. {
  251. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  252. mavlink_msg_gps_status_send(chan, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
  253. #else
  254. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)gps_status, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  255. #endif
  256. }
  257. #if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  258. /*
  259. This variant of _send() can be used to save stack space by re-using
  260. memory from the receive buffer. The caller provides a
  261. mavlink_message_t which is the size of a full mavlink message. This
  262. is usually the receive buffer for the channel, and allows a reply to an
  263. incoming message with minimum stack space usage.
  264. */
  265. static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
  266. {
  267. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  268. char *buf = (char *)msgbuf;
  269. _mav_put_uint8_t(buf, 0, satellites_visible);
  270. _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
  271. _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
  272. _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
  273. _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
  274. _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
  275. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  276. #else
  277. mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf;
  278. packet->satellites_visible = satellites_visible;
  279. mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20);
  280. mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20);
  281. mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
  282. mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
  283. mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20);
  284. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_MIN_LEN, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
  285. #endif
  286. }
  287. #endif
  288. #endif
  289. // MESSAGE GPS_STATUS UNPACKING
  290. /**
  291. * @brief Get field satellites_visible from gps_status message
  292. *
  293. * @return Number of satellites visible
  294. */
  295. static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
  296. {
  297. return _MAV_RETURN_uint8_t(msg, 0);
  298. }
  299. /**
  300. * @brief Get field satellite_prn from gps_status message
  301. *
  302. * @return Global satellite ID
  303. */
  304. static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
  305. {
  306. return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1);
  307. }
  308. /**
  309. * @brief Get field satellite_used from gps_status message
  310. *
  311. * @return 0: Satellite not used, 1: used for localization
  312. */
  313. static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
  314. {
  315. return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21);
  316. }
  317. /**
  318. * @brief Get field satellite_elevation from gps_status message
  319. *
  320. * @return [deg] Elevation (0: right on top of receiver, 90: on the horizon) of satellite
  321. */
  322. static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
  323. {
  324. return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41);
  325. }
  326. /**
  327. * @brief Get field satellite_azimuth from gps_status message
  328. *
  329. * @return [deg] Direction of satellite, 0: 0 deg, 255: 360 deg.
  330. */
  331. static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
  332. {
  333. return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61);
  334. }
  335. /**
  336. * @brief Get field satellite_snr from gps_status message
  337. *
  338. * @return [dB] Signal to noise ratio of satellite
  339. */
  340. static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
  341. {
  342. return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81);
  343. }
  344. /**
  345. * @brief Decode a gps_status message into a struct
  346. *
  347. * @param msg The message to decode
  348. * @param gps_status C-struct to decode the message contents into
  349. */
  350. static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
  351. {
  352. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  353. gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
  354. mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
  355. mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
  356. mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
  357. mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
  358. mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
  359. #else
  360. uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GPS_STATUS_LEN;
  361. memset(gps_status, 0, MAVLINK_MSG_ID_GPS_STATUS_LEN);
  362. memcpy(gps_status, _MAV_PAYLOAD(msg), len);
  363. #endif
  364. }