mavlink_msg_gps_raw.h 10.9 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE GPS_RAW PACKING

#define MAVLINK_MSG_ID_GPS_RAW 32
LM's avatar
LM committed
4 5
#define MAVLINK_MSG_ID_GPS_RAW_LEN 38
#define MAVLINK_MSG_32_LEN 38
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11 12 13 14 15 16

typedef struct __mavlink_gps_raw_t 
{
	uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
	float lat; ///< Latitude in degrees
	float lon; ///< Longitude in degrees
	float alt; ///< Altitude in meters
	float eph; ///< GPS HDOP
	float epv; ///< GPS VDOP
	float v; ///< GPS ground speed
	float hdg; ///< Compass heading in degrees, 0..360 degrees
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
James Goppert's avatar
James Goppert committed
19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36

} mavlink_gps_raw_t;

/**
 * @brief Pack a gps_raw 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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
37
 * @param satellites_visible Number of satellites visible
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_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
41
{
lm's avatar
lm committed
42
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
43 44
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW;

lm's avatar
lm committed
45 46 47 48 49 50 51 52 53
	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; // float:Latitude in degrees
	p->lon = lon; // float:Longitude in degrees
	p->alt = alt; // float:Altitude in meters
	p->eph = eph; // float:GPS HDOP
	p->epv = epv; // float:GPS VDOP
	p->v = v; // float:GPS ground speed
	p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
54
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
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_LEN);
James Goppert's avatar
James Goppert committed
57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73
}

/**
 * @brief Pack a gps_raw 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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
74
 * @param satellites_visible Number of satellites visible
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_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
James Goppert's avatar
James Goppert committed
78
{
lm's avatar
lm committed
79
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
80 81
	msg->msgid = MAVLINK_MSG_ID_GPS_RAW;

lm's avatar
lm committed
82 83 84 85 86 87 88 89 90
	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; // float:Latitude in degrees
	p->lon = lon; // float:Longitude in degrees
	p->alt = alt; // float:Altitude in meters
	p->eph = eph; // float:GPS HDOP
	p->epv = epv; // float:GPS VDOP
	p->v = v; // float:GPS ground speed
	p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
91
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
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_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 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 C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
{
LM's avatar
LM committed
106
	return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg, gps_raw->satellites_visible);
James Goppert's avatar
James Goppert committed
107 108 109 110 111 112 113 114 115 116 117 118 119 120 121
}

/**
 * @brief Send a gps_raw 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 degrees
 * @param lon Longitude in degrees
 * @param alt Altitude in meters
 * @param eph GPS HDOP
 * @param epv GPS VDOP
 * @param v GPS ground speed
 * @param hdg Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
122
 * @param satellites_visible Number of satellites visible
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_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg, uint8_t satellites_visible)
lm's avatar
lm committed
128 129 130 131 132 133 134 135 136 137 138 139 140 141 142
{
	mavlink_header_t hdr;
	mavlink_gps_raw_t payload;
	uint16_t checksum;
	mavlink_gps_raw_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; // float:Latitude in degrees
	p->lon = lon; // float:Longitude in degrees
	p->alt = alt; // float:Altitude in meters
	p->eph = eph; // float:GPS HDOP
	p->epv = epv; // float:GPS VDOP
	p->v = v; // float:GPS ground speed
	p->hdg = hdg; // float:Compass heading in degrees, 0..360 degrees
LM's avatar
LM committed
143
	p->satellites_visible = satellites_visible; // uint8_t:Number of satellites visible
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_LEN;
	hdr.msgid = MAVLINK_MSG_ID_GPS_RAW;
	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 UNPACKING

/**
 * @brief Get field usec from gps_raw message
 *
 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
 */
static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
{
lm's avatar
lm committed
174 175
	mavlink_gps_raw_t *p = (mavlink_gps_raw_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 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_get_fix_type(const mavlink_message_t* msg)
{
lm's avatar
lm committed
185 186
	mavlink_gps_raw_t *p = (mavlink_gps_raw_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 message
 *
 * @return Latitude in degrees
 */
static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
{
lm's avatar
lm committed
196 197
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(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 message
 *
 * @return Longitude in degrees
 */
static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
{
lm's avatar
lm committed
207 208
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->lon);
James Goppert's avatar
James Goppert committed
209 210 211 212 213 214 215 216 217
}

/**
 * @brief Get field alt from gps_raw message
 *
 * @return Altitude in meters
 */
static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
{
lm's avatar
lm committed
218 219
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->alt);
James Goppert's avatar
James Goppert committed
220 221 222 223 224 225 226 227 228
}

/**
 * @brief Get field eph from gps_raw message
 *
 * @return GPS HDOP
 */
static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
{
lm's avatar
lm committed
229 230
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->eph);
James Goppert's avatar
James Goppert committed
231 232 233 234 235 236 237 238 239
}

/**
 * @brief Get field epv from gps_raw message
 *
 * @return GPS VDOP
 */
static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
{
lm's avatar
lm committed
240 241
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->epv);
James Goppert's avatar
James Goppert committed
242 243 244 245 246 247 248 249 250
}

/**
 * @brief Get field v from gps_raw message
 *
 * @return GPS ground speed
 */
static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
{
lm's avatar
lm committed
251 252
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->v);
James Goppert's avatar
James Goppert committed
253 254 255 256 257 258 259 260 261
}

/**
 * @brief Get field hdg from gps_raw message
 *
 * @return Compass heading in degrees, 0..360 degrees
 */
static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
{
lm's avatar
lm committed
262 263
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (float)(p->hdg);
James Goppert's avatar
James Goppert committed
264 265
}

LM's avatar
LM committed
266 267 268 269 270 271 272 273 274 275 276
/**
 * @brief Get field satellites_visible from gps_raw message
 *
 * @return Number of satellites visible
 */
static inline uint8_t mavlink_msg_gps_raw_get_satellites_visible(const mavlink_message_t* msg)
{
	mavlink_gps_raw_t *p = (mavlink_gps_raw_t *)&msg->payload[0];
	return (uint8_t)(p->satellites_visible);
}

James Goppert's avatar
James Goppert committed
277 278 279 280 281 282 283 284
/**
 * @brief Decode a gps_raw message into a struct
 *
 * @param msg The message to decode
 * @param gps_raw C-struct to decode the message contents into
 */
static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
{
lm's avatar
lm committed
285
	memcpy( gps_raw, msg->payload, sizeof(mavlink_gps_raw_t));
James Goppert's avatar
James Goppert committed
286
}