Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE GPS_RAW PACKING
2
 
3
#define MAVLINK_MSG_ID_GPS_RAW 32
4
 
5
typedef struct __mavlink_gps_raw_t
6
{
7
 uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
8
 uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
9
 float lat; ///< Latitude in degrees
10
 float lon; ///< Longitude in degrees
11
 float alt; ///< Altitude in meters
12
 float eph; ///< GPS HDOP
13
 float epv; ///< GPS VDOP
14
 float v; ///< GPS ground speed
15
 float hdg; ///< Compass heading in degrees, 0..360 degrees
16
} mavlink_gps_raw_t;
17
 
18
#define MAVLINK_MSG_ID_GPS_RAW_LEN 37
19
#define MAVLINK_MSG_ID_32_LEN 37
20
 
21
 
22
 
23
#define MAVLINK_MESSAGE_INFO_GPS_RAW { \
24
        "GPS_RAW", \
25
        9, \
26
        {  { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \
27
         { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_t, fix_type) }, \
28
         { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_gps_raw_t, lat) }, \
29
         { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_gps_raw_t, lon) }, \
30
         { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_gps_raw_t, alt) }, \
31
         { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_t, eph) }, \
32
         { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_t, epv) }, \
33
         { "v", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_t, v) }, \
34
         { "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_t, hdg) }, \
35
         } \
36
}
37
 
38
 
39
/**
40
 * @brief Pack a gps_raw message
41
 * @param system_id ID of this system
42
 * @param component_id ID of this component (e.g. 200 for IMU)
43
 * @param msg The MAVLink message to compress the data into
44
 *
45
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
46
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
47
 * @param lat Latitude in degrees
48
 * @param lon Longitude in degrees
49
 * @param alt Altitude in meters
50
 * @param eph GPS HDOP
51
 * @param epv GPS VDOP
52
 * @param v GPS ground speed
53
 * @param hdg Compass heading in degrees, 0..360 degrees
54
 * @return length of the message in bytes (excluding serial stream start sign)
55
 */
56
static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57
                                                       uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
58
{
59
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
60
        char buf[37];
61
        _mav_put_uint64_t(buf, 0, usec);
62
        _mav_put_uint8_t(buf, 8, fix_type);
63
        _mav_put_float(buf, 9, lat);
64
        _mav_put_float(buf, 13, lon);
65
        _mav_put_float(buf, 17, alt);
66
        _mav_put_float(buf, 21, eph);
67
        _mav_put_float(buf, 25, epv);
68
        _mav_put_float(buf, 29, v);
69
        _mav_put_float(buf, 33, hdg);
70
 
71
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
72
#else
73
        mavlink_gps_raw_t packet;
74
        packet.usec = usec;
75
        packet.fix_type = fix_type;
76
        packet.lat = lat;
77
        packet.lon = lon;
78
        packet.alt = alt;
79
        packet.eph = eph;
80
        packet.epv = epv;
81
        packet.v = v;
82
        packet.hdg = hdg;
83
 
84
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
85
#endif
86
 
87
        msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
88
        return mavlink_finalize_message(msg, system_id, component_id, 37);
89
}
90
 
91
/**
92
 * @brief Pack a gps_raw message on a channel
93
 * @param system_id ID of this system
94
 * @param component_id ID of this component (e.g. 200 for IMU)
95
 * @param chan The MAVLink channel this message was sent over
96
 * @param msg The MAVLink message to compress the data into
97
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
98
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
99
 * @param lat Latitude in degrees
100
 * @param lon Longitude in degrees
101
 * @param alt Altitude in meters
102
 * @param eph GPS HDOP
103
 * @param epv GPS VDOP
104
 * @param v GPS ground speed
105
 * @param hdg Compass heading in degrees, 0..360 degrees
106
 * @return length of the message in bytes (excluding serial stream start sign)
107
 */
108
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
109
                                                           mavlink_message_t* msg,
110
                                                           uint64_t usec,uint8_t fix_type,float lat,float lon,float alt,float eph,float epv,float v,float hdg)
111
{
112
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
113
        char buf[37];
114
        _mav_put_uint64_t(buf, 0, usec);
115
        _mav_put_uint8_t(buf, 8, fix_type);
116
        _mav_put_float(buf, 9, lat);
117
        _mav_put_float(buf, 13, lon);
118
        _mav_put_float(buf, 17, alt);
119
        _mav_put_float(buf, 21, eph);
120
        _mav_put_float(buf, 25, epv);
121
        _mav_put_float(buf, 29, v);
122
        _mav_put_float(buf, 33, hdg);
123
 
124
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
125
#else
126
        mavlink_gps_raw_t packet;
127
        packet.usec = usec;
128
        packet.fix_type = fix_type;
129
        packet.lat = lat;
130
        packet.lon = lon;
131
        packet.alt = alt;
132
        packet.eph = eph;
133
        packet.epv = epv;
134
        packet.v = v;
135
        packet.hdg = hdg;
136
 
137
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
138
#endif
139
 
140
        msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
141
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37);
142
}
143
 
144
/**
145
 * @brief Encode a gps_raw struct into a message
146
 *
147
 * @param system_id ID of this system
148
 * @param component_id ID of this component (e.g. 200 for IMU)
149
 * @param msg The MAVLink message to compress the data into
150
 * @param gps_raw C-struct to read the message contents from
151
 */
152
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
153
{
154
        return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
155
}
156
 
157
/**
158
 * @brief Send a gps_raw message
159
 * @param chan MAVLink channel to send the message
160
 *
161
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
162
 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
163
 * @param lat Latitude in degrees
164
 * @param lon Longitude in degrees
165
 * @param alt Altitude in meters
166
 * @param eph GPS HDOP
167
 * @param epv GPS VDOP
168
 * @param v GPS ground speed
169
 * @param hdg Compass heading in degrees, 0..360 degrees
170
 */
171
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
172
 
173
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
174
{
175
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
176
        char buf[37];
177
        _mav_put_uint64_t(buf, 0, usec);
178
        _mav_put_uint8_t(buf, 8, fix_type);
179
        _mav_put_float(buf, 9, lat);
180
        _mav_put_float(buf, 13, lon);
181
        _mav_put_float(buf, 17, alt);
182
        _mav_put_float(buf, 21, eph);
183
        _mav_put_float(buf, 25, epv);
184
        _mav_put_float(buf, 29, v);
185
        _mav_put_float(buf, 33, hdg);
186
 
187
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, buf, 37);
188
#else
189
        mavlink_gps_raw_t packet;
190
        packet.usec = usec;
191
        packet.fix_type = fix_type;
192
        packet.lat = lat;
193
        packet.lon = lon;
194
        packet.alt = alt;
195
        packet.eph = eph;
196
        packet.epv = epv;
197
        packet.v = v;
198
        packet.hdg = hdg;
199
 
200
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, (const char *)&packet, 37);
201
#endif
202
}
203
 
204
#endif
205
 
206
// MESSAGE GPS_RAW UNPACKING
207
 
208
 
209
/**
210
 * @brief Get field usec from gps_raw message
211
 *
212
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
213
 */
214
static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
215
{
216
        return _MAV_RETURN_uint64_t(msg,  0);
217
}
218
 
219
/**
220
 * @brief Get field fix_type from gps_raw message
221
 *
222
 * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
223
 */
224
static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg)
225
{
226
        return _MAV_RETURN_uint8_t(msg,  8);
227
}
228
 
229
/**
230
 * @brief Get field lat from gps_raw message
231
 *
232
 * @return Latitude in degrees
233
 */
234
static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
235
{
236
        return _MAV_RETURN_float(msg,  9);
237
}
238
 
239
/**
240
 * @brief Get field lon from gps_raw message
241
 *
242
 * @return Longitude in degrees
243
 */
244
static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
245
{
246
        return _MAV_RETURN_float(msg,  13);
247
}
248
 
249
/**
250
 * @brief Get field alt from gps_raw message
251
 *
252
 * @return Altitude in meters
253
 */
254
static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
255
{
256
        return _MAV_RETURN_float(msg,  17);
257
}
258
 
259
/**
260
 * @brief Get field eph from gps_raw message
261
 *
262
 * @return GPS HDOP
263
 */
264
static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
265
{
266
        return _MAV_RETURN_float(msg,  21);
267
}
268
 
269
/**
270
 * @brief Get field epv from gps_raw message
271
 *
272
 * @return GPS VDOP
273
 */
274
static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
275
{
276
        return _MAV_RETURN_float(msg,  25);
277
}
278
 
279
/**
280
 * @brief Get field v from gps_raw message
281
 *
282
 * @return GPS ground speed
283
 */
284
static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
285
{
286
        return _MAV_RETURN_float(msg,  29);
287
}
288
 
289
/**
290
 * @brief Get field hdg from gps_raw message
291
 *
292
 * @return Compass heading in degrees, 0..360 degrees
293
 */
294
static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
295
{
296
        return _MAV_RETURN_float(msg,  33);
297
}
298
 
299
/**
300
 * @brief Decode a gps_raw message into a struct
301
 *
302
 * @param msg The message to decode
303
 * @param gps_raw C-struct to decode the message contents into
304
 */
305
static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
306
{
307
#if MAVLINK_NEED_BYTE_SWAP
308
        gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);
309
        gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg);
310
        gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg);
311
        gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg);
312
        gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg);
313
        gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg);
314
        gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg);
315
        gps_raw->v = mavlink_msg_gps_raw_get_v(msg);
316
        gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg);
317
#else
318
        memcpy(gps_raw, _MAV_PAYLOAD(msg), 37);
319
#endif
320
}