Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / lib / main / MAVLink / common / mavlink_msg_gps2_raw.h
blob5e741ef4930488b30e4650ab7344f519040b5173
1 #pragma once
2 // MESSAGE GPS2_RAW PACKING
4 #define MAVLINK_MSG_ID_GPS2_RAW 124
6 MAVPACKED(
7 typedef struct __mavlink_gps2_raw_t {
8 uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
9 int32_t lat; /*< [degE7] Latitude (WGS84)*/
10 int32_t lon; /*< [degE7] Longitude (WGS84)*/
11 int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/
12 uint32_t dgps_age; /*< [ms] Age of DGPS info*/
13 uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
14 uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
15 uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
16 uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
17 uint8_t fix_type; /*< GPS fix type.*/
18 uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
19 uint8_t dgps_numch; /*< Number of DGPS satellites*/
20 uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/
21 }) mavlink_gps2_raw_t;
23 #define MAVLINK_MSG_ID_GPS2_RAW_LEN 37
24 #define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35
25 #define MAVLINK_MSG_ID_124_LEN 37
26 #define MAVLINK_MSG_ID_124_MIN_LEN 35
28 #define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
29 #define MAVLINK_MSG_ID_124_CRC 87
33 #if MAVLINK_COMMAND_24BIT
34 #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
35 124, \
36 "GPS2_RAW", \
37 13, \
38 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
39 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
40 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
41 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
42 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
43 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
44 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
45 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
46 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
47 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
48 { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
49 { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
50 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
51 } \
53 #else
54 #define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
55 "GPS2_RAW", \
56 13, \
57 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
58 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
59 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
60 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
61 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
62 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
63 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
64 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
65 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
66 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
67 { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
68 { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
69 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
70 } \
72 #endif
74 /**
75 * @brief Pack a gps2_raw message
76 * @param system_id ID of this system
77 * @param component_id ID of this component (e.g. 200 for IMU)
78 * @param msg The MAVLink message to compress the data into
80 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
81 * @param fix_type GPS fix type.
82 * @param lat [degE7] Latitude (WGS84)
83 * @param lon [degE7] Longitude (WGS84)
84 * @param alt [mm] Altitude (MSL). Positive for up.
85 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
86 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
87 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
88 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
89 * @param satellites_visible Number of satellites visible. If unknown, set to 255
90 * @param dgps_numch Number of DGPS satellites
91 * @param dgps_age [ms] Age of DGPS info
92 * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
93 * @return length of the message in bytes (excluding serial stream start sign)
95 static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
96 uint64_t time_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 cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw)
98 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
100 _mav_put_uint64_t(buf, 0, time_usec);
101 _mav_put_int32_t(buf, 8, lat);
102 _mav_put_int32_t(buf, 12, lon);
103 _mav_put_int32_t(buf, 16, alt);
104 _mav_put_uint32_t(buf, 20, dgps_age);
105 _mav_put_uint16_t(buf, 24, eph);
106 _mav_put_uint16_t(buf, 26, epv);
107 _mav_put_uint16_t(buf, 28, vel);
108 _mav_put_uint16_t(buf, 30, cog);
109 _mav_put_uint8_t(buf, 32, fix_type);
110 _mav_put_uint8_t(buf, 33, satellites_visible);
111 _mav_put_uint8_t(buf, 34, dgps_numch);
112 _mav_put_uint16_t(buf, 35, yaw);
114 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
115 #else
116 mavlink_gps2_raw_t packet;
117 packet.time_usec = time_usec;
118 packet.lat = lat;
119 packet.lon = lon;
120 packet.alt = alt;
121 packet.dgps_age = dgps_age;
122 packet.eph = eph;
123 packet.epv = epv;
124 packet.vel = vel;
125 packet.cog = cog;
126 packet.fix_type = fix_type;
127 packet.satellites_visible = satellites_visible;
128 packet.dgps_numch = dgps_numch;
129 packet.yaw = yaw;
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
132 #endif
134 msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
135 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
139 * @brief Pack a gps2_raw message on a channel
140 * @param system_id ID of this system
141 * @param component_id ID of this component (e.g. 200 for IMU)
142 * @param chan The MAVLink channel this message will be sent over
143 * @param msg The MAVLink message to compress the data into
144 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
145 * @param fix_type GPS fix type.
146 * @param lat [degE7] Latitude (WGS84)
147 * @param lon [degE7] Longitude (WGS84)
148 * @param alt [mm] Altitude (MSL). Positive for up.
149 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
150 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
151 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
152 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
153 * @param satellites_visible Number of satellites visible. If unknown, set to 255
154 * @param dgps_numch Number of DGPS satellites
155 * @param dgps_age [ms] Age of DGPS info
156 * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
157 * @return length of the message in bytes (excluding serial stream start sign)
159 static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
160 mavlink_message_t* msg,
161 uint64_t time_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 cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age,uint16_t yaw)
163 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
164 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
165 _mav_put_uint64_t(buf, 0, time_usec);
166 _mav_put_int32_t(buf, 8, lat);
167 _mav_put_int32_t(buf, 12, lon);
168 _mav_put_int32_t(buf, 16, alt);
169 _mav_put_uint32_t(buf, 20, dgps_age);
170 _mav_put_uint16_t(buf, 24, eph);
171 _mav_put_uint16_t(buf, 26, epv);
172 _mav_put_uint16_t(buf, 28, vel);
173 _mav_put_uint16_t(buf, 30, cog);
174 _mav_put_uint8_t(buf, 32, fix_type);
175 _mav_put_uint8_t(buf, 33, satellites_visible);
176 _mav_put_uint8_t(buf, 34, dgps_numch);
177 _mav_put_uint16_t(buf, 35, yaw);
179 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
180 #else
181 mavlink_gps2_raw_t packet;
182 packet.time_usec = time_usec;
183 packet.lat = lat;
184 packet.lon = lon;
185 packet.alt = alt;
186 packet.dgps_age = dgps_age;
187 packet.eph = eph;
188 packet.epv = epv;
189 packet.vel = vel;
190 packet.cog = cog;
191 packet.fix_type = fix_type;
192 packet.satellites_visible = satellites_visible;
193 packet.dgps_numch = dgps_numch;
194 packet.yaw = yaw;
196 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
197 #endif
199 msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
200 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
204 * @brief Encode a gps2_raw struct
206 * @param system_id ID of this system
207 * @param component_id ID of this component (e.g. 200 for IMU)
208 * @param msg The MAVLink message to compress the data into
209 * @param gps2_raw C-struct to read the message contents from
211 static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
213 return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw);
217 * @brief Encode a gps2_raw struct on a channel
219 * @param system_id ID of this system
220 * @param component_id ID of this component (e.g. 200 for IMU)
221 * @param chan The MAVLink channel this message will be sent over
222 * @param msg The MAVLink message to compress the data into
223 * @param gps2_raw C-struct to read the message contents from
225 static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
227 return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw);
231 * @brief Send a gps2_raw message
232 * @param chan MAVLink channel to send the message
234 * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
235 * @param fix_type GPS fix type.
236 * @param lat [degE7] Latitude (WGS84)
237 * @param lon [degE7] Longitude (WGS84)
238 * @param alt [mm] Altitude (MSL). Positive for up.
239 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
240 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
241 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
242 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
243 * @param satellites_visible Number of satellites visible. If unknown, set to 255
244 * @param dgps_numch Number of DGPS satellites
245 * @param dgps_age [ms] Age of DGPS info
246 * @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
248 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
250 static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw)
252 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
253 char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
254 _mav_put_uint64_t(buf, 0, time_usec);
255 _mav_put_int32_t(buf, 8, lat);
256 _mav_put_int32_t(buf, 12, lon);
257 _mav_put_int32_t(buf, 16, alt);
258 _mav_put_uint32_t(buf, 20, dgps_age);
259 _mav_put_uint16_t(buf, 24, eph);
260 _mav_put_uint16_t(buf, 26, epv);
261 _mav_put_uint16_t(buf, 28, vel);
262 _mav_put_uint16_t(buf, 30, cog);
263 _mav_put_uint8_t(buf, 32, fix_type);
264 _mav_put_uint8_t(buf, 33, satellites_visible);
265 _mav_put_uint8_t(buf, 34, dgps_numch);
266 _mav_put_uint16_t(buf, 35, yaw);
268 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
269 #else
270 mavlink_gps2_raw_t packet;
271 packet.time_usec = time_usec;
272 packet.lat = lat;
273 packet.lon = lon;
274 packet.alt = alt;
275 packet.dgps_age = dgps_age;
276 packet.eph = eph;
277 packet.epv = epv;
278 packet.vel = vel;
279 packet.cog = cog;
280 packet.fix_type = fix_type;
281 packet.satellites_visible = satellites_visible;
282 packet.dgps_numch = dgps_numch;
283 packet.yaw = yaw;
285 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
286 #endif
290 * @brief Send a gps2_raw message
291 * @param chan MAVLink channel to send the message
292 * @param struct The MAVLink struct to serialize
294 static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw)
296 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
297 mavlink_msg_gps2_raw_send(chan, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age, gps2_raw->yaw);
298 #else
299 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
300 #endif
303 #if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
305 This varient of _send() can be used to save stack space by re-using
306 memory from the receive buffer. The caller provides a
307 mavlink_message_t which is the size of a full mavlink message. This
308 is usually the receive buffer for the channel, and allows a reply to an
309 incoming message with minimum stack space usage.
311 static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_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 cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age, uint16_t yaw)
313 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
314 char *buf = (char *)msgbuf;
315 _mav_put_uint64_t(buf, 0, time_usec);
316 _mav_put_int32_t(buf, 8, lat);
317 _mav_put_int32_t(buf, 12, lon);
318 _mav_put_int32_t(buf, 16, alt);
319 _mav_put_uint32_t(buf, 20, dgps_age);
320 _mav_put_uint16_t(buf, 24, eph);
321 _mav_put_uint16_t(buf, 26, epv);
322 _mav_put_uint16_t(buf, 28, vel);
323 _mav_put_uint16_t(buf, 30, cog);
324 _mav_put_uint8_t(buf, 32, fix_type);
325 _mav_put_uint8_t(buf, 33, satellites_visible);
326 _mav_put_uint8_t(buf, 34, dgps_numch);
327 _mav_put_uint16_t(buf, 35, yaw);
329 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
330 #else
331 mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
332 packet->time_usec = time_usec;
333 packet->lat = lat;
334 packet->lon = lon;
335 packet->alt = alt;
336 packet->dgps_age = dgps_age;
337 packet->eph = eph;
338 packet->epv = epv;
339 packet->vel = vel;
340 packet->cog = cog;
341 packet->fix_type = fix_type;
342 packet->satellites_visible = satellites_visible;
343 packet->dgps_numch = dgps_numch;
344 packet->yaw = yaw;
346 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
347 #endif
349 #endif
351 #endif
353 // MESSAGE GPS2_RAW UNPACKING
357 * @brief Get field time_usec from gps2_raw message
359 * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
361 static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
363 return _MAV_RETURN_uint64_t(msg, 0);
367 * @brief Get field fix_type from gps2_raw message
369 * @return GPS fix type.
371 static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg)
373 return _MAV_RETURN_uint8_t(msg, 32);
377 * @brief Get field lat from gps2_raw message
379 * @return [degE7] Latitude (WGS84)
381 static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
383 return _MAV_RETURN_int32_t(msg, 8);
387 * @brief Get field lon from gps2_raw message
389 * @return [degE7] Longitude (WGS84)
391 static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
393 return _MAV_RETURN_int32_t(msg, 12);
397 * @brief Get field alt from gps2_raw message
399 * @return [mm] Altitude (MSL). Positive for up.
401 static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
403 return _MAV_RETURN_int32_t(msg, 16);
407 * @brief Get field eph from gps2_raw message
409 * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
411 static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
413 return _MAV_RETURN_uint16_t(msg, 24);
417 * @brief Get field epv from gps2_raw message
419 * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
421 static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
423 return _MAV_RETURN_uint16_t(msg, 26);
427 * @brief Get field vel from gps2_raw message
429 * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
431 static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
433 return _MAV_RETURN_uint16_t(msg, 28);
437 * @brief Get field cog from gps2_raw message
439 * @return [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
441 static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
443 return _MAV_RETURN_uint16_t(msg, 30);
447 * @brief Get field satellites_visible from gps2_raw message
449 * @return Number of satellites visible. If unknown, set to 255
451 static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
453 return _MAV_RETURN_uint8_t(msg, 33);
457 * @brief Get field dgps_numch from gps2_raw message
459 * @return Number of DGPS satellites
461 static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
463 return _MAV_RETURN_uint8_t(msg, 34);
467 * @brief Get field dgps_age from gps2_raw message
469 * @return [ms] Age of DGPS info
471 static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
473 return _MAV_RETURN_uint32_t(msg, 20);
477 * @brief Get field yaw from gps2_raw message
479 * @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
481 static inline uint16_t mavlink_msg_gps2_raw_get_yaw(const mavlink_message_t* msg)
483 return _MAV_RETURN_uint16_t(msg, 35);
487 * @brief Decode a gps2_raw message into a struct
489 * @param msg The message to decode
490 * @param gps2_raw C-struct to decode the message contents into
492 static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
494 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
495 gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
496 gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg);
497 gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg);
498 gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg);
499 gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
500 gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg);
501 gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg);
502 gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg);
503 gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg);
504 gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
505 gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg);
506 gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
507 gps2_raw->yaw = mavlink_msg_gps2_raw_get_yaw(msg);
508 #else
509 uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN;
510 memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN);
511 memcpy(gps2_raw, _MAV_PAYLOAD(msg), len);
512 #endif