Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE GLOBAL_POSITION_INT PACKING
2
 
3
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
4
 
5
typedef struct __mavlink_global_position_int_t
6
{
7
 int32_t lat; ///< Latitude, expressed as * 1E7
8
 int32_t lon; ///< Longitude, expressed as * 1E7
9
 int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
10
 int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
11
 int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
12
 int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
13
} mavlink_global_position_int_t;
14
 
15
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 18
16
#define MAVLINK_MSG_ID_73_LEN 18
17
 
18
 
19
 
20
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
21
        "GLOBAL_POSITION_INT", \
22
        6, \
23
        {  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_int_t, lat) }, \
24
         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lon) }, \
25
         { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, alt) }, \
26
         { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_int_t, vx) }, \
27
         { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_global_position_int_t, vy) }, \
28
         { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_global_position_int_t, vz) }, \
29
         } \
30
}
31
 
32
 
33
/**
34
 * @brief Pack a global_position_int message
35
 * @param system_id ID of this system
36
 * @param component_id ID of this component (e.g. 200 for IMU)
37
 * @param msg The MAVLink message to compress the data into
38
 *
39
 * @param lat Latitude, expressed as * 1E7
40
 * @param lon Longitude, expressed as * 1E7
41
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
42
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
43
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
44
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
45
 * @return length of the message in bytes (excluding serial stream start sign)
46
 */
47
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
48
                                                       int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
49
{
50
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
51
        char buf[18];
52
        _mav_put_int32_t(buf, 0, lat);
53
        _mav_put_int32_t(buf, 4, lon);
54
        _mav_put_int32_t(buf, 8, alt);
55
        _mav_put_int16_t(buf, 12, vx);
56
        _mav_put_int16_t(buf, 14, vy);
57
        _mav_put_int16_t(buf, 16, vz);
58
 
59
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
60
#else
61
        mavlink_global_position_int_t packet;
62
        packet.lat = lat;
63
        packet.lon = lon;
64
        packet.alt = alt;
65
        packet.vx = vx;
66
        packet.vy = vy;
67
        packet.vz = vz;
68
 
69
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
70
#endif
71
 
72
        msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
73
        return mavlink_finalize_message(msg, system_id, component_id, 18);
74
}
75
 
76
/**
77
 * @brief Pack a global_position_int message on a channel
78
 * @param system_id ID of this system
79
 * @param component_id ID of this component (e.g. 200 for IMU)
80
 * @param chan The MAVLink channel this message was sent over
81
 * @param msg The MAVLink message to compress the data into
82
 * @param lat Latitude, expressed as * 1E7
83
 * @param lon Longitude, expressed as * 1E7
84
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
85
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
86
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
87
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
88
 * @return length of the message in bytes (excluding serial stream start sign)
89
 */
90
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
91
                                                           mavlink_message_t* msg,
92
                                                           int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz)
93
{
94
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
95
        char buf[18];
96
        _mav_put_int32_t(buf, 0, lat);
97
        _mav_put_int32_t(buf, 4, lon);
98
        _mav_put_int32_t(buf, 8, alt);
99
        _mav_put_int16_t(buf, 12, vx);
100
        _mav_put_int16_t(buf, 14, vy);
101
        _mav_put_int16_t(buf, 16, vz);
102
 
103
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
104
#else
105
        mavlink_global_position_int_t packet;
106
        packet.lat = lat;
107
        packet.lon = lon;
108
        packet.alt = alt;
109
        packet.vx = vx;
110
        packet.vy = vy;
111
        packet.vz = vz;
112
 
113
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
114
#endif
115
 
116
        msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
117
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
118
}
119
 
120
/**
121
 * @brief Encode a global_position_int 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 global_position_int C-struct to read the message contents from
127
 */
128
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
129
{
130
        return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
131
}
132
 
133
/**
134
 * @brief Send a global_position_int message
135
 * @param chan MAVLink channel to send the message
136
 *
137
 * @param lat Latitude, expressed as * 1E7
138
 * @param lon Longitude, expressed as * 1E7
139
 * @param alt Altitude in meters, expressed as * 1000 (millimeters)
140
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
141
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
142
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
143
 */
144
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
145
 
146
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
147
{
148
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
149
        char buf[18];
150
        _mav_put_int32_t(buf, 0, lat);
151
        _mav_put_int32_t(buf, 4, lon);
152
        _mav_put_int32_t(buf, 8, alt);
153
        _mav_put_int16_t(buf, 12, vx);
154
        _mav_put_int16_t(buf, 14, vy);
155
        _mav_put_int16_t(buf, 16, vz);
156
 
157
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 18);
158
#else
159
        mavlink_global_position_int_t packet;
160
        packet.lat = lat;
161
        packet.lon = lon;
162
        packet.alt = alt;
163
        packet.vx = vx;
164
        packet.vy = vy;
165
        packet.vz = vz;
166
 
167
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 18);
168
#endif
169
}
170
 
171
#endif
172
 
173
// MESSAGE GLOBAL_POSITION_INT UNPACKING
174
 
175
 
176
/**
177
 * @brief Get field lat from global_position_int message
178
 *
179
 * @return Latitude, expressed as * 1E7
180
 */
181
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
182
{
183
        return _MAV_RETURN_int32_t(msg,  0);
184
}
185
 
186
/**
187
 * @brief Get field lon from global_position_int message
188
 *
189
 * @return Longitude, expressed as * 1E7
190
 */
191
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
192
{
193
        return _MAV_RETURN_int32_t(msg,  4);
194
}
195
 
196
/**
197
 * @brief Get field alt from global_position_int message
198
 *
199
 * @return Altitude in meters, expressed as * 1000 (millimeters)
200
 */
201
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
202
{
203
        return _MAV_RETURN_int32_t(msg,  8);
204
}
205
 
206
/**
207
 * @brief Get field vx from global_position_int message
208
 *
209
 * @return Ground X Speed (Latitude), expressed as m/s * 100
210
 */
211
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
212
{
213
        return _MAV_RETURN_int16_t(msg,  12);
214
}
215
 
216
/**
217
 * @brief Get field vy from global_position_int message
218
 *
219
 * @return Ground Y Speed (Longitude), expressed as m/s * 100
220
 */
221
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
222
{
223
        return _MAV_RETURN_int16_t(msg,  14);
224
}
225
 
226
/**
227
 * @brief Get field vz from global_position_int message
228
 *
229
 * @return Ground Z Speed (Altitude), expressed as m/s * 100
230
 */
231
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
232
{
233
        return _MAV_RETURN_int16_t(msg,  16);
234
}
235
 
236
/**
237
 * @brief Decode a global_position_int message into a struct
238
 *
239
 * @param msg The message to decode
240
 * @param global_position_int C-struct to decode the message contents into
241
 */
242
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
243
{
244
#if MAVLINK_NEED_BYTE_SWAP
245
        global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
246
        global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
247
        global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
248
        global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
249
        global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
250
        global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
251
#else
252
        memcpy(global_position_int, _MAV_PAYLOAD(msg), 18);
253
#endif
254
}