1 // MESSAGE GPS_RAW_INT PACKING
3 #define MAVLINK_MSG_ID_GPS_RAW_INT 24
5 typedef struct __mavlink_gps_raw_int_t
{
6 uint64_t time_usec
; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
7 int32_t lat
; ///< Latitude in 1E7 degrees
8 int32_t lon
; ///< Longitude in 1E7 degrees
9 int32_t alt
; ///< Altitude in 1E3 meters (millimeters) above MSL
10 uint16_t eph
; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
11 uint16_t epv
; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
12 uint16_t vel
; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
13 uint16_t cog
; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
14 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.
15 uint8_t satellites_visible
; ///< Number of satellites visible. If unknown, set to 255
16 } mavlink_gps_raw_int_t
;
18 #define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
19 #define MAVLINK_MSG_ID_24_LEN 30
22 #define MAVLINK_MESSAGE_INFO_GPS_RAW_INT \
27 { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
28 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
29 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
30 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
31 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
32 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
33 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
34 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
35 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
36 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
42 * @brief Pack a gps_raw_int message
43 * @param system_id ID of this system
44 * @param component_id ID of this component (e.g. 200 for IMU)
45 * @param msg The MAVLink message to compress the data into
47 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
48 * @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.
49 * @param lat Latitude in 1E7 degrees
50 * @param lon Longitude in 1E7 degrees
51 * @param alt Altitude in 1E3 meters (millimeters) above MSL
52 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
53 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
54 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
55 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
56 * @param satellites_visible Number of satellites visible. If unknown, set to 255
57 * @return length of the message in bytes (excluding serial stream start sign)
59 static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
*msg
,
60 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
)
62 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
64 _mav_put_uint64_t(buf
, 0, time_usec
);
65 _mav_put_int32_t(buf
, 8, lat
);
66 _mav_put_int32_t(buf
, 12, lon
);
67 _mav_put_int32_t(buf
, 16, alt
);
68 _mav_put_uint16_t(buf
, 20, eph
);
69 _mav_put_uint16_t(buf
, 22, epv
);
70 _mav_put_uint16_t(buf
, 24, vel
);
71 _mav_put_uint16_t(buf
, 26, cog
);
72 _mav_put_uint8_t(buf
, 28, fix_type
);
73 _mav_put_uint8_t(buf
, 29, satellites_visible
);
75 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 30);
77 mavlink_gps_raw_int_t packet
;
78 packet
.time_usec
= time_usec
;
86 packet
.fix_type
= fix_type
;
87 packet
.satellites_visible
= satellites_visible
;
89 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 30);
90 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
92 msg
->msgid
= MAVLINK_MSG_ID_GPS_RAW_INT
;
93 return mavlink_finalize_message(msg
, system_id
, component_id
, 30, 24);
97 * @brief Pack a gps_raw_int message on a channel
98 * @param system_id ID of this system
99 * @param component_id ID of this component (e.g. 200 for IMU)
100 * @param chan The MAVLink channel this message was sent over
101 * @param msg The MAVLink message to compress the data into
102 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
103 * @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.
104 * @param lat Latitude in 1E7 degrees
105 * @param lon Longitude in 1E7 degrees
106 * @param alt Altitude in 1E3 meters (millimeters) above MSL
107 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
108 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
109 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
110 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
111 * @param satellites_visible Number of satellites visible. If unknown, set to 255
112 * @return length of the message in bytes (excluding serial stream start sign)
114 static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
115 mavlink_message_t
*msg
,
116 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
)
118 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
120 _mav_put_uint64_t(buf
, 0, time_usec
);
121 _mav_put_int32_t(buf
, 8, lat
);
122 _mav_put_int32_t(buf
, 12, lon
);
123 _mav_put_int32_t(buf
, 16, alt
);
124 _mav_put_uint16_t(buf
, 20, eph
);
125 _mav_put_uint16_t(buf
, 22, epv
);
126 _mav_put_uint16_t(buf
, 24, vel
);
127 _mav_put_uint16_t(buf
, 26, cog
);
128 _mav_put_uint8_t(buf
, 28, fix_type
);
129 _mav_put_uint8_t(buf
, 29, satellites_visible
);
131 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, 30);
133 mavlink_gps_raw_int_t packet
;
134 packet
.time_usec
= time_usec
;
142 packet
.fix_type
= fix_type
;
143 packet
.satellites_visible
= satellites_visible
;
145 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, 30);
146 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
148 msg
->msgid
= MAVLINK_MSG_ID_GPS_RAW_INT
;
149 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, 30, 24);
153 * @brief Encode a gps_raw_int struct into a message
155 * @param system_id ID of this system
156 * @param component_id ID of this component (e.g. 200 for IMU)
157 * @param msg The MAVLink message to compress the data into
158 * @param gps_raw_int C-struct to read the message contents from
160 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
)
162 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
);
166 * @brief Send a gps_raw_int message
167 * @param chan MAVLink channel to send the message
169 * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
170 * @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.
171 * @param lat Latitude in 1E7 degrees
172 * @param lon Longitude in 1E7 degrees
173 * @param alt Altitude in 1E3 meters (millimeters) above MSL
174 * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
175 * @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
176 * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
177 * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
178 * @param satellites_visible Number of satellites visible. If unknown, set to 255
180 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
182 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
)
184 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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
);
197 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, buf
, 30, 24);
199 mavlink_gps_raw_int_t packet
;
200 packet
.time_usec
= time_usec
;
208 packet
.fix_type
= fix_type
;
209 packet
.satellites_visible
= satellites_visible
;
211 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_GPS_RAW_INT
, (const char *)&packet
, 30, 24);
212 #endif // if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 #endif // ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
217 // MESSAGE GPS_RAW_INT UNPACKING
221 * @brief Get field time_usec from gps_raw_int message
223 * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
225 static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t
*msg
)
227 return _MAV_RETURN_uint64_t(msg
, 0);
231 * @brief Get field fix_type from gps_raw_int message
233 * @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.
235 static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t
*msg
)
237 return _MAV_RETURN_uint8_t(msg
, 28);
241 * @brief Get field lat from gps_raw_int message
243 * @return Latitude in 1E7 degrees
245 static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t
*msg
)
247 return _MAV_RETURN_int32_t(msg
, 8);
251 * @brief Get field lon from gps_raw_int message
253 * @return Longitude in 1E7 degrees
255 static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t
*msg
)
257 return _MAV_RETURN_int32_t(msg
, 12);
261 * @brief Get field alt from gps_raw_int message
263 * @return Altitude in 1E3 meters (millimeters) above MSL
265 static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t
*msg
)
267 return _MAV_RETURN_int32_t(msg
, 16);
271 * @brief Get field eph from gps_raw_int message
273 * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
275 static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t
*msg
)
277 return _MAV_RETURN_uint16_t(msg
, 20);
281 * @brief Get field epv from gps_raw_int message
283 * @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
285 static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t
*msg
)
287 return _MAV_RETURN_uint16_t(msg
, 22);
291 * @brief Get field vel from gps_raw_int message
293 * @return GPS ground speed (m/s * 100). If unknown, set to: 65535
295 static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t
*msg
)
297 return _MAV_RETURN_uint16_t(msg
, 24);
301 * @brief Get field cog from gps_raw_int message
303 * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
305 static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t
*msg
)
307 return _MAV_RETURN_uint16_t(msg
, 26);
311 * @brief Get field satellites_visible from gps_raw_int message
313 * @return Number of satellites visible. If unknown, set to 255
315 static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t
*msg
)
317 return _MAV_RETURN_uint8_t(msg
, 29);
321 * @brief Decode a gps_raw_int message into a struct
323 * @param msg The message to decode
324 * @param gps_raw_int C-struct to decode the message contents into
326 static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t
*msg
, mavlink_gps_raw_int_t
*gps_raw_int
)
328 #if MAVLINK_NEED_BYTE_SWAP
329 gps_raw_int
->time_usec
= mavlink_msg_gps_raw_int_get_time_usec(msg
);
330 gps_raw_int
->lat
= mavlink_msg_gps_raw_int_get_lat(msg
);
331 gps_raw_int
->lon
= mavlink_msg_gps_raw_int_get_lon(msg
);
332 gps_raw_int
->alt
= mavlink_msg_gps_raw_int_get_alt(msg
);
333 gps_raw_int
->eph
= mavlink_msg_gps_raw_int_get_eph(msg
);
334 gps_raw_int
->epv
= mavlink_msg_gps_raw_int_get_epv(msg
);
335 gps_raw_int
->vel
= mavlink_msg_gps_raw_int_get_vel(msg
);
336 gps_raw_int
->cog
= mavlink_msg_gps_raw_int_get_cog(msg
);
337 gps_raw_int
->fix_type
= mavlink_msg_gps_raw_int_get_fix_type(msg
);
338 gps_raw_int
->satellites_visible
= mavlink_msg_gps_raw_int_get_satellites_visible(msg
);
340 memcpy(gps_raw_int
, _MAV_PAYLOAD(msg
), 30);