mavlink_msg_gps_status.h
Go to the documentation of this file.
1 // MESSAGE GPS_STATUS PACKING
2 
3 #define MAVLINK_MSG_ID_GPS_STATUS 25
4 
5 typedef struct __mavlink_gps_status_t
6 {
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*/
14 
15 #define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
16 #define MAVLINK_MSG_ID_25_LEN 101
17 
18 #define MAVLINK_MSG_ID_GPS_STATUS_CRC 23
19 #define MAVLINK_MSG_ID_25_CRC 23
20 
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
26 
27 #define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
28  "GPS_STATUS", \
29  6, \
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) }, \
36  } \
37 }
38 
39 
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)
56 {
57 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
66 #else
67  mavlink_gps_status_t packet;
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);
75 #endif
76 
77  msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
78 #if MAVLINK_CRC_EXTRA
80 #else
81  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN);
82 #endif
83 }
84 
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)
102 {
103 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
112 #else
113  mavlink_gps_status_t packet;
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);
121 #endif
122 
123  msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
124 #if MAVLINK_CRC_EXTRA
126 #else
127  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN);
128 #endif
129 }
130 
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)
140 {
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);
142 }
143 
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)
154 {
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);
156 }
157 
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
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)
172 {
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
183 #else
184  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
185 #endif
186 #else
187  mavlink_gps_status_t packet;
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);
196 #else
197  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
198 #endif
199 #endif
200 }
201 
202 #if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
203 /*
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.
209  */
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)
211 {
212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213  char *buf = (char *)msgbuf;
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);
222 #else
223  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
224 #endif
225 #else
226  mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf;
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);
235 #else
236  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
237 #endif
238 #endif
239 }
240 #endif
241 
242 #endif
243 
244 // MESSAGE GPS_STATUS UNPACKING
245 
246 
252 static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
253 {
254  return _MAV_RETURN_uint8_t(msg, 0);
255 }
256 
262 static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
263 {
264  return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1);
265 }
266 
272 static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
273 {
274  return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21);
275 }
276 
282 static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
283 {
284  return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41);
285 }
286 
292 static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
293 {
294  return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61);
295 }
296 
302 static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
303 {
304  return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81);
305 }
306 
313 static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
314 {
315 #if MAVLINK_NEED_BYTE_SWAP
322 #else
323  memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN);
324 #endif
325 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
Definition: protocol.h:197
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:295


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47