2 // MESSAGE GPS_RAW_INT PACKING
4 #define MAVLINK_MSG_ID_GPS_RAW_INT 24
7 typedef struct __mavlink_gps_raw_int_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, EGM96 ellipsoid)*/
10 int32_t lon
; /*< [degE7] Longitude (WGS84, EGM96 ellipsoid)*/
11 int32_t alt
; /*< [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.*/
12 uint16_t eph
; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
13 uint16_t epv
; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
14 uint16_t vel
; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
15 uint16_t cog
; /*< [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
16 uint8_t fix_type
; /*< GPS fix type.*/
17 uint8_t satellites_visible
; /*< Number of satellites visible. If unknown, set to 255*/
18 int32_t alt_ellipsoid
; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/
19 uint32_t h_acc
; /*< [mm] Position uncertainty.*/
20 uint32_t v_acc
; /*< [mm] Altitude uncertainty.*/
21 uint32_t vel_acc
; /*< [mm] Speed uncertainty.*/
22 uint32_t hdg_acc
; /*< [degE5] Heading / track uncertainty*/
23 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.*/
24 }) mavlink_gps_raw_int_t
;
26 #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 52
27 #define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
28 #define MAVLINK_MSG_ID_24_LEN 52
29 #define MAVLINK_MSG_ID_24_MIN_LEN 30
31 #define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
32 #define MAVLINK_MSG_ID_24_CRC 24
36 #if MAVLINK_COMMAND_24BIT
37 #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
41 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
42 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
43 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
44 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
45 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
46 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
47 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
48 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
49 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
50 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
51 { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
52 { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
53 { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
54 { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
55 { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
56 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
60 #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
63 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
64 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
65 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
66 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
67 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
68 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
69 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
70 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
71 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
72 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
73 { "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
74 { "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
75 { "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
76 { "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
77 { "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
78 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
84 * @brief Pack a gps_raw_int message
85 * @param system_id ID of this system
86 * @param component_id ID of this component (e.g. 200 for IMU)
87 * @param msg The MAVLink message to compress the data into
89 * @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.
90 * @param fix_type GPS fix type.
91 * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
92 * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
93 * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
94 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
95 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
96 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
97 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
98 * @param satellites_visible Number of satellites visible. If unknown, set to 255
99 * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
100 * @param h_acc [mm] Position uncertainty.
101 * @param v_acc [mm] Altitude uncertainty.
102 * @param vel_acc [mm] Speed uncertainty.
103 * @param hdg_acc [degE5] Heading / track uncertainty
104 * @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.
105 * @return length of the message in bytes (excluding serial stream start sign)
107 static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
108 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
, int32_t alt_ellipsoid
, uint32_t h_acc
, uint32_t v_acc
, uint32_t vel_acc
, uint32_t hdg_acc
, uint16_t yaw
)
110 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
111 char buf
[MAVLINK_MSG_ID_GPS_RAW_INT_LEN
];
112 _mav_put_uint64_t(buf
, 0, time_usec
);
113 _mav_put_int32_t(buf
, 8, lat
);
114 _mav_put_int32_t(buf
, 12, lon
);
115 _mav_put_int32_t(buf
, 16, alt
);
116 _mav_put_uint16_t(buf
, 20, eph
);
117 _mav_put_uint16_t(buf
, 22, epv
);
118 _mav_put_uint16_t(buf
, 24, vel
);
119 _mav_put_uint16_t(buf
, 26, cog
);
120 _mav_put_uint8_t(buf
, 28, fix_type
);
121 _mav_put_uint8_t(buf
, 29, satellites_visible
);
122 _mav_put_int32_t(buf
, 30, alt_ellipsoid
);
123 _mav_put_uint32_t(buf
, 34, h_acc
);
124 _mav_put_uint32_t(buf
, 38, v_acc
);
125 _mav_put_uint32_t(buf
, 42, vel_acc
);
126 _mav_put_uint32_t(buf
, 46, hdg_acc
);
127 _mav_put_uint16_t(buf
, 50, yaw
);
129 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
);
131 mavlink_gps_raw_int_t packet
;
132 packet
.time_usec
= time_usec
;
140 packet
.fix_type
= fix_type
;
141 packet
.satellites_visible
= satellites_visible
;
142 packet
.alt_ellipsoid
= alt_ellipsoid
;
143 packet
.h_acc
= h_acc
;
144 packet
.v_acc
= v_acc
;
145 packet
.vel_acc
= vel_acc
;
146 packet
.hdg_acc
= hdg_acc
;
149 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
);
152 msg
->msgid
= MAVLINK_MSG_ID_GPS_RAW_INT
;
153 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
157 * @brief Pack a gps_raw_int message on a channel
158 * @param system_id ID of this system
159 * @param component_id ID of this component (e.g. 200 for IMU)
160 * @param chan The MAVLink channel this message will be sent over
161 * @param msg The MAVLink message to compress the data into
162 * @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.
163 * @param fix_type GPS fix type.
164 * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
165 * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
166 * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
167 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
168 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
169 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
170 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
171 * @param satellites_visible Number of satellites visible. If unknown, set to 255
172 * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
173 * @param h_acc [mm] Position uncertainty.
174 * @param v_acc [mm] Altitude uncertainty.
175 * @param vel_acc [mm] Speed uncertainty.
176 * @param hdg_acc [degE5] Heading / track uncertainty
177 * @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.
178 * @return length of the message in bytes (excluding serial stream start sign)
180 static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
181 mavlink_message_t
* msg
,
182 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
,int32_t alt_ellipsoid
,uint32_t h_acc
,uint32_t v_acc
,uint32_t vel_acc
,uint32_t hdg_acc
,uint16_t yaw
)
184 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
185 char buf
[MAVLINK_MSG_ID_GPS_RAW_INT_LEN
];
186 _mav_put_uint64_t(buf
, 0, time_usec
);
187 _mav_put_int32_t(buf
, 8, lat
);
188 _mav_put_int32_t(buf
, 12, lon
);
189 _mav_put_int32_t(buf
, 16, alt
);
190 _mav_put_uint16_t(buf
, 20, eph
);
191 _mav_put_uint16_t(buf
, 22, epv
);
192 _mav_put_uint16_t(buf
, 24, vel
);
193 _mav_put_uint16_t(buf
, 26, cog
);
194 _mav_put_uint8_t(buf
, 28, fix_type
);
195 _mav_put_uint8_t(buf
, 29, satellites_visible
);
196 _mav_put_int32_t(buf
, 30, alt_ellipsoid
);
197 _mav_put_uint32_t(buf
, 34, h_acc
);
198 _mav_put_uint32_t(buf
, 38, v_acc
);
199 _mav_put_uint32_t(buf
, 42, vel_acc
);
200 _mav_put_uint32_t(buf
, 46, hdg_acc
);
201 _mav_put_uint16_t(buf
, 50, yaw
);
203 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
);
205 mavlink_gps_raw_int_t packet
;
206 packet
.time_usec
= time_usec
;
214 packet
.fix_type
= fix_type
;
215 packet
.satellites_visible
= satellites_visible
;
216 packet
.alt_ellipsoid
= alt_ellipsoid
;
217 packet
.h_acc
= h_acc
;
218 packet
.v_acc
= v_acc
;
219 packet
.vel_acc
= vel_acc
;
220 packet
.hdg_acc
= hdg_acc
;
223 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
);
226 msg
->msgid
= MAVLINK_MSG_ID_GPS_RAW_INT
;
227 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
231 * @brief Encode a gps_raw_int struct
233 * @param system_id ID of this system
234 * @param component_id ID of this component (e.g. 200 for IMU)
235 * @param msg The MAVLink message to compress the data into
236 * @param gps_raw_int C-struct to read the message contents from
238 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
)
240 return mavlink_msg_gps_raw_int_pack(system_id
, component_id
, msg
, gps_raw_int
->time_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
->cog
, gps_raw_int
->satellites_visible
, gps_raw_int
->alt_ellipsoid
, gps_raw_int
->h_acc
, gps_raw_int
->v_acc
, gps_raw_int
->vel_acc
, gps_raw_int
->hdg_acc
, gps_raw_int
->yaw
);
244 * @brief Encode a gps_raw_int struct on a channel
246 * @param system_id ID of this system
247 * @param component_id ID of this component (e.g. 200 for IMU)
248 * @param chan The MAVLink channel this message will be sent over
249 * @param msg The MAVLink message to compress the data into
250 * @param gps_raw_int C-struct to read the message contents from
252 static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_gps_raw_int_t
* gps_raw_int
)
254 return mavlink_msg_gps_raw_int_pack_chan(system_id
, component_id
, chan
, msg
, gps_raw_int
->time_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
->cog
, gps_raw_int
->satellites_visible
, gps_raw_int
->alt_ellipsoid
, gps_raw_int
->h_acc
, gps_raw_int
->v_acc
, gps_raw_int
->vel_acc
, gps_raw_int
->hdg_acc
, gps_raw_int
->yaw
);
258 * @brief Send a gps_raw_int message
259 * @param chan MAVLink channel to send the message
261 * @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.
262 * @param fix_type GPS fix type.
263 * @param lat [degE7] Latitude (WGS84, EGM96 ellipsoid)
264 * @param lon [degE7] Longitude (WGS84, EGM96 ellipsoid)
265 * @param alt [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
266 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
267 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
268 * @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
269 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
270 * @param satellites_visible Number of satellites visible. If unknown, set to 255
271 * @param alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
272 * @param h_acc [mm] Position uncertainty.
273 * @param v_acc [mm] Altitude uncertainty.
274 * @param vel_acc [mm] Speed uncertainty.
275 * @param hdg_acc [degE5] Heading / track uncertainty
276 * @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.
278 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
280 static inline void mavlink_msg_gps_raw_int_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
, int32_t alt_ellipsoid
, uint32_t h_acc
, uint32_t v_acc
, uint32_t vel_acc
, uint32_t hdg_acc
, uint16_t yaw
)
282 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
283 char buf
[MAVLINK_MSG_ID_GPS_RAW_INT_LEN
];
284 _mav_put_uint64_t(buf
, 0, time_usec
);
285 _mav_put_int32_t(buf
, 8, lat
);
286 _mav_put_int32_t(buf
, 12, lon
);
287 _mav_put_int32_t(buf
, 16, alt
);
288 _mav_put_uint16_t(buf
, 20, eph
);
289 _mav_put_uint16_t(buf
, 22, epv
);
290 _mav_put_uint16_t(buf
, 24, vel
);
291 _mav_put_uint16_t(buf
, 26, cog
);
292 _mav_put_uint8_t(buf
, 28, fix_type
);
293 _mav_put_uint8_t(buf
, 29, satellites_visible
);
294 _mav_put_int32_t(buf
, 30, alt_ellipsoid
);
295 _mav_put_uint32_t(buf
, 34, h_acc
);
296 _mav_put_uint32_t(buf
, 38, v_acc
);
297 _mav_put_uint32_t(buf
, 42, vel_acc
);
298 _mav_put_uint32_t(buf
, 46, hdg_acc
);
299 _mav_put_uint16_t(buf
, 50, yaw
);
301 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, buf
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
303 mavlink_gps_raw_int_t packet
;
304 packet
.time_usec
= time_usec
;
312 packet
.fix_type
= fix_type
;
313 packet
.satellites_visible
= satellites_visible
;
314 packet
.alt_ellipsoid
= alt_ellipsoid
;
315 packet
.h_acc
= h_acc
;
316 packet
.v_acc
= v_acc
;
317 packet
.vel_acc
= vel_acc
;
318 packet
.hdg_acc
= hdg_acc
;
321 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, (const char *)&packet
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
326 * @brief Send a gps_raw_int message
327 * @param chan MAVLink channel to send the message
328 * @param struct The MAVLink struct to serialize
330 static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan
, const mavlink_gps_raw_int_t
* gps_raw_int
)
332 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
333 mavlink_msg_gps_raw_int_send(chan
, gps_raw_int
->time_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
->cog
, gps_raw_int
->satellites_visible
, gps_raw_int
->alt_ellipsoid
, gps_raw_int
->h_acc
, gps_raw_int
->v_acc
, gps_raw_int
->vel_acc
, gps_raw_int
->hdg_acc
, gps_raw_int
->yaw
);
335 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, (const char *)gps_raw_int
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
339 #if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
341 This varient of _send() can be used to save stack space by re-using
342 memory from the receive buffer. The caller provides a
343 mavlink_message_t which is the size of a full mavlink message. This
344 is usually the receive buffer for the channel, and allows a reply to an
345 incoming message with minimum stack space usage.
347 static inline void mavlink_msg_gps_raw_int_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
, int32_t alt_ellipsoid
, uint32_t h_acc
, uint32_t v_acc
, uint32_t vel_acc
, uint32_t hdg_acc
, uint16_t yaw
)
349 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
350 char *buf
= (char *)msgbuf
;
351 _mav_put_uint64_t(buf
, 0, time_usec
);
352 _mav_put_int32_t(buf
, 8, lat
);
353 _mav_put_int32_t(buf
, 12, lon
);
354 _mav_put_int32_t(buf
, 16, alt
);
355 _mav_put_uint16_t(buf
, 20, eph
);
356 _mav_put_uint16_t(buf
, 22, epv
);
357 _mav_put_uint16_t(buf
, 24, vel
);
358 _mav_put_uint16_t(buf
, 26, cog
);
359 _mav_put_uint8_t(buf
, 28, fix_type
);
360 _mav_put_uint8_t(buf
, 29, satellites_visible
);
361 _mav_put_int32_t(buf
, 30, alt_ellipsoid
);
362 _mav_put_uint32_t(buf
, 34, h_acc
);
363 _mav_put_uint32_t(buf
, 38, v_acc
);
364 _mav_put_uint32_t(buf
, 42, vel_acc
);
365 _mav_put_uint32_t(buf
, 46, hdg_acc
);
366 _mav_put_uint16_t(buf
, 50, yaw
);
368 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, buf
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
370 mavlink_gps_raw_int_t
*packet
= (mavlink_gps_raw_int_t
*)msgbuf
;
371 packet
->time_usec
= time_usec
;
379 packet
->fix_type
= fix_type
;
380 packet
->satellites_visible
= satellites_visible
;
381 packet
->alt_ellipsoid
= alt_ellipsoid
;
382 packet
->h_acc
= h_acc
;
383 packet
->v_acc
= v_acc
;
384 packet
->vel_acc
= vel_acc
;
385 packet
->hdg_acc
= hdg_acc
;
388 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, (const char *)packet
, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
, MAVLINK_MSG_ID_GPS_RAW_INT_CRC
);
395 // MESSAGE GPS_RAW_INT UNPACKING
399 * @brief Get field time_usec from gps_raw_int message
401 * @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.
403 static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t
* msg
)
405 return _MAV_RETURN_uint64_t(msg
, 0);
409 * @brief Get field fix_type from gps_raw_int message
411 * @return GPS fix type.
413 static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t
* msg
)
415 return _MAV_RETURN_uint8_t(msg
, 28);
419 * @brief Get field lat from gps_raw_int message
421 * @return [degE7] Latitude (WGS84, EGM96 ellipsoid)
423 static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t
* msg
)
425 return _MAV_RETURN_int32_t(msg
, 8);
429 * @brief Get field lon from gps_raw_int message
431 * @return [degE7] Longitude (WGS84, EGM96 ellipsoid)
433 static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t
* msg
)
435 return _MAV_RETURN_int32_t(msg
, 12);
439 * @brief Get field alt from gps_raw_int message
441 * @return [mm] Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude.
443 static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t
* msg
)
445 return _MAV_RETURN_int32_t(msg
, 16);
449 * @brief Get field eph from gps_raw_int message
451 * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
453 static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t
* msg
)
455 return _MAV_RETURN_uint16_t(msg
, 20);
459 * @brief Get field epv from gps_raw_int message
461 * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
463 static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t
* msg
)
465 return _MAV_RETURN_uint16_t(msg
, 22);
469 * @brief Get field vel from gps_raw_int message
471 * @return [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
473 static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t
* msg
)
475 return _MAV_RETURN_uint16_t(msg
, 24);
479 * @brief Get field cog from gps_raw_int message
481 * @return [cdeg] Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
483 static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t
* msg
)
485 return _MAV_RETURN_uint16_t(msg
, 26);
489 * @brief Get field satellites_visible from gps_raw_int message
491 * @return Number of satellites visible. If unknown, set to 255
493 static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t
* msg
)
495 return _MAV_RETURN_uint8_t(msg
, 29);
499 * @brief Get field alt_ellipsoid from gps_raw_int message
501 * @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
503 static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t
* msg
)
505 return _MAV_RETURN_int32_t(msg
, 30);
509 * @brief Get field h_acc from gps_raw_int message
511 * @return [mm] Position uncertainty.
513 static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t
* msg
)
515 return _MAV_RETURN_uint32_t(msg
, 34);
519 * @brief Get field v_acc from gps_raw_int message
521 * @return [mm] Altitude uncertainty.
523 static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t
* msg
)
525 return _MAV_RETURN_uint32_t(msg
, 38);
529 * @brief Get field vel_acc from gps_raw_int message
531 * @return [mm] Speed uncertainty.
533 static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t
* msg
)
535 return _MAV_RETURN_uint32_t(msg
, 42);
539 * @brief Get field hdg_acc from gps_raw_int message
541 * @return [degE5] Heading / track uncertainty
543 static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t
* msg
)
545 return _MAV_RETURN_uint32_t(msg
, 46);
549 * @brief Get field yaw from gps_raw_int message
551 * @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.
553 static inline uint16_t mavlink_msg_gps_raw_int_get_yaw(const mavlink_message_t
* msg
)
555 return _MAV_RETURN_uint16_t(msg
, 50);
559 * @brief Decode a gps_raw_int message into a struct
561 * @param msg The message to decode
562 * @param gps_raw_int C-struct to decode the message contents into
564 static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t
* msg
, mavlink_gps_raw_int_t
* gps_raw_int
)
566 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
567 gps_raw_int
->time_usec
= mavlink_msg_gps_raw_int_get_time_usec(msg
);
568 gps_raw_int
->lat
= mavlink_msg_gps_raw_int_get_lat(msg
);
569 gps_raw_int
->lon
= mavlink_msg_gps_raw_int_get_lon(msg
);
570 gps_raw_int
->alt
= mavlink_msg_gps_raw_int_get_alt(msg
);
571 gps_raw_int
->eph
= mavlink_msg_gps_raw_int_get_eph(msg
);
572 gps_raw_int
->epv
= mavlink_msg_gps_raw_int_get_epv(msg
);
573 gps_raw_int
->vel
= mavlink_msg_gps_raw_int_get_vel(msg
);
574 gps_raw_int
->cog
= mavlink_msg_gps_raw_int_get_cog(msg
);
575 gps_raw_int
->fix_type
= mavlink_msg_gps_raw_int_get_fix_type(msg
);
576 gps_raw_int
->satellites_visible
= mavlink_msg_gps_raw_int_get_satellites_visible(msg
);
577 gps_raw_int
->alt_ellipsoid
= mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg
);
578 gps_raw_int
->h_acc
= mavlink_msg_gps_raw_int_get_h_acc(msg
);
579 gps_raw_int
->v_acc
= mavlink_msg_gps_raw_int_get_v_acc(msg
);
580 gps_raw_int
->vel_acc
= mavlink_msg_gps_raw_int_get_vel_acc(msg
);
581 gps_raw_int
->hdg_acc
= mavlink_msg_gps_raw_int_get_hdg_acc(msg
);
582 gps_raw_int
->yaw
= mavlink_msg_gps_raw_int_get_yaw(msg
);
584 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_GPS_RAW_INT_LEN
? msg
->len
: MAVLINK_MSG_ID_GPS_RAW_INT_LEN
;
585 memset(gps_raw_int
, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN
);
586 memcpy(gps_raw_int
, _MAV_PAYLOAD(msg
), len
);