Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / lib / main / MAVLink / common / mavlink_msg_hil_gps.h
blob4b8ff2b85e3497109f5506ed177cdef2dba51452
1 #pragma once
2 // MESSAGE HIL_GPS PACKING
4 #define MAVLINK_MSG_ID_HIL_GPS 113
6 MAVPACKED(
7 typedef struct __mavlink_hil_gps_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 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: 65535*/
15 int16_t vn; /*< [cm/s] GPS velocity in north direction in earth-fixed NED frame*/
16 int16_t ve; /*< [cm/s] GPS velocity in east direction in earth-fixed NED frame*/
17 int16_t vd; /*< [cm/s] GPS velocity in down direction in earth-fixed NED frame*/
18 uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535*/
19 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.*/
20 uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
21 uint8_t id; /*< GPS ID (zero indexed). Used for multiple GPS inputs*/
22 uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/
23 }) mavlink_hil_gps_t;
25 #define MAVLINK_MSG_ID_HIL_GPS_LEN 39
26 #define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36
27 #define MAVLINK_MSG_ID_113_LEN 39
28 #define MAVLINK_MSG_ID_113_MIN_LEN 36
30 #define MAVLINK_MSG_ID_HIL_GPS_CRC 124
31 #define MAVLINK_MSG_ID_113_CRC 124
35 #if MAVLINK_COMMAND_24BIT
36 #define MAVLINK_MESSAGE_INFO_HIL_GPS { \
37 113, \
38 "HIL_GPS", \
39 15, \
40 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
41 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
42 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
43 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
44 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
45 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \
46 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \
47 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \
48 { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \
49 { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
50 { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
51 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
52 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
53 { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \
54 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \
55 } \
57 #else
58 #define MAVLINK_MESSAGE_INFO_HIL_GPS { \
59 "HIL_GPS", \
60 15, \
61 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
62 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
63 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
64 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
65 { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
66 { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \
67 { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \
68 { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \
69 { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \
70 { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
71 { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
72 { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
73 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
74 { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \
75 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \
76 } \
78 #endif
80 /**
81 * @brief Pack a hil_gps message
82 * @param system_id ID of this system
83 * @param component_id ID of this component (e.g. 200 for IMU)
84 * @param msg The MAVLink message to compress the data into
86 * @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.
87 * @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.
88 * @param lat [degE7] Latitude (WGS84)
89 * @param lon [degE7] Longitude (WGS84)
90 * @param alt [mm] Altitude (MSL). Positive for up.
91 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
92 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
93 * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
94 * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
95 * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
96 * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
97 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
98 * @param satellites_visible Number of satellites visible. If unknown, set to 255
99 * @param id GPS ID (zero indexed). Used for multiple GPS inputs
100 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
101 * @return length of the message in bytes (excluding serial stream start sign)
103 static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
104 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw)
106 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
108 _mav_put_uint64_t(buf, 0, time_usec);
109 _mav_put_int32_t(buf, 8, lat);
110 _mav_put_int32_t(buf, 12, lon);
111 _mav_put_int32_t(buf, 16, alt);
112 _mav_put_uint16_t(buf, 20, eph);
113 _mav_put_uint16_t(buf, 22, epv);
114 _mav_put_uint16_t(buf, 24, vel);
115 _mav_put_int16_t(buf, 26, vn);
116 _mav_put_int16_t(buf, 28, ve);
117 _mav_put_int16_t(buf, 30, vd);
118 _mav_put_uint16_t(buf, 32, cog);
119 _mav_put_uint8_t(buf, 34, fix_type);
120 _mav_put_uint8_t(buf, 35, satellites_visible);
121 _mav_put_uint8_t(buf, 36, id);
122 _mav_put_uint16_t(buf, 37, yaw);
124 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
125 #else
126 mavlink_hil_gps_t packet;
127 packet.time_usec = time_usec;
128 packet.lat = lat;
129 packet.lon = lon;
130 packet.alt = alt;
131 packet.eph = eph;
132 packet.epv = epv;
133 packet.vel = vel;
134 packet.vn = vn;
135 packet.ve = ve;
136 packet.vd = vd;
137 packet.cog = cog;
138 packet.fix_type = fix_type;
139 packet.satellites_visible = satellites_visible;
140 packet.id = id;
141 packet.yaw = yaw;
143 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
144 #endif
146 msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
147 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
151 * @brief Pack a hil_gps message on a channel
152 * @param system_id ID of this system
153 * @param component_id ID of this component (e.g. 200 for IMU)
154 * @param chan The MAVLink channel this message will be sent over
155 * @param msg The MAVLink message to compress the data into
156 * @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.
157 * @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.
158 * @param lat [degE7] Latitude (WGS84)
159 * @param lon [degE7] Longitude (WGS84)
160 * @param alt [mm] Altitude (MSL). Positive for up.
161 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
162 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
163 * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
164 * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
165 * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
166 * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
167 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
168 * @param satellites_visible Number of satellites visible. If unknown, set to 255
169 * @param id GPS ID (zero indexed). Used for multiple GPS inputs
170 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
171 * @return length of the message in bytes (excluding serial stream start sign)
173 static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
174 mavlink_message_t* msg,
175 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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible,uint8_t id,uint16_t yaw)
177 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
178 char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
179 _mav_put_uint64_t(buf, 0, time_usec);
180 _mav_put_int32_t(buf, 8, lat);
181 _mav_put_int32_t(buf, 12, lon);
182 _mav_put_int32_t(buf, 16, alt);
183 _mav_put_uint16_t(buf, 20, eph);
184 _mav_put_uint16_t(buf, 22, epv);
185 _mav_put_uint16_t(buf, 24, vel);
186 _mav_put_int16_t(buf, 26, vn);
187 _mav_put_int16_t(buf, 28, ve);
188 _mav_put_int16_t(buf, 30, vd);
189 _mav_put_uint16_t(buf, 32, cog);
190 _mav_put_uint8_t(buf, 34, fix_type);
191 _mav_put_uint8_t(buf, 35, satellites_visible);
192 _mav_put_uint8_t(buf, 36, id);
193 _mav_put_uint16_t(buf, 37, yaw);
195 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
196 #else
197 mavlink_hil_gps_t packet;
198 packet.time_usec = time_usec;
199 packet.lat = lat;
200 packet.lon = lon;
201 packet.alt = alt;
202 packet.eph = eph;
203 packet.epv = epv;
204 packet.vel = vel;
205 packet.vn = vn;
206 packet.ve = ve;
207 packet.vd = vd;
208 packet.cog = cog;
209 packet.fix_type = fix_type;
210 packet.satellites_visible = satellites_visible;
211 packet.id = id;
212 packet.yaw = yaw;
214 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
215 #endif
217 msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
218 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
222 * @brief Encode a hil_gps struct
224 * @param system_id ID of this system
225 * @param component_id ID of this component (e.g. 200 for IMU)
226 * @param msg The MAVLink message to compress the data into
227 * @param hil_gps C-struct to read the message contents from
229 static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
231 return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw);
235 * @brief Encode a hil_gps struct on a channel
237 * @param system_id ID of this system
238 * @param component_id ID of this component (e.g. 200 for IMU)
239 * @param chan The MAVLink channel this message will be sent over
240 * @param msg The MAVLink message to compress the data into
241 * @param hil_gps C-struct to read the message contents from
243 static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
245 return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw);
249 * @brief Send a hil_gps message
250 * @param chan MAVLink channel to send the message
252 * @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.
253 * @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.
254 * @param lat [degE7] Latitude (WGS84)
255 * @param lon [degE7] Longitude (WGS84)
256 * @param alt [mm] Altitude (MSL). Positive for up.
257 * @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
258 * @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
259 * @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
260 * @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
261 * @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
262 * @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
263 * @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
264 * @param satellites_visible Number of satellites visible. If unknown, set to 255
265 * @param id GPS ID (zero indexed). Used for multiple GPS inputs
266 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
268 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
270 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw)
272 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
273 char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
274 _mav_put_uint64_t(buf, 0, time_usec);
275 _mav_put_int32_t(buf, 8, lat);
276 _mav_put_int32_t(buf, 12, lon);
277 _mav_put_int32_t(buf, 16, alt);
278 _mav_put_uint16_t(buf, 20, eph);
279 _mav_put_uint16_t(buf, 22, epv);
280 _mav_put_uint16_t(buf, 24, vel);
281 _mav_put_int16_t(buf, 26, vn);
282 _mav_put_int16_t(buf, 28, ve);
283 _mav_put_int16_t(buf, 30, vd);
284 _mav_put_uint16_t(buf, 32, cog);
285 _mav_put_uint8_t(buf, 34, fix_type);
286 _mav_put_uint8_t(buf, 35, satellites_visible);
287 _mav_put_uint8_t(buf, 36, id);
288 _mav_put_uint16_t(buf, 37, yaw);
290 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
291 #else
292 mavlink_hil_gps_t packet;
293 packet.time_usec = time_usec;
294 packet.lat = lat;
295 packet.lon = lon;
296 packet.alt = alt;
297 packet.eph = eph;
298 packet.epv = epv;
299 packet.vel = vel;
300 packet.vn = vn;
301 packet.ve = ve;
302 packet.vd = vd;
303 packet.cog = cog;
304 packet.fix_type = fix_type;
305 packet.satellites_visible = satellites_visible;
306 packet.id = id;
307 packet.yaw = yaw;
309 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
310 #endif
314 * @brief Send a hil_gps message
315 * @param chan MAVLink channel to send the message
316 * @param struct The MAVLink struct to serialize
318 static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps)
320 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
321 mavlink_msg_hil_gps_send(chan, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible, hil_gps->id, hil_gps->yaw);
322 #else
323 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)hil_gps, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
324 #endif
327 #if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
329 This varient of _send() can be used to save stack space by re-using
330 memory from the receive buffer. The caller provides a
331 mavlink_message_t which is the size of a full mavlink message. This
332 is usually the receive buffer for the channel, and allows a reply to an
333 incoming message with minimum stack space usage.
335 static inline void mavlink_msg_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible, uint8_t id, uint16_t yaw)
337 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
338 char *buf = (char *)msgbuf;
339 _mav_put_uint64_t(buf, 0, time_usec);
340 _mav_put_int32_t(buf, 8, lat);
341 _mav_put_int32_t(buf, 12, lon);
342 _mav_put_int32_t(buf, 16, alt);
343 _mav_put_uint16_t(buf, 20, eph);
344 _mav_put_uint16_t(buf, 22, epv);
345 _mav_put_uint16_t(buf, 24, vel);
346 _mav_put_int16_t(buf, 26, vn);
347 _mav_put_int16_t(buf, 28, ve);
348 _mav_put_int16_t(buf, 30, vd);
349 _mav_put_uint16_t(buf, 32, cog);
350 _mav_put_uint8_t(buf, 34, fix_type);
351 _mav_put_uint8_t(buf, 35, satellites_visible);
352 _mav_put_uint8_t(buf, 36, id);
353 _mav_put_uint16_t(buf, 37, yaw);
355 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
356 #else
357 mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
358 packet->time_usec = time_usec;
359 packet->lat = lat;
360 packet->lon = lon;
361 packet->alt = alt;
362 packet->eph = eph;
363 packet->epv = epv;
364 packet->vel = vel;
365 packet->vn = vn;
366 packet->ve = ve;
367 packet->vd = vd;
368 packet->cog = cog;
369 packet->fix_type = fix_type;
370 packet->satellites_visible = satellites_visible;
371 packet->id = id;
372 packet->yaw = yaw;
374 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
375 #endif
377 #endif
379 #endif
381 // MESSAGE HIL_GPS UNPACKING
385 * @brief Get field time_usec from hil_gps message
387 * @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.
389 static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
391 return _MAV_RETURN_uint64_t(msg, 0);
395 * @brief Get field fix_type from hil_gps message
397 * @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.
399 static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg)
401 return _MAV_RETURN_uint8_t(msg, 34);
405 * @brief Get field lat from hil_gps message
407 * @return [degE7] Latitude (WGS84)
409 static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
411 return _MAV_RETURN_int32_t(msg, 8);
415 * @brief Get field lon from hil_gps message
417 * @return [degE7] Longitude (WGS84)
419 static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
421 return _MAV_RETURN_int32_t(msg, 12);
425 * @brief Get field alt from hil_gps message
427 * @return [mm] Altitude (MSL). Positive for up.
429 static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
431 return _MAV_RETURN_int32_t(msg, 16);
435 * @brief Get field eph from hil_gps message
437 * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
439 static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
441 return _MAV_RETURN_uint16_t(msg, 20);
445 * @brief Get field epv from hil_gps message
447 * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
449 static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
451 return _MAV_RETURN_uint16_t(msg, 22);
455 * @brief Get field vel from hil_gps message
457 * @return [cm/s] GPS ground speed. If unknown, set to: 65535
459 static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
461 return _MAV_RETURN_uint16_t(msg, 24);
465 * @brief Get field vn from hil_gps message
467 * @return [cm/s] GPS velocity in north direction in earth-fixed NED frame
469 static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
471 return _MAV_RETURN_int16_t(msg, 26);
475 * @brief Get field ve from hil_gps message
477 * @return [cm/s] GPS velocity in east direction in earth-fixed NED frame
479 static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
481 return _MAV_RETURN_int16_t(msg, 28);
485 * @brief Get field vd from hil_gps message
487 * @return [cm/s] GPS velocity in down direction in earth-fixed NED frame
489 static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
491 return _MAV_RETURN_int16_t(msg, 30);
495 * @brief Get field cog from hil_gps message
497 * @return [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
499 static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg)
501 return _MAV_RETURN_uint16_t(msg, 32);
505 * @brief Get field satellites_visible from hil_gps message
507 * @return Number of satellites visible. If unknown, set to 255
509 static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg)
511 return _MAV_RETURN_uint8_t(msg, 35);
515 * @brief Get field id from hil_gps message
517 * @return GPS ID (zero indexed). Used for multiple GPS inputs
519 static inline uint8_t mavlink_msg_hil_gps_get_id(const mavlink_message_t* msg)
521 return _MAV_RETURN_uint8_t(msg, 36);
525 * @brief Get field yaw from hil_gps message
527 * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
529 static inline uint16_t mavlink_msg_hil_gps_get_yaw(const mavlink_message_t* msg)
531 return _MAV_RETURN_uint16_t(msg, 37);
535 * @brief Decode a hil_gps message into a struct
537 * @param msg The message to decode
538 * @param hil_gps C-struct to decode the message contents into
540 static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps)
542 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
543 hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg);
544 hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg);
545 hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg);
546 hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg);
547 hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg);
548 hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg);
549 hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg);
550 hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg);
551 hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg);
552 hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg);
553 hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg);
554 hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg);
555 hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg);
556 hil_gps->id = mavlink_msg_hil_gps_get_id(msg);
557 hil_gps->yaw = mavlink_msg_hil_gps_get_yaw(msg);
558 #else
559 uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN;
560 memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN);
561 memcpy(hil_gps, _MAV_PAYLOAD(msg), len);
562 #endif