Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 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
13
} mavlink_gps_status_t;
14
 
15
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
16
#define MAVLINK_MSG_ID_25_LEN 101
17
 
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
 
24
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
25
        "GPS_STATUS", \
26
        6, \
27
        {  { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
28
         { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
29
         { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
30
         { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
31
         { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
32
         { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
33
         } \
34
}
35
 
36
 
37
/**
38
 * @brief Pack a gps_status message
39
 * @param system_id ID of this system
40
 * @param component_id ID of this component (e.g. 200 for IMU)
41
 * @param msg The MAVLink message to compress the data into
42
 *
43
 * @param satellites_visible Number of satellites visible
44
 * @param satellite_prn Global satellite ID
45
 * @param satellite_used 0: Satellite not used, 1: used for localization
46
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
47
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
48
 * @param satellite_snr Signal to noise ratio of satellite
49
 * @return length of the message in bytes (excluding serial stream start sign)
50
 */
51
static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
52
                                                       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)
53
{
54
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55
        char buf[101];
56
        _mav_put_uint8_t(buf, 0, satellites_visible);
57
        _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
58
        _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
59
        _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
60
        _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
61
        _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
62
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
63
#else
64
        mavlink_gps_status_t packet;
65
        packet.satellites_visible = satellites_visible;
66
        mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
67
        mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
68
        mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
69
        mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
70
        mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
71
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
72
#endif
73
 
74
        msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
75
        return mavlink_finalize_message(msg, system_id, component_id, 101, 23);
76
}
77
 
78
/**
79
 * @brief Pack a gps_status message on a channel
80
 * @param system_id ID of this system
81
 * @param component_id ID of this component (e.g. 200 for IMU)
82
 * @param chan The MAVLink channel this message was sent over
83
 * @param msg The MAVLink message to compress the data into
84
 * @param satellites_visible Number of satellites visible
85
 * @param satellite_prn Global satellite ID
86
 * @param satellite_used 0: Satellite not used, 1: used for localization
87
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
88
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
89
 * @param satellite_snr Signal to noise ratio of satellite
90
 * @return length of the message in bytes (excluding serial stream start sign)
91
 */
92
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
93
                                                           mavlink_message_t* msg,
94
                                                           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)
95
{
96
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97
        char buf[101];
98
        _mav_put_uint8_t(buf, 0, satellites_visible);
99
        _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
100
        _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
101
        _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
102
        _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
103
        _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
104
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
105
#else
106
        mavlink_gps_status_t packet;
107
        packet.satellites_visible = satellites_visible;
108
        mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
109
        mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
110
        mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
111
        mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
112
        mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23);
118
}
119
 
120
/**
121
 * @brief Encode a gps_status struct into a message
122
 *
123
 * @param system_id ID of this system
124
 * @param component_id ID of this component (e.g. 200 for IMU)
125
 * @param msg The MAVLink message to compress the data into
126
 * @param gps_status C-struct to read the message contents from
127
 */
128
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)
129
{
130
        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);
131
}
132
 
133
/**
134
 * @brief Send a gps_status message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param satellites_visible Number of satellites visible
138
 * @param satellite_prn Global satellite ID
139
 * @param satellite_used 0: Satellite not used, 1: used for localization
140
 * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
141
 * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
142
 * @param satellite_snr Signal to noise ratio of satellite
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
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)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[101];
150
        _mav_put_uint8_t(buf, 0, satellites_visible);
151
        _mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
152
        _mav_put_uint8_t_array(buf, 21, satellite_used, 20);
153
        _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
154
        _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
155
        _mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
156
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23);
157
#else
158
        mavlink_gps_status_t packet;
159
        packet.satellites_visible = satellites_visible;
160
        mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
161
        mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
162
        mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
163
        mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
164
        mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
165
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23);
166
#endif
167
}
168
 
169
#endif
170
 
171
// MESSAGE GPS_STATUS UNPACKING
172
 
173
 
174
/**
175
 * @brief Get field satellites_visible from gps_status message
176
 *
177
 * @return Number of satellites visible
178
 */
179
static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
180
{
181
        return _MAV_RETURN_uint8_t(msg,  0);
182
}
183
 
184
/**
185
 * @brief Get field satellite_prn from gps_status message
186
 *
187
 * @return Global satellite ID
188
 */
189
static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
190
{
191
        return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20,  1);
192
}
193
 
194
/**
195
 * @brief Get field satellite_used from gps_status message
196
 *
197
 * @return 0: Satellite not used, 1: used for localization
198
 */
199
static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
200
{
201
        return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20,  21);
202
}
203
 
204
/**
205
 * @brief Get field satellite_elevation from gps_status message
206
 *
207
 * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
208
 */
209
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
210
{
211
        return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20,  41);
212
}
213
 
214
/**
215
 * @brief Get field satellite_azimuth from gps_status message
216
 *
217
 * @return Direction of satellite, 0: 0 deg, 255: 360 deg.
218
 */
219
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
220
{
221
        return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20,  61);
222
}
223
 
224
/**
225
 * @brief Get field satellite_snr from gps_status message
226
 *
227
 * @return Signal to noise ratio of satellite
228
 */
229
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
230
{
231
        return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20,  81);
232
}
233
 
234
/**
235
 * @brief Decode a gps_status message into a struct
236
 *
237
 * @param msg The message to decode
238
 * @param gps_status C-struct to decode the message contents into
239
 */
240
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
241
{
242
#if MAVLINK_NEED_BYTE_SWAP
243
        gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
244
        mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
245
        mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
246
        mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
247
        mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
248
        mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
249
#else
250
        memcpy(gps_status, _MAV_PAYLOAD(msg), 101);
251
#endif
252
}