mavlink_msg_global_position_int.h
Go to the documentation of this file.
1 // MESSAGE GLOBAL_POSITION_INT PACKING
2 
3 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
4 
6 {
7  uint32_t time_boot_ms; /*< Timestamp (milliseconds since system boot)*/
8  int32_t lat; /*< Latitude, expressed as degrees * 1E7*/
9  int32_t lon; /*< Longitude, expressed as degrees * 1E7*/
10  int32_t alt; /*< Altitude in meters, expressed as * 1000 (millimeters), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)*/
11  int32_t relative_alt; /*< Altitude above ground in meters, expressed as * 1000 (millimeters)*/
12  int16_t vx; /*< Ground X Speed (Latitude, positive north), expressed as m/s * 100*/
13  int16_t vy; /*< Ground Y Speed (Longitude, positive east), expressed as m/s * 100*/
14  int16_t vz; /*< Ground Z Speed (Altitude, positive down), expressed as m/s * 100*/
15  uint16_t hdg; /*< Vehicle heading (yaw angle) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
17 
18 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
19 #define MAVLINK_MSG_ID_33_LEN 28
20 
21 #define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
22 #define MAVLINK_MSG_ID_33_CRC 104
23 
24 
25 
26 #define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
27  "GLOBAL_POSITION_INT", \
28  9, \
29  { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
30  { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
31  { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
32  { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
33  { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
34  { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
35  { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
36  { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
37  { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
38  } \
39 }
40 
41 
59 static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
60  uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
61 {
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
64  _mav_put_uint32_t(buf, 0, time_boot_ms);
65  _mav_put_int32_t(buf, 4, lat);
66  _mav_put_int32_t(buf, 8, lon);
67  _mav_put_int32_t(buf, 12, alt);
68  _mav_put_int32_t(buf, 16, relative_alt);
69  _mav_put_int16_t(buf, 20, vx);
70  _mav_put_int16_t(buf, 22, vy);
71  _mav_put_int16_t(buf, 24, vz);
72  _mav_put_uint16_t(buf, 26, hdg);
73 
75 #else
77  packet.time_boot_ms = time_boot_ms;
78  packet.lat = lat;
79  packet.lon = lon;
80  packet.alt = alt;
81  packet.relative_alt = relative_alt;
82  packet.vx = vx;
83  packet.vy = vy;
84  packet.vz = vz;
85  packet.hdg = hdg;
86 
88 #endif
89 
91 #if MAVLINK_CRC_EXTRA
93 #else
94  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
95 #endif
96 }
97 
115 static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
116  mavlink_message_t* msg,
117  uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
118 {
119 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
121  _mav_put_uint32_t(buf, 0, time_boot_ms);
122  _mav_put_int32_t(buf, 4, lat);
123  _mav_put_int32_t(buf, 8, lon);
124  _mav_put_int32_t(buf, 12, alt);
125  _mav_put_int32_t(buf, 16, relative_alt);
126  _mav_put_int16_t(buf, 20, vx);
127  _mav_put_int16_t(buf, 22, vy);
128  _mav_put_int16_t(buf, 24, vz);
129  _mav_put_uint16_t(buf, 26, hdg);
130 
132 #else
134  packet.time_boot_ms = time_boot_ms;
135  packet.lat = lat;
136  packet.lon = lon;
137  packet.alt = alt;
138  packet.relative_alt = relative_alt;
139  packet.vx = vx;
140  packet.vy = vy;
141  packet.vz = vz;
142  packet.hdg = hdg;
143 
145 #endif
146 
148 #if MAVLINK_CRC_EXTRA
150 #else
151  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
152 #endif
153 }
154 
163 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)
164 {
165  return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
166 }
167 
177 static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
178 {
179  return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
180 }
181 
196 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
197 
198 static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
199 {
200 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
203  _mav_put_int32_t(buf, 4, lat);
204  _mav_put_int32_t(buf, 8, lon);
205  _mav_put_int32_t(buf, 12, alt);
206  _mav_put_int32_t(buf, 16, relative_alt);
207  _mav_put_int16_t(buf, 20, vx);
208  _mav_put_int16_t(buf, 22, vy);
209  _mav_put_int16_t(buf, 24, vz);
210  _mav_put_uint16_t(buf, 26, hdg);
211 
212 #if MAVLINK_CRC_EXTRA
214 #else
215  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
216 #endif
217 #else
219  packet.time_boot_ms = time_boot_ms;
220  packet.lat = lat;
221  packet.lon = lon;
222  packet.alt = alt;
223  packet.relative_alt = relative_alt;
224  packet.vx = vx;
225  packet.vy = vy;
226  packet.vz = vz;
227  packet.hdg = hdg;
228 
229 #if MAVLINK_CRC_EXTRA
230  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
231 #else
232  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
233 #endif
234 #endif
235 }
236 
237 #if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
238 /*
239  This varient of _send() can be used to save stack space by re-using
240  memory from the receive buffer. The caller provides a
241  mavlink_message_t which is the size of a full mavlink message. This
242  is usually the receive buffer for the channel, and allows a reply to an
243  incoming message with minimum stack space usage.
244  */
245 static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
246 {
247 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
248  char *buf = (char *)msgbuf;
250  _mav_put_int32_t(buf, 4, lat);
251  _mav_put_int32_t(buf, 8, lon);
252  _mav_put_int32_t(buf, 12, alt);
253  _mav_put_int32_t(buf, 16, relative_alt);
254  _mav_put_int16_t(buf, 20, vx);
255  _mav_put_int16_t(buf, 22, vy);
256  _mav_put_int16_t(buf, 24, vz);
257  _mav_put_uint16_t(buf, 26, hdg);
258 
259 #if MAVLINK_CRC_EXTRA
261 #else
262  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
263 #endif
264 #else
266  packet->time_boot_ms = time_boot_ms;
267  packet->lat = lat;
268  packet->lon = lon;
269  packet->alt = alt;
270  packet->relative_alt = relative_alt;
271  packet->vx = vx;
272  packet->vy = vy;
273  packet->vz = vz;
274  packet->hdg = hdg;
275 
276 #if MAVLINK_CRC_EXTRA
278 #else
279  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
280 #endif
281 #endif
282 }
283 #endif
284 
285 #endif
286 
287 // MESSAGE GLOBAL_POSITION_INT UNPACKING
288 
289 
295 static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
296 {
297  return _MAV_RETURN_uint32_t(msg, 0);
298 }
299 
305 static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
306 {
307  return _MAV_RETURN_int32_t(msg, 4);
308 }
309 
315 static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
316 {
317  return _MAV_RETURN_int32_t(msg, 8);
318 }
319 
325 static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
326 {
327  return _MAV_RETURN_int32_t(msg, 12);
328 }
329 
335 static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
336 {
337  return _MAV_RETURN_int32_t(msg, 16);
338 }
339 
345 static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
346 {
347  return _MAV_RETURN_int16_t(msg, 20);
348 }
349 
355 static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
356 {
357  return _MAV_RETURN_int16_t(msg, 22);
358 }
359 
365 static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
366 {
367  return _MAV_RETURN_int16_t(msg, 24);
368 }
369 
375 static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
376 {
377  return _MAV_RETURN_uint16_t(msg, 26);
378 }
379 
386 static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
387 {
388 #if MAVLINK_NEED_BYTE_SWAP
390  global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
391  global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
392  global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
394  global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
395  global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
396  global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
397  global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
398 #else
399  memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
400 #endif
401 }
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:148
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24