1 // MESSAGE GPS_STATUS PACKING
3 #define MAVLINK_MSG_ID_GPS_STATUS 25
5 typedef struct __mavlink_gps_status_t
{
6 uint8_t satellites_visible
; ///< Number of satellites visible
7 uint8_t satellite_prn
[20]; ///< Global satellite ID
8 uint8_t satellite_used
[20]; ///< 0: Satellite not used, 1: used for localization
9 uint8_t satellite_elevation
[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
10 uint8_t satellite_azimuth
[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
11 uint8_t satellite_snr
[20]; ///< Signal to noise ratio of satellite
12 } mavlink_gps_status_t
;
14 #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
15 #define MAVLINK_MSG_ID_25_LEN 101
17 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
18 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
19 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
20 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
21 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
23 #define MAVLINK_MESSAGE_INFO_GPS_STATUS \
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) }, \
39 * @brief Pack a gps_status message
40 * @param system_id ID of this system
41 * @param component_id ID of this component (e.g. 200 for IMU)
42 * @param msg The MAVLink message to compress the data into
44 * @param satellites_visible Number of satellites visible
45 * @param satellite_prn Global satellite ID
46 * @param satellite_used 0: Satellite not used, 1: used for localization
47 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
48 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
49 * @param satellite_snr Signal to noise ratio of satellite
50 * @return length of the message in bytes (excluding serial stream start sign)
52 static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
53 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
)
55 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
57 _mav_put_uint8_t(buf
, 0, satellites_visible
);
58 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
59 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
60 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
61 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
62 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
63 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 101);
65 mavlink_gps_status_t packet
;
66 packet
.satellites_visible
= satellites_visible
;
67 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t) * 20);
68 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t) * 20);
69 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t) * 20);
70 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t) * 20);
71 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t) * 20);
72 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 101);
75 msg
->msgid
= MAVLINK_MSG_ID_GPS_STATUS
;
76 return mavlink_finalize_message(msg
, system_id
, component_id
, 101, 23);
80 * @brief Pack a gps_status message on a channel
81 * @param system_id ID of this system
82 * @param component_id ID of this component (e.g. 200 for IMU)
83 * @param chan The MAVLink channel this message was sent over
84 * @param msg The MAVLink message to compress the data into
85 * @param satellites_visible Number of satellites visible
86 * @param satellite_prn Global satellite ID
87 * @param satellite_used 0: Satellite not used, 1: used for localization
88 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
89 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
90 * @param satellite_snr Signal to noise ratio of satellite
91 * @return length of the message in bytes (excluding serial stream start sign)
93 static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
94 mavlink_message_t
*msg
,
95 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
)
97 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 _mav_put_uint8_t(buf
, 0, satellites_visible
);
100 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
101 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
102 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
103 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
104 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
105 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 101);
107 mavlink_gps_status_t packet
;
108 packet
.satellites_visible
= satellites_visible
;
109 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t) * 20);
110 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t) * 20);
111 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t) * 20);
112 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t) * 20);
113 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t) * 20);
114 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 101);
117 msg
->msgid
= MAVLINK_MSG_ID_GPS_STATUS
;
118 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 101, 23);
122 * @brief Encode a gps_status struct into a message
124 * @param system_id ID of this system
125 * @param component_id ID of this component (e.g. 200 for IMU)
126 * @param msg The MAVLink message to compress the data into
127 * @param gps_status C-struct to read the message contents from
129 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
)
131 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
);
135 * @brief Send a gps_status message
136 * @param chan MAVLink channel to send the message
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 Elevation (0: right on top of receiver, 90: on the horizon) of satellite
142 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
143 * @param satellite_snr Signal to noise ratio of satellite
145 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
147 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
)
149 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
151 _mav_put_uint8_t(buf
, 0, satellites_visible
);
152 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
153 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
154 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
155 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
156 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
157 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, buf
, 101, 23);
159 mavlink_gps_status_t packet
;
160 packet
.satellites_visible
= satellites_visible
;
161 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t) * 20);
162 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t) * 20);
163 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t) * 20);
164 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t) * 20);
165 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t) * 20);
166 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, (const char *)&packet
, 101, 23);
170 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
172 // MESSAGE GPS_STATUS UNPACKING
176 * @brief Get field satellites_visible from gps_status message
178 * @return Number of satellites visible
180 static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t
*msg
)
182 return _MAV_RETURN_uint8_t(msg
, 0);
186 * @brief Get field satellite_prn from gps_status message
188 * @return Global satellite ID
190 static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t
*msg
, uint8_t *satellite_prn
)
192 return _MAV_RETURN_uint8_t_array(msg
, satellite_prn
, 20, 1);
196 * @brief Get field satellite_used from gps_status message
198 * @return 0: Satellite not used, 1: used for localization
200 static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t
*msg
, uint8_t *satellite_used
)
202 return _MAV_RETURN_uint8_t_array(msg
, satellite_used
, 20, 21);
206 * @brief Get field satellite_elevation from gps_status message
208 * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
210 static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t
*msg
, uint8_t *satellite_elevation
)
212 return _MAV_RETURN_uint8_t_array(msg
, satellite_elevation
, 20, 41);
216 * @brief Get field satellite_azimuth from gps_status message
218 * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
220 static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t
*msg
, uint8_t *satellite_azimuth
)
222 return _MAV_RETURN_uint8_t_array(msg
, satellite_azimuth
, 20, 61);
226 * @brief Get field satellite_snr from gps_status message
228 * @return Signal to noise ratio of satellite
230 static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t
*msg
, uint8_t *satellite_snr
)
232 return _MAV_RETURN_uint8_t_array(msg
, satellite_snr
, 20, 81);
236 * @brief Decode a gps_status message into a struct
238 * @param msg The message to decode
239 * @param gps_status C-struct to decode the message contents into
241 static inline void mavlink_msg_gps_status_decode(const mavlink_message_t
*msg
, mavlink_gps_status_t
*gps_status
)
243 #if MAVLINK_NEED_BYTE_SWAP
244 gps_status
->satellites_visible
= mavlink_msg_gps_status_get_satellites_visible(msg
);
245 mavlink_msg_gps_status_get_satellite_prn(msg
, gps_status
->satellite_prn
);
246 mavlink_msg_gps_status_get_satellite_used(msg
, gps_status
->satellite_used
);
247 mavlink_msg_gps_status_get_satellite_elevation(msg
, gps_status
->satellite_elevation
);
248 mavlink_msg_gps_status_get_satellite_azimuth(msg
, gps_status
->satellite_azimuth
);
249 mavlink_msg_gps_status_get_satellite_snr(msg
, gps_status
->satellite_snr
);
251 memcpy(gps_status
, _MAV_PAYLOAD(msg
), 101);