1 // MESSAGE GPS_STATUS PACKING
3 #define MAVLINK_MSG_ID_GPS_STATUS 25
5 typedef struct __mavlink_gps_status_t
7 uint8_t satellites_visible
; ///< Number of satellites visible
8 uint8_t satellite_prn
[20]; ///< Global satellite ID
9 uint8_t satellite_used
[20]; ///< 0: Satellite not used, 1: used for localization
10 uint8_t satellite_elevation
[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
11 uint8_t satellite_azimuth
[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
12 uint8_t satellite_snr
[20]; ///< Signal to noise ratio of satellite
13 } mavlink_gps_status_t
;
15 #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
16 #define MAVLINK_MSG_ID_25_LEN 101
18 #define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
19 #define MAVLINK_MSG_ID_25_CRC 23
21 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
22 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
23 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
24 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
25 #define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
27 #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
30 { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
31 { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
32 { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
33 { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
34 { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
35 { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
41 * @brief Pack a gps_status message
42 * @param system_id ID of this system
43 * @param component_id ID of this component (e.g. 200 for IMU)
44 * @param msg The MAVLink message to compress the data into
46 * @param satellites_visible Number of satellites visible
47 * @param satellite_prn Global satellite ID
48 * @param satellite_used 0: Satellite not used, 1: used for localization
49 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
50 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
51 * @param satellite_snr Signal to noise ratio of satellite
52 * @return length of the message in bytes (excluding serial stream start sign)
54 static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
55 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
)
57 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
58 char buf
[MAVLINK_MSG_ID_GPS_STATUS_LEN
];
59 _mav_put_uint8_t(buf
, 0, satellites_visible
);
60 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
61 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
62 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
63 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
64 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
65 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
67 mavlink_gps_status_t packet
;
68 packet
.satellites_visible
= satellites_visible
;
69 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t)*20);
70 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t)*20);
71 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t)*20);
72 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t)*20);
73 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t)*20);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
77 msg
->msgid
= MAVLINK_MSG_ID_GPS_STATUS
;
79 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
81 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
86 * @brief Pack a gps_status message on a channel
87 * @param system_id ID of this system
88 * @param component_id ID of this component (e.g. 200 for IMU)
89 * @param chan The MAVLink channel this message will be sent over
90 * @param msg The MAVLink message to compress the data into
91 * @param satellites_visible Number of satellites visible
92 * @param satellite_prn Global satellite ID
93 * @param satellite_used 0: Satellite not used, 1: used for localization
94 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
95 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
96 * @param satellite_snr Signal to noise ratio of satellite
97 * @return length of the message in bytes (excluding serial stream start sign)
99 static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
100 mavlink_message_t
* msg
,
101 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
)
103 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
104 char buf
[MAVLINK_MSG_ID_GPS_STATUS_LEN
];
105 _mav_put_uint8_t(buf
, 0, satellites_visible
);
106 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
107 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
108 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
109 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
110 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
111 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
113 mavlink_gps_status_t packet
;
114 packet
.satellites_visible
= satellites_visible
;
115 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t)*20);
116 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t)*20);
117 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t)*20);
118 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t)*20);
119 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t)*20);
120 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
123 msg
->msgid
= MAVLINK_MSG_ID_GPS_STATUS
;
124 #if MAVLINK_CRC_EXTRA
125 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
127 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
132 * @brief Encode a gps_status struct
134 * @param system_id ID of this system
135 * @param component_id ID of this component (e.g. 200 for IMU)
136 * @param msg The MAVLink message to compress the data into
137 * @param gps_status C-struct to read the message contents from
139 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
)
141 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
);
145 * @brief Encode a gps_status struct on a channel
147 * @param system_id ID of this system
148 * @param component_id ID of this component (e.g. 200 for IMU)
149 * @param chan The MAVLink channel this message will be sent over
150 * @param msg The MAVLink message to compress the data into
151 * @param gps_status C-struct to read the message contents from
153 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
)
155 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
);
159 * @brief Send a gps_status message
160 * @param chan MAVLink channel to send the message
162 * @param satellites_visible Number of satellites visible
163 * @param satellite_prn Global satellite ID
164 * @param satellite_used 0: Satellite not used, 1: used for localization
165 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
166 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
167 * @param satellite_snr Signal to noise ratio of satellite
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 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
)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
174 char buf
[MAVLINK_MSG_ID_GPS_STATUS_LEN
];
175 _mav_put_uint8_t(buf
, 0, satellites_visible
);
176 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
177 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
178 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
179 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
180 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
181 #if MAVLINK_CRC_EXTRA
182 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
184 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
187 mavlink_gps_status_t packet
;
188 packet
.satellites_visible
= satellites_visible
;
189 mav_array_memcpy(packet
.satellite_prn
, satellite_prn
, sizeof(uint8_t)*20);
190 mav_array_memcpy(packet
.satellite_used
, satellite_used
, sizeof(uint8_t)*20);
191 mav_array_memcpy(packet
.satellite_elevation
, satellite_elevation
, sizeof(uint8_t)*20);
192 mav_array_memcpy(packet
.satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t)*20);
193 mav_array_memcpy(packet
.satellite_snr
, satellite_snr
, sizeof(uint8_t)*20);
194 #if MAVLINK_CRC_EXTRA
195 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, (const char *)&packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
197 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, (const char *)&packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
202 #if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
204 This varient of _send() can be used to save stack space by re-using
205 memory from the receive buffer. The caller provides a
206 mavlink_message_t which is the size of a full mavlink message. This
207 is usually the receive buffer for the channel, and allows a reply to an
208 incoming message with minimum stack space usage.
210 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
)
212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 char *buf
= (char *)msgbuf
;
214 _mav_put_uint8_t(buf
, 0, satellites_visible
);
215 _mav_put_uint8_t_array(buf
, 1, satellite_prn
, 20);
216 _mav_put_uint8_t_array(buf
, 21, satellite_used
, 20);
217 _mav_put_uint8_t_array(buf
, 41, satellite_elevation
, 20);
218 _mav_put_uint8_t_array(buf
, 61, satellite_azimuth
, 20);
219 _mav_put_uint8_t_array(buf
, 81, satellite_snr
, 20);
220 #if MAVLINK_CRC_EXTRA
221 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
223 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, buf
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
226 mavlink_gps_status_t
*packet
= (mavlink_gps_status_t
*)msgbuf
;
227 packet
->satellites_visible
= satellites_visible
;
228 mav_array_memcpy(packet
->satellite_prn
, satellite_prn
, sizeof(uint8_t)*20);
229 mav_array_memcpy(packet
->satellite_used
, satellite_used
, sizeof(uint8_t)*20);
230 mav_array_memcpy(packet
->satellite_elevation
, satellite_elevation
, sizeof(uint8_t)*20);
231 mav_array_memcpy(packet
->satellite_azimuth
, satellite_azimuth
, sizeof(uint8_t)*20);
232 mav_array_memcpy(packet
->satellite_snr
, satellite_snr
, sizeof(uint8_t)*20);
233 #if MAVLINK_CRC_EXTRA
234 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, (const char *)packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
, MAVLINK_MSG_ID_GPS_STATUS_CRC
);
236 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_STATUS
, (const char *)packet
, MAVLINK_MSG_ID_GPS_STATUS_LEN
);
244 // MESSAGE GPS_STATUS UNPACKING
248 * @brief Get field satellites_visible from gps_status message
250 * @return Number of satellites visible
252 static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t
* msg
)
254 return _MAV_RETURN_uint8_t(msg
, 0);
258 * @brief Get field satellite_prn from gps_status message
260 * @return Global satellite ID
262 static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t
* msg
, uint8_t *satellite_prn
)
264 return _MAV_RETURN_uint8_t_array(msg
, satellite_prn
, 20, 1);
268 * @brief Get field satellite_used from gps_status message
270 * @return 0: Satellite not used, 1: used for localization
272 static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t
* msg
, uint8_t *satellite_used
)
274 return _MAV_RETURN_uint8_t_array(msg
, satellite_used
, 20, 21);
278 * @brief Get field satellite_elevation from gps_status message
280 * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
282 static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t
* msg
, uint8_t *satellite_elevation
)
284 return _MAV_RETURN_uint8_t_array(msg
, satellite_elevation
, 20, 41);
288 * @brief Get field satellite_azimuth from gps_status message
290 * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
292 static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t
* msg
, uint8_t *satellite_azimuth
)
294 return _MAV_RETURN_uint8_t_array(msg
, satellite_azimuth
, 20, 61);
298 * @brief Get field satellite_snr from gps_status message
300 * @return Signal to noise ratio of satellite
302 static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t
* msg
, uint8_t *satellite_snr
)
304 return _MAV_RETURN_uint8_t_array(msg
, satellite_snr
, 20, 81);
308 * @brief Decode a gps_status message into a struct
310 * @param msg The message to decode
311 * @param gps_status C-struct to decode the message contents into
313 static inline void mavlink_msg_gps_status_decode(const mavlink_message_t
* msg
, mavlink_gps_status_t
* gps_status
)
315 #if MAVLINK_NEED_BYTE_SWAP
316 gps_status
->satellites_visible
= mavlink_msg_gps_status_get_satellites_visible(msg
);
317 mavlink_msg_gps_status_get_satellite_prn(msg
, gps_status
->satellite_prn
);
318 mavlink_msg_gps_status_get_satellite_used(msg
, gps_status
->satellite_used
);
319 mavlink_msg_gps_status_get_satellite_elevation(msg
, gps_status
->satellite_elevation
);
320 mavlink_msg_gps_status_get_satellite_azimuth(msg
, gps_status
->satellite_azimuth
);
321 mavlink_msg_gps_status_get_satellite_snr(msg
, gps_status
->satellite_snr
);
323 memcpy(gps_status
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_GPS_STATUS_LEN
);