mavlink_msg_gps_raw_int.h 13.7 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE GPS_RAW_INT PACKING

#define MAVLINK_MSG_ID_GPS_RAW_INT 25
LM's avatar
LM committed
4 5
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_25_LEN 30
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11

typedef struct __mavlink_gps_raw_int_t 
{
	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	int32_t lat; ///< Latitude in 1E7 degrees
	int32_t lon; ///< Longitude in 1E7 degrees
LM's avatar
LM committed
12 13 14 15 16
	int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL
	uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
	uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
17
	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.
LM's avatar
LM committed
18
	uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
19 20 21 22 23 24 25 26 27 28 29 30 31

} mavlink_gps_raw_int_t;

/**
 * @brief Pack a gps_raw_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
 *
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
32 33 34 35 36 37
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
38 39
 * @return length of the message in bytes (excluding serial stream start sign)
 */
LM's avatar
LM committed
40
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
41
{
lm's avatar
lm committed
42
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
43 44
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;

lm's avatar
lm committed
45 46 47 48
	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->fix_type = fix_type; // uint8_t: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.
	p->lat = lat; // int32_t:Latitude in 1E7 degrees
	p->lon = lon; // int32_t:Longitude in 1E7 degrees
LM's avatar
LM committed
49 50 51 52 53 54
	p->alt = alt; // int32_t:Altitude in 1E3 meters (millimeters) above MSL
	p->eph = eph; // uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->epv = epv; // uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->vel = vel; // uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
	p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
55

lm's avatar
lm committed
56
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
James Goppert's avatar
James Goppert committed
57 58 59 60 61 62 63 64 65 66 67 68
}

/**
 * @brief Pack a gps_raw_int message
 * @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
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
69 70 71 72 73 74
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
75 76
 * @return length of the message in bytes (excluding serial stream start sign)
 */
LM's avatar
LM committed
77
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
78
{
lm's avatar
lm committed
79
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
80 81
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;

lm's avatar
lm committed
82 83 84 85
	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->fix_type = fix_type; // uint8_t: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.
	p->lat = lat; // int32_t:Latitude in 1E7 degrees
	p->lon = lon; // int32_t:Longitude in 1E7 degrees
LM's avatar
LM committed
86 87 88 89 90 91
	p->alt = alt; // int32_t:Altitude in 1E3 meters (millimeters) above MSL
	p->eph = eph; // uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->epv = epv; // uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->vel = vel; // uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
	p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
92

lm's avatar
lm committed
93
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
James Goppert's avatar
James Goppert committed
94 95 96 97 98 99 100 101 102 103 104 105
}

/**
 * @brief Encode a gps_raw_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 gps_raw_int C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
LM's avatar
LM committed
106
	return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->hdg, gps_raw_int->satellites_visible);
James Goppert's avatar
James Goppert committed
107 108 109 110 111 112 113 114 115 116
}

/**
 * @brief Send a gps_raw_int message
 * @param chan MAVLink channel to send the message
 *
 * @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 * @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.
 * @param lat Latitude in 1E7 degrees
 * @param lon Longitude in 1E7 degrees
LM's avatar
LM committed
117 118 119 120 121 122
 * @param alt Altitude in 1E3 meters (millimeters) above MSL
 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
 * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
 * @param satellites_visible Number of satellites visible. If unknown, set to 255
James Goppert's avatar
James Goppert committed
123
 */
lm's avatar
lm committed
124 125


126
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
LM's avatar
LM committed
127
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t hdg, uint8_t satellites_visible)
lm's avatar
lm committed
128 129 130 131 132 133 134 135 136 137
{
	mavlink_header_t hdr;
	mavlink_gps_raw_int_t payload;
	uint16_t checksum;
	mavlink_gps_raw_int_t *p = &payload;

	p->usec = usec; // uint64_t:Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	p->fix_type = fix_type; // uint8_t: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.
	p->lat = lat; // int32_t:Latitude in 1E7 degrees
	p->lon = lon; // int32_t:Longitude in 1E7 degrees
LM's avatar
LM committed
138 139 140 141 142 143
	p->alt = alt; // int32_t:Altitude in 1E3 meters (millimeters) above MSL
	p->eph = eph; // uint16_t:GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->epv = epv; // uint16_t:GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
	p->vel = vel; // uint16_t:GPS ground speed (m/s * 100). If unknown, set to: 65535
	p->hdg = hdg; // uint16_t:Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible. If unknown, set to 255
lm's avatar
lm committed
144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
	hdr.msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
162 163 164 165 166 167 168 169 170 171 172 173
}

#endif
// MESSAGE GPS_RAW_INT UNPACKING

/**
 * @brief Get field usec from gps_raw_int message
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
static inline uint64_t mavlink_msg_gps_raw_int_get_usec(const mavlink_message_t* msg)
{
lm's avatar
lm committed
174 175
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (uint64_t)(p->usec);
James Goppert's avatar
James Goppert committed
176 177 178 179 180 181 182 183 184
}

/**
 * @brief Get field fix_type from gps_raw_int message
 *
 * @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.
 */
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
lm's avatar
lm committed
185 186
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (uint8_t)(p->fix_type);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192 193 194 195
}

/**
 * @brief Get field lat from gps_raw_int message
 *
 * @return Latitude in 1E7 degrees
 */
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
lm's avatar
lm committed
196 197
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (int32_t)(p->lat);
James Goppert's avatar
James Goppert committed
198 199 200 201 202 203 204 205 206
}

/**
 * @brief Get field lon from gps_raw_int message
 *
 * @return Longitude in 1E7 degrees
 */
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
lm's avatar
lm committed
207 208
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (int32_t)(p->lon);
James Goppert's avatar
James Goppert committed
209 210 211 212 213
}

/**
 * @brief Get field alt from gps_raw_int message
 *
LM's avatar
LM committed
214
 * @return Altitude in 1E3 meters (millimeters) above MSL
James Goppert's avatar
James Goppert committed
215 216 217
 */
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
lm's avatar
lm committed
218 219
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (int32_t)(p->alt);
James Goppert's avatar
James Goppert committed
220 221 222 223 224
}

/**
 * @brief Get field eph from gps_raw_int message
 *
LM's avatar
LM committed
225
 * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
226
 */
LM's avatar
LM committed
227
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
228
{
lm's avatar
lm committed
229
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
LM's avatar
LM committed
230
	return (uint16_t)(p->eph);
James Goppert's avatar
James Goppert committed
231 232 233 234 235
}

/**
 * @brief Get field epv from gps_raw_int message
 *
LM's avatar
LM committed
236
 * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
237
 */
LM's avatar
LM committed
238
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
239
{
lm's avatar
lm committed
240
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
LM's avatar
LM committed
241
	return (uint16_t)(p->epv);
James Goppert's avatar
James Goppert committed
242 243 244
}

/**
LM's avatar
LM committed
245
 * @brief Get field vel from gps_raw_int message
James Goppert's avatar
James Goppert committed
246
 *
LM's avatar
LM committed
247
 * @return GPS ground speed (m/s * 100). If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
248
 */
LM's avatar
LM committed
249
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
250
{
lm's avatar
lm committed
251
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
LM's avatar
LM committed
252
	return (uint16_t)(p->vel);
James Goppert's avatar
James Goppert committed
253 254 255 256 257
}

/**
 * @brief Get field hdg from gps_raw_int message
 *
LM's avatar
LM committed
258
 * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
James Goppert's avatar
James Goppert committed
259
 */
LM's avatar
LM committed
260
static inline uint16_t mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
James Goppert's avatar
James Goppert committed
261
{
lm's avatar
lm committed
262
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
LM's avatar
LM committed
263 264 265 266 267 268 269 270 271 272 273 274
	return (uint16_t)(p->hdg);
}

/**
 * @brief Get field satellites_visible from gps_raw_int message
 *
 * @return Number of satellites visible. If unknown, set to 255
 */
static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
{
	mavlink_gps_raw_int_t *p = (mavlink_gps_raw_int_t *)&msg->payload[0];
	return (uint8_t)(p->satellites_visible);
James Goppert's avatar
James Goppert committed
275 276 277 278 279 280 281 282 283 284
}

/**
 * @brief Decode a gps_raw_int message into a struct
 *
 * @param msg The message to decode
 * @param gps_raw_int C-struct to decode the message contents into
 */
static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
{
lm's avatar
lm committed
285
	memcpy( gps_raw_int, msg->payload, sizeof(mavlink_gps_raw_int_t));
James Goppert's avatar
James Goppert committed
286
}