mavlink_msg_global_position_int.h 10.8 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2
// MESSAGE GLOBAL_POSITION_INT PACKING

3
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
James Goppert's avatar
James Goppert committed
4

lm's avatar
lm committed
5
typedef struct __mavlink_global_position_int_t
James Goppert's avatar
James Goppert committed
6
{
7
 uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
lm's avatar
lm committed
8 9 10 11 12 13 14
 int32_t lat; ///< Latitude, expressed as * 1E7
 int32_t lon; ///< Longitude, expressed as * 1E7
 int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
 int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
 int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
 int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
 uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
15 16
} mavlink_global_position_int_t;

17 18
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 24
#define MAVLINK_MSG_ID_33_LEN 24
lm's avatar
lm committed
19 20 21 22 23



#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
	"GLOBAL_POSITION_INT", \
24 25 26 27 28 29 30 31 32
	8, \
	{  { "time_boot_ms", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
         { "lat", MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
         { "lon", MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
         { "alt", MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
         { "vx", MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_global_position_int_t, vx) }, \
         { "vy", MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_global_position_int_t, vy) }, \
         { "vz", MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vz) }, \
         { "hdg", MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_global_position_int_t, hdg) }, \
lm's avatar
lm committed
33 34 35 36
         } \
}


James Goppert's avatar
James Goppert committed
37 38 39 40 41 42
/**
 * @brief Pack a global_position_int message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
43
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
44 45
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
LM's avatar
LM committed
46
 * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
James Goppert's avatar
James Goppert committed
47 48 49
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
LM's avatar
LM committed
50
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
51 52
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
53
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54
						       uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
James Goppert's avatar
James Goppert committed
55
{
LM's avatar
LM committed
56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_int32_t(buf, 4, lat);
	_mav_put_int32_t(buf, 8, lon);
	_mav_put_int32_t(buf, 12, alt);
	_mav_put_int16_t(buf, 16, vx);
	_mav_put_int16_t(buf, 18, vy);
	_mav_put_int16_t(buf, 20, vz);
	_mav_put_uint16_t(buf, 22, hdg);

        memcpy(_MAV_PAYLOAD(msg), buf, 24);
#else
	mavlink_global_position_int_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.hdg = hdg;
James Goppert's avatar
James Goppert committed
78

LM's avatar
LM committed
79 80
        memcpy(_MAV_PAYLOAD(msg), &packet, 24);
#endif
James Goppert's avatar
James Goppert committed
81

LM's avatar
LM committed
82
	msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
83
	return mavlink_finalize_message(msg, system_id, component_id, 24, 102);
James Goppert's avatar
James Goppert committed
84 85 86
}

/**
lm's avatar
lm committed
87
 * @brief Pack a global_position_int message on a channel
James Goppert's avatar
James Goppert committed
88 89 90 91
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
92
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
93 94
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
LM's avatar
LM committed
95
 * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
James Goppert's avatar
James Goppert committed
96 97 98
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
LM's avatar
LM committed
99
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
100 101
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
102 103
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
104
						           uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
James Goppert's avatar
James Goppert committed
105
{
LM's avatar
LM committed
106 107 108 109 110 111 112 113 114 115
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_int32_t(buf, 4, lat);
	_mav_put_int32_t(buf, 8, lon);
	_mav_put_int32_t(buf, 12, alt);
	_mav_put_int16_t(buf, 16, vx);
	_mav_put_int16_t(buf, 18, vy);
	_mav_put_int16_t(buf, 20, vz);
	_mav_put_uint16_t(buf, 22, hdg);
James Goppert's avatar
James Goppert committed
116

LM's avatar
LM committed
117 118 119 120 121 122 123 124 125 126 127
        memcpy(_MAV_PAYLOAD(msg), buf, 24);
#else
	mavlink_global_position_int_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.hdg = hdg;
James Goppert's avatar
James Goppert committed
128

LM's avatar
LM committed
129 130 131 132
        memcpy(_MAV_PAYLOAD(msg), &packet, 24);
#endif

	msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
133
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 102);
James Goppert's avatar
James Goppert committed
134 135 136 137 138 139 140 141 142 143 144 145
}

/**
 * @brief Encode a global_position_int struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param global_position_int C-struct to read the message contents from
 */
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)
{
146
	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->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
James Goppert's avatar
James Goppert committed
147 148 149 150 151 152
}

/**
 * @brief Send a global_position_int message
 * @param chan MAVLink channel to send the message
 *
153
 * @param time_boot_ms Timestamp (milliseconds since system boot)
James Goppert's avatar
James Goppert committed
154 155
 * @param lat Latitude, expressed as * 1E7
 * @param lon Longitude, expressed as * 1E7
LM's avatar
LM committed
156
 * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
James Goppert's avatar
James Goppert committed
157 158 159
 * @param vx Ground X Speed (Latitude), expressed as m/s * 100
 * @param vy Ground Y Speed (Longitude), expressed as m/s * 100
 * @param vz Ground Z Speed (Altitude), expressed as m/s * 100
LM's avatar
LM committed
160
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
161
 */
lm's avatar
lm committed
162 163
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

164
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, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
lm's avatar
lm committed
165
{
LM's avatar
LM committed
166 167 168 169 170 171 172 173 174 175
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[24];
	_mav_put_uint32_t(buf, 0, time_boot_ms);
	_mav_put_int32_t(buf, 4, lat);
	_mav_put_int32_t(buf, 8, lon);
	_mav_put_int32_t(buf, 12, alt);
	_mav_put_int16_t(buf, 16, vx);
	_mav_put_int16_t(buf, 18, vy);
	_mav_put_int16_t(buf, 20, vz);
	_mav_put_uint16_t(buf, 22, hdg);
LM's avatar
LM committed
176

LM's avatar
LM committed
177 178 179 180 181 182 183 184 185 186 187
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 24, 102);
#else
	mavlink_global_position_int_t packet;
	packet.time_boot_ms = time_boot_ms;
	packet.lat = lat;
	packet.lon = lon;
	packet.alt = alt;
	packet.vx = vx;
	packet.vy = vy;
	packet.vz = vz;
	packet.hdg = hdg;
LM's avatar
LM committed
188

LM's avatar
LM committed
189 190
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 24, 102);
#endif
James Goppert's avatar
James Goppert committed
191 192 193
}

#endif
lm's avatar
lm committed
194

James Goppert's avatar
James Goppert committed
195 196
// MESSAGE GLOBAL_POSITION_INT UNPACKING

lm's avatar
lm committed
197

198 199 200 201 202 203 204
/**
 * @brief Get field time_boot_ms from global_position_int message
 *
 * @return Timestamp (milliseconds since system boot)
 */
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
{
LM's avatar
LM committed
205
	return _MAV_RETURN_uint32_t(msg,  0);
206 207
}

James Goppert's avatar
James Goppert committed
208 209 210 211 212 213 214
/**
 * @brief Get field lat from global_position_int message
 *
 * @return Latitude, expressed as * 1E7
 */
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
LM's avatar
LM committed
215
	return _MAV_RETURN_int32_t(msg,  4);
James Goppert's avatar
James Goppert committed
216 217 218 219 220 221 222 223 224
}

/**
 * @brief Get field lon from global_position_int message
 *
 * @return Longitude, expressed as * 1E7
 */
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
LM's avatar
LM committed
225
	return _MAV_RETURN_int32_t(msg,  8);
James Goppert's avatar
James Goppert committed
226 227 228 229 230
}

/**
 * @brief Get field alt from global_position_int message
 *
LM's avatar
LM committed
231
 * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
James Goppert's avatar
James Goppert committed
232 233 234
 */
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
LM's avatar
LM committed
235
	return _MAV_RETURN_int32_t(msg,  12);
James Goppert's avatar
James Goppert committed
236 237 238 239 240 241 242 243 244
}

/**
 * @brief Get field vx from global_position_int message
 *
 * @return Ground X Speed (Latitude), expressed as m/s * 100
 */
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{
LM's avatar
LM committed
245
	return _MAV_RETURN_int16_t(msg,  16);
James Goppert's avatar
James Goppert committed
246 247 248 249 250 251 252 253 254
}

/**
 * @brief Get field vy from global_position_int message
 *
 * @return Ground Y Speed (Longitude), expressed as m/s * 100
 */
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{
LM's avatar
LM committed
255
	return _MAV_RETURN_int16_t(msg,  18);
James Goppert's avatar
James Goppert committed
256 257 258 259 260 261 262 263 264
}

/**
 * @brief Get field vz from global_position_int message
 *
 * @return Ground Z Speed (Altitude), expressed as m/s * 100
 */
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{
LM's avatar
LM committed
265
	return _MAV_RETURN_int16_t(msg,  20);
James Goppert's avatar
James Goppert committed
266 267
}

LM's avatar
LM committed
268 269 270 271 272 273 274
/**
 * @brief Get field hdg from global_position_int message
 *
 * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 */
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{
LM's avatar
LM committed
275
	return _MAV_RETURN_uint16_t(msg,  22);
LM's avatar
LM committed
276 277
}

James Goppert's avatar
James Goppert committed
278 279 280 281 282 283 284 285
/**
 * @brief Decode a global_position_int message into a struct
 *
 * @param msg The message to decode
 * @param global_position_int C-struct to decode the message contents into
 */
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
{
lm's avatar
lm committed
286
#if MAVLINK_NEED_BYTE_SWAP
287
	global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
lm's avatar
lm committed
288 289 290 291 292 293 294 295
	global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
	global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
	global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
	global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
	global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
	global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
	global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
#else
LM's avatar
LM committed
296
	memcpy(global_position_int, _MAV_PAYLOAD(msg), 24);
lm's avatar
lm committed
297
#endif
James Goppert's avatar
James Goppert committed
298
}