Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE GLOBAL_POSITION PACKING
2
 
3
#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
4
 
5
typedef struct __mavlink_global_position_t
6
{
7
 uint64_t usec; ///< Timestamp (microseconds since unix epoch)
8
 float lat; ///< Latitude, in degrees
9
 float lon; ///< Longitude, in degrees
10
 float alt; ///< Absolute altitude, in meters
11
 float vx; ///< X Speed (in Latitude direction, positive: going north)
12
 float vy; ///< Y Speed (in Longitude direction, positive: going east)
13
 float vz; ///< Z Speed (in Altitude direction, positive: going up)
14
} mavlink_global_position_t;
15
 
16
#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32
17
#define MAVLINK_MSG_ID_33_LEN 32
18
 
19
 
20
 
21
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \
22
        "GLOBAL_POSITION", \
23
        7, \
24
        {  { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \
25
         { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \
26
         { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \
27
         { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \
28
         { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \
29
         { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \
30
         { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \
31
         } \
32
}
33
 
34
 
35
/**
36
 * @brief Pack a global_position message
37
 * @param system_id ID of this system
38
 * @param component_id ID of this component (e.g. 200 for IMU)
39
 * @param msg The MAVLink message to compress the data into
40
 *
41
 * @param usec Timestamp (microseconds since unix epoch)
42
 * @param lat Latitude, in degrees
43
 * @param lon Longitude, in degrees
44
 * @param alt Absolute altitude, in meters
45
 * @param vx X Speed (in Latitude direction, positive: going north)
46
 * @param vy Y Speed (in Longitude direction, positive: going east)
47
 * @param vz Z Speed (in Altitude direction, positive: going up)
48
 * @return length of the message in bytes (excluding serial stream start sign)
49
 */
50
static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51
                                                       uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
52
{
53
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54
        char buf[32];
55
        _mav_put_uint64_t(buf, 0, usec);
56
        _mav_put_float(buf, 8, lat);
57
        _mav_put_float(buf, 12, lon);
58
        _mav_put_float(buf, 16, alt);
59
        _mav_put_float(buf, 20, vx);
60
        _mav_put_float(buf, 24, vy);
61
        _mav_put_float(buf, 28, vz);
62
 
63
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
64
#else
65
        mavlink_global_position_t packet;
66
        packet.usec = usec;
67
        packet.lat = lat;
68
        packet.lon = lon;
69
        packet.alt = alt;
70
        packet.vx = vx;
71
        packet.vy = vy;
72
        packet.vz = vz;
73
 
74
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
75
#endif
76
 
77
        msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
78
        return mavlink_finalize_message(msg, system_id, component_id, 32);
79
}
80
 
81
/**
82
 * @brief Pack a global_position message on a channel
83
 * @param system_id ID of this system
84
 * @param component_id ID of this component (e.g. 200 for IMU)
85
 * @param chan The MAVLink channel this message was sent over
86
 * @param msg The MAVLink message to compress the data into
87
 * @param usec Timestamp (microseconds since unix epoch)
88
 * @param lat Latitude, in degrees
89
 * @param lon Longitude, in degrees
90
 * @param alt Absolute altitude, in meters
91
 * @param vx X Speed (in Latitude direction, positive: going north)
92
 * @param vy Y Speed (in Longitude direction, positive: going east)
93
 * @param vz Z Speed (in Altitude direction, positive: going up)
94
 * @return length of the message in bytes (excluding serial stream start sign)
95
 */
96
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
97
                                                           mavlink_message_t* msg,
98
                                                           uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz)
99
{
100
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101
        char buf[32];
102
        _mav_put_uint64_t(buf, 0, usec);
103
        _mav_put_float(buf, 8, lat);
104
        _mav_put_float(buf, 12, lon);
105
        _mav_put_float(buf, 16, alt);
106
        _mav_put_float(buf, 20, vx);
107
        _mav_put_float(buf, 24, vy);
108
        _mav_put_float(buf, 28, vz);
109
 
110
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
111
#else
112
        mavlink_global_position_t packet;
113
        packet.usec = usec;
114
        packet.lat = lat;
115
        packet.lon = lon;
116
        packet.alt = alt;
117
        packet.vx = vx;
118
        packet.vy = vy;
119
        packet.vz = vz;
120
 
121
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
122
#endif
123
 
124
        msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
125
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
126
}
127
 
128
/**
129
 * @brief Encode a global_position struct into a message
130
 *
131
 * @param system_id ID of this system
132
 * @param component_id ID of this component (e.g. 200 for IMU)
133
 * @param msg The MAVLink message to compress the data into
134
 * @param global_position C-struct to read the message contents from
135
 */
136
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
137
{
138
        return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
139
}
140
 
141
/**
142
 * @brief Send a global_position message
143
 * @param chan MAVLink channel to send the message
144
 *
145
 * @param usec Timestamp (microseconds since unix epoch)
146
 * @param lat Latitude, in degrees
147
 * @param lon Longitude, in degrees
148
 * @param alt Absolute altitude, in meters
149
 * @param vx X Speed (in Latitude direction, positive: going north)
150
 * @param vy Y Speed (in Longitude direction, positive: going east)
151
 * @param vz Z Speed (in Altitude direction, positive: going up)
152
 */
153
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
154
 
155
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
156
{
157
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
158
        char buf[32];
159
        _mav_put_uint64_t(buf, 0, usec);
160
        _mav_put_float(buf, 8, lat);
161
        _mav_put_float(buf, 12, lon);
162
        _mav_put_float(buf, 16, alt);
163
        _mav_put_float(buf, 20, vx);
164
        _mav_put_float(buf, 24, vy);
165
        _mav_put_float(buf, 28, vz);
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, buf, 32);
168
#else
169
        mavlink_global_position_t packet;
170
        packet.usec = usec;
171
        packet.lat = lat;
172
        packet.lon = lon;
173
        packet.alt = alt;
174
        packet.vx = vx;
175
        packet.vy = vy;
176
        packet.vz = vz;
177
 
178
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, (const char *)&packet, 32);
179
#endif
180
}
181
 
182
#endif
183
 
184
// MESSAGE GLOBAL_POSITION UNPACKING
185
 
186
 
187
/**
188
 * @brief Get field usec from global_position message
189
 *
190
 * @return Timestamp (microseconds since unix epoch)
191
 */
192
static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
193
{
194
        return _MAV_RETURN_uint64_t(msg,  0);
195
}
196
 
197
/**
198
 * @brief Get field lat from global_position message
199
 *
200
 * @return Latitude, in degrees
201
 */
202
static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
203
{
204
        return _MAV_RETURN_float(msg,  8);
205
}
206
 
207
/**
208
 * @brief Get field lon from global_position message
209
 *
210
 * @return Longitude, in degrees
211
 */
212
static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
213
{
214
        return _MAV_RETURN_float(msg,  12);
215
}
216
 
217
/**
218
 * @brief Get field alt from global_position message
219
 *
220
 * @return Absolute altitude, in meters
221
 */
222
static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
223
{
224
        return _MAV_RETURN_float(msg,  16);
225
}
226
 
227
/**
228
 * @brief Get field vx from global_position message
229
 *
230
 * @return X Speed (in Latitude direction, positive: going north)
231
 */
232
static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
233
{
234
        return _MAV_RETURN_float(msg,  20);
235
}
236
 
237
/**
238
 * @brief Get field vy from global_position message
239
 *
240
 * @return Y Speed (in Longitude direction, positive: going east)
241
 */
242
static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
243
{
244
        return _MAV_RETURN_float(msg,  24);
245
}
246
 
247
/**
248
 * @brief Get field vz from global_position message
249
 *
250
 * @return Z Speed (in Altitude direction, positive: going up)
251
 */
252
static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
253
{
254
        return _MAV_RETURN_float(msg,  28);
255
}
256
 
257
/**
258
 * @brief Decode a global_position message into a struct
259
 *
260
 * @param msg The message to decode
261
 * @param global_position C-struct to decode the message contents into
262
 */
263
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
264
{
265
#if MAVLINK_NEED_BYTE_SWAP
266
        global_position->usec = mavlink_msg_global_position_get_usec(msg);
267
        global_position->lat = mavlink_msg_global_position_get_lat(msg);
268
        global_position->lon = mavlink_msg_global_position_get_lon(msg);
269
        global_position->alt = mavlink_msg_global_position_get_alt(msg);
270
        global_position->vx = mavlink_msg_global_position_get_vx(msg);
271
        global_position->vy = mavlink_msg_global_position_get_vy(msg);
272
        global_position->vz = mavlink_msg_global_position_get_vz(msg);
273
#else
274
        memcpy(global_position, _MAV_PAYLOAD(msg), 32);
275
#endif
276
}