Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / lib / main / MAVLink / common / mavlink_msg_gps_input.h
blobde76ddbf1d5fcf9e4f63f15c5c509d9e5edc842f
1 #pragma once
2 // MESSAGE GPS_INPUT PACKING
4 #define MAVLINK_MSG_ID_GPS_INPUT 232
6 MAVPACKED(
7 typedef struct __mavlink_gps_input_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 uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/
10 int32_t lat; /*< [degE7] Latitude (WGS84)*/
11 int32_t lon; /*< [degE7] Longitude (WGS84)*/
12 float alt; /*< [m] Altitude (MSL). Positive for up.*/
13 float hdop; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
14 float vdop; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
15 float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/
16 float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/
17 float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/
18 float speed_accuracy; /*< [m/s] GPS speed accuracy*/
19 float horiz_accuracy; /*< [m] GPS horizontal accuracy*/
20 float vert_accuracy; /*< [m] GPS vertical accuracy*/
21 uint16_t ignore_flags; /*< Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.*/
22 uint16_t time_week; /*< GPS week number*/
23 uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/
24 uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/
25 uint8_t satellites_visible; /*< Number of satellites visible.*/
26 uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/
27 }) mavlink_gps_input_t;
29 #define MAVLINK_MSG_ID_GPS_INPUT_LEN 65
30 #define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63
31 #define MAVLINK_MSG_ID_232_LEN 65
32 #define MAVLINK_MSG_ID_232_MIN_LEN 63
34 #define MAVLINK_MSG_ID_GPS_INPUT_CRC 151
35 #define MAVLINK_MSG_ID_232_CRC 151
39 #if MAVLINK_COMMAND_24BIT
40 #define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
41 232, \
42 "GPS_INPUT", \
43 19, \
44 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
45 { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
46 { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
47 { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
48 { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
49 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
50 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
51 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
52 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
53 { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \
54 { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \
55 { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \
56 { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \
57 { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \
58 { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
59 { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
60 { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
61 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
62 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
63 } \
65 #else
66 #define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
67 "GPS_INPUT", \
68 19, \
69 { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
70 { "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
71 { "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
72 { "time_week_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gps_input_t, time_week_ms) }, \
73 { "time_week", NULL, MAVLINK_TYPE_UINT16_T, 0, 58, offsetof(mavlink_gps_input_t, time_week) }, \
74 { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 61, offsetof(mavlink_gps_input_t, fix_type) }, \
75 { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_input_t, lat) }, \
76 { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_input_t, lon) }, \
77 { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gps_input_t, alt) }, \
78 { "hdop", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gps_input_t, hdop) }, \
79 { "vdop", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gps_input_t, vdop) }, \
80 { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gps_input_t, vn) }, \
81 { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gps_input_t, ve) }, \
82 { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gps_input_t, vd) }, \
83 { "speed_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_gps_input_t, speed_accuracy) }, \
84 { "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
85 { "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
86 { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
87 { "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
88 } \
90 #endif
92 /**
93 * @brief Pack a gps_input message
94 * @param system_id ID of this system
95 * @param component_id ID of this component (e.g. 200 for IMU)
96 * @param msg The MAVLink message to compress the data into
98 * @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.
99 * @param gps_id ID of the GPS for multiple GPS inputs
100 * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
101 * @param time_week_ms [ms] GPS time (from start of GPS week)
102 * @param time_week GPS week number
103 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
104 * @param lat [degE7] Latitude (WGS84)
105 * @param lon [degE7] Longitude (WGS84)
106 * @param alt [m] Altitude (MSL). Positive for up.
107 * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
108 * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
109 * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
110 * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
111 * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
112 * @param speed_accuracy [m/s] GPS speed accuracy
113 * @param horiz_accuracy [m] GPS horizontal accuracy
114 * @param vert_accuracy [m] GPS vertical accuracy
115 * @param satellites_visible Number of satellites visible.
116 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
117 * @return length of the message in bytes (excluding serial stream start sign)
119 static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
120 uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
122 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
123 char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
124 _mav_put_uint64_t(buf, 0, time_usec);
125 _mav_put_uint32_t(buf, 8, time_week_ms);
126 _mav_put_int32_t(buf, 12, lat);
127 _mav_put_int32_t(buf, 16, lon);
128 _mav_put_float(buf, 20, alt);
129 _mav_put_float(buf, 24, hdop);
130 _mav_put_float(buf, 28, vdop);
131 _mav_put_float(buf, 32, vn);
132 _mav_put_float(buf, 36, ve);
133 _mav_put_float(buf, 40, vd);
134 _mav_put_float(buf, 44, speed_accuracy);
135 _mav_put_float(buf, 48, horiz_accuracy);
136 _mav_put_float(buf, 52, vert_accuracy);
137 _mav_put_uint16_t(buf, 56, ignore_flags);
138 _mav_put_uint16_t(buf, 58, time_week);
139 _mav_put_uint8_t(buf, 60, gps_id);
140 _mav_put_uint8_t(buf, 61, fix_type);
141 _mav_put_uint8_t(buf, 62, satellites_visible);
142 _mav_put_uint16_t(buf, 63, yaw);
144 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
145 #else
146 mavlink_gps_input_t packet;
147 packet.time_usec = time_usec;
148 packet.time_week_ms = time_week_ms;
149 packet.lat = lat;
150 packet.lon = lon;
151 packet.alt = alt;
152 packet.hdop = hdop;
153 packet.vdop = vdop;
154 packet.vn = vn;
155 packet.ve = ve;
156 packet.vd = vd;
157 packet.speed_accuracy = speed_accuracy;
158 packet.horiz_accuracy = horiz_accuracy;
159 packet.vert_accuracy = vert_accuracy;
160 packet.ignore_flags = ignore_flags;
161 packet.time_week = time_week;
162 packet.gps_id = gps_id;
163 packet.fix_type = fix_type;
164 packet.satellites_visible = satellites_visible;
165 packet.yaw = yaw;
167 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
168 #endif
170 msg->msgid = MAVLINK_MSG_ID_GPS_INPUT;
171 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
175 * @brief Pack a gps_input message on a channel
176 * @param system_id ID of this system
177 * @param component_id ID of this component (e.g. 200 for IMU)
178 * @param chan The MAVLink channel this message will be sent over
179 * @param msg The MAVLink message to compress the data into
180 * @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.
181 * @param gps_id ID of the GPS for multiple GPS inputs
182 * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
183 * @param time_week_ms [ms] GPS time (from start of GPS week)
184 * @param time_week GPS week number
185 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
186 * @param lat [degE7] Latitude (WGS84)
187 * @param lon [degE7] Longitude (WGS84)
188 * @param alt [m] Altitude (MSL). Positive for up.
189 * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
190 * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
191 * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
192 * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
193 * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
194 * @param speed_accuracy [m/s] GPS speed accuracy
195 * @param horiz_accuracy [m] GPS horizontal accuracy
196 * @param vert_accuracy [m] GPS vertical accuracy
197 * @param satellites_visible Number of satellites visible.
198 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
199 * @return length of the message in bytes (excluding serial stream start sign)
201 static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
202 mavlink_message_t* msg,
203 uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible,uint16_t yaw)
205 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
206 char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
207 _mav_put_uint64_t(buf, 0, time_usec);
208 _mav_put_uint32_t(buf, 8, time_week_ms);
209 _mav_put_int32_t(buf, 12, lat);
210 _mav_put_int32_t(buf, 16, lon);
211 _mav_put_float(buf, 20, alt);
212 _mav_put_float(buf, 24, hdop);
213 _mav_put_float(buf, 28, vdop);
214 _mav_put_float(buf, 32, vn);
215 _mav_put_float(buf, 36, ve);
216 _mav_put_float(buf, 40, vd);
217 _mav_put_float(buf, 44, speed_accuracy);
218 _mav_put_float(buf, 48, horiz_accuracy);
219 _mav_put_float(buf, 52, vert_accuracy);
220 _mav_put_uint16_t(buf, 56, ignore_flags);
221 _mav_put_uint16_t(buf, 58, time_week);
222 _mav_put_uint8_t(buf, 60, gps_id);
223 _mav_put_uint8_t(buf, 61, fix_type);
224 _mav_put_uint8_t(buf, 62, satellites_visible);
225 _mav_put_uint16_t(buf, 63, yaw);
227 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
228 #else
229 mavlink_gps_input_t packet;
230 packet.time_usec = time_usec;
231 packet.time_week_ms = time_week_ms;
232 packet.lat = lat;
233 packet.lon = lon;
234 packet.alt = alt;
235 packet.hdop = hdop;
236 packet.vdop = vdop;
237 packet.vn = vn;
238 packet.ve = ve;
239 packet.vd = vd;
240 packet.speed_accuracy = speed_accuracy;
241 packet.horiz_accuracy = horiz_accuracy;
242 packet.vert_accuracy = vert_accuracy;
243 packet.ignore_flags = ignore_flags;
244 packet.time_week = time_week;
245 packet.gps_id = gps_id;
246 packet.fix_type = fix_type;
247 packet.satellites_visible = satellites_visible;
248 packet.yaw = yaw;
250 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
251 #endif
253 msg->msgid = MAVLINK_MSG_ID_GPS_INPUT;
254 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
258 * @brief Encode a gps_input struct
260 * @param system_id ID of this system
261 * @param component_id ID of this component (e.g. 200 for IMU)
262 * @param msg The MAVLink message to compress the data into
263 * @param gps_input C-struct to read the message contents from
265 static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
267 return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
271 * @brief Encode a gps_input struct on a channel
273 * @param system_id ID of this system
274 * @param component_id ID of this component (e.g. 200 for IMU)
275 * @param chan The MAVLink channel this message will be sent over
276 * @param msg The MAVLink message to compress the data into
277 * @param gps_input C-struct to read the message contents from
279 static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
281 return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
285 * @brief Send a gps_input message
286 * @param chan MAVLink channel to send the message
288 * @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.
289 * @param gps_id ID of the GPS for multiple GPS inputs
290 * @param ignore_flags Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
291 * @param time_week_ms [ms] GPS time (from start of GPS week)
292 * @param time_week GPS week number
293 * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
294 * @param lat [degE7] Latitude (WGS84)
295 * @param lon [degE7] Longitude (WGS84)
296 * @param alt [m] Altitude (MSL). Positive for up.
297 * @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
298 * @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
299 * @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
300 * @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
301 * @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
302 * @param speed_accuracy [m/s] GPS speed accuracy
303 * @param horiz_accuracy [m] GPS horizontal accuracy
304 * @param vert_accuracy [m] GPS vertical accuracy
305 * @param satellites_visible Number of satellites visible.
306 * @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
308 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
310 static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
312 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
313 char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
314 _mav_put_uint64_t(buf, 0, time_usec);
315 _mav_put_uint32_t(buf, 8, time_week_ms);
316 _mav_put_int32_t(buf, 12, lat);
317 _mav_put_int32_t(buf, 16, lon);
318 _mav_put_float(buf, 20, alt);
319 _mav_put_float(buf, 24, hdop);
320 _mav_put_float(buf, 28, vdop);
321 _mav_put_float(buf, 32, vn);
322 _mav_put_float(buf, 36, ve);
323 _mav_put_float(buf, 40, vd);
324 _mav_put_float(buf, 44, speed_accuracy);
325 _mav_put_float(buf, 48, horiz_accuracy);
326 _mav_put_float(buf, 52, vert_accuracy);
327 _mav_put_uint16_t(buf, 56, ignore_flags);
328 _mav_put_uint16_t(buf, 58, time_week);
329 _mav_put_uint8_t(buf, 60, gps_id);
330 _mav_put_uint8_t(buf, 61, fix_type);
331 _mav_put_uint8_t(buf, 62, satellites_visible);
332 _mav_put_uint16_t(buf, 63, yaw);
334 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
335 #else
336 mavlink_gps_input_t packet;
337 packet.time_usec = time_usec;
338 packet.time_week_ms = time_week_ms;
339 packet.lat = lat;
340 packet.lon = lon;
341 packet.alt = alt;
342 packet.hdop = hdop;
343 packet.vdop = vdop;
344 packet.vn = vn;
345 packet.ve = ve;
346 packet.vd = vd;
347 packet.speed_accuracy = speed_accuracy;
348 packet.horiz_accuracy = horiz_accuracy;
349 packet.vert_accuracy = vert_accuracy;
350 packet.ignore_flags = ignore_flags;
351 packet.time_week = time_week;
352 packet.gps_id = gps_id;
353 packet.fix_type = fix_type;
354 packet.satellites_visible = satellites_visible;
355 packet.yaw = yaw;
357 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
358 #endif
362 * @brief Send a gps_input message
363 * @param chan MAVLink channel to send the message
364 * @param struct The MAVLink struct to serialize
366 static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input)
368 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
369 mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
370 #else
371 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
372 #endif
375 #if MAVLINK_MSG_ID_GPS_INPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
377 This varient of _send() can be used to save stack space by re-using
378 memory from the receive buffer. The caller provides a
379 mavlink_message_t which is the size of a full mavlink message. This
380 is usually the receive buffer for the channel, and allows a reply to an
381 incoming message with minimum stack space usage.
383 static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
385 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
386 char *buf = (char *)msgbuf;
387 _mav_put_uint64_t(buf, 0, time_usec);
388 _mav_put_uint32_t(buf, 8, time_week_ms);
389 _mav_put_int32_t(buf, 12, lat);
390 _mav_put_int32_t(buf, 16, lon);
391 _mav_put_float(buf, 20, alt);
392 _mav_put_float(buf, 24, hdop);
393 _mav_put_float(buf, 28, vdop);
394 _mav_put_float(buf, 32, vn);
395 _mav_put_float(buf, 36, ve);
396 _mav_put_float(buf, 40, vd);
397 _mav_put_float(buf, 44, speed_accuracy);
398 _mav_put_float(buf, 48, horiz_accuracy);
399 _mav_put_float(buf, 52, vert_accuracy);
400 _mav_put_uint16_t(buf, 56, ignore_flags);
401 _mav_put_uint16_t(buf, 58, time_week);
402 _mav_put_uint8_t(buf, 60, gps_id);
403 _mav_put_uint8_t(buf, 61, fix_type);
404 _mav_put_uint8_t(buf, 62, satellites_visible);
405 _mav_put_uint16_t(buf, 63, yaw);
407 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
408 #else
409 mavlink_gps_input_t *packet = (mavlink_gps_input_t *)msgbuf;
410 packet->time_usec = time_usec;
411 packet->time_week_ms = time_week_ms;
412 packet->lat = lat;
413 packet->lon = lon;
414 packet->alt = alt;
415 packet->hdop = hdop;
416 packet->vdop = vdop;
417 packet->vn = vn;
418 packet->ve = ve;
419 packet->vd = vd;
420 packet->speed_accuracy = speed_accuracy;
421 packet->horiz_accuracy = horiz_accuracy;
422 packet->vert_accuracy = vert_accuracy;
423 packet->ignore_flags = ignore_flags;
424 packet->time_week = time_week;
425 packet->gps_id = gps_id;
426 packet->fix_type = fix_type;
427 packet->satellites_visible = satellites_visible;
428 packet->yaw = yaw;
430 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
431 #endif
433 #endif
435 #endif
437 // MESSAGE GPS_INPUT UNPACKING
441 * @brief Get field time_usec from gps_input message
443 * @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.
445 static inline uint64_t mavlink_msg_gps_input_get_time_usec(const mavlink_message_t* msg)
447 return _MAV_RETURN_uint64_t(msg, 0);
451 * @brief Get field gps_id from gps_input message
453 * @return ID of the GPS for multiple GPS inputs
455 static inline uint8_t mavlink_msg_gps_input_get_gps_id(const mavlink_message_t* msg)
457 return _MAV_RETURN_uint8_t(msg, 60);
461 * @brief Get field ignore_flags from gps_input message
463 * @return Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided.
465 static inline uint16_t mavlink_msg_gps_input_get_ignore_flags(const mavlink_message_t* msg)
467 return _MAV_RETURN_uint16_t(msg, 56);
471 * @brief Get field time_week_ms from gps_input message
473 * @return [ms] GPS time (from start of GPS week)
475 static inline uint32_t mavlink_msg_gps_input_get_time_week_ms(const mavlink_message_t* msg)
477 return _MAV_RETURN_uint32_t(msg, 8);
481 * @brief Get field time_week from gps_input message
483 * @return GPS week number
485 static inline uint16_t mavlink_msg_gps_input_get_time_week(const mavlink_message_t* msg)
487 return _MAV_RETURN_uint16_t(msg, 58);
491 * @brief Get field fix_type from gps_input message
493 * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK
495 static inline uint8_t mavlink_msg_gps_input_get_fix_type(const mavlink_message_t* msg)
497 return _MAV_RETURN_uint8_t(msg, 61);
501 * @brief Get field lat from gps_input message
503 * @return [degE7] Latitude (WGS84)
505 static inline int32_t mavlink_msg_gps_input_get_lat(const mavlink_message_t* msg)
507 return _MAV_RETURN_int32_t(msg, 12);
511 * @brief Get field lon from gps_input message
513 * @return [degE7] Longitude (WGS84)
515 static inline int32_t mavlink_msg_gps_input_get_lon(const mavlink_message_t* msg)
517 return _MAV_RETURN_int32_t(msg, 16);
521 * @brief Get field alt from gps_input message
523 * @return [m] Altitude (MSL). Positive for up.
525 static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg)
527 return _MAV_RETURN_float(msg, 20);
531 * @brief Get field hdop from gps_input message
533 * @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
535 static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
537 return _MAV_RETURN_float(msg, 24);
541 * @brief Get field vdop from gps_input message
543 * @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
545 static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg)
547 return _MAV_RETURN_float(msg, 28);
551 * @brief Get field vn from gps_input message
553 * @return [m/s] GPS velocity in north direction in earth-fixed NED frame
555 static inline float mavlink_msg_gps_input_get_vn(const mavlink_message_t* msg)
557 return _MAV_RETURN_float(msg, 32);
561 * @brief Get field ve from gps_input message
563 * @return [m/s] GPS velocity in east direction in earth-fixed NED frame
565 static inline float mavlink_msg_gps_input_get_ve(const mavlink_message_t* msg)
567 return _MAV_RETURN_float(msg, 36);
571 * @brief Get field vd from gps_input message
573 * @return [m/s] GPS velocity in down direction in earth-fixed NED frame
575 static inline float mavlink_msg_gps_input_get_vd(const mavlink_message_t* msg)
577 return _MAV_RETURN_float(msg, 40);
581 * @brief Get field speed_accuracy from gps_input message
583 * @return [m/s] GPS speed accuracy
585 static inline float mavlink_msg_gps_input_get_speed_accuracy(const mavlink_message_t* msg)
587 return _MAV_RETURN_float(msg, 44);
591 * @brief Get field horiz_accuracy from gps_input message
593 * @return [m] GPS horizontal accuracy
595 static inline float mavlink_msg_gps_input_get_horiz_accuracy(const mavlink_message_t* msg)
597 return _MAV_RETURN_float(msg, 48);
601 * @brief Get field vert_accuracy from gps_input message
603 * @return [m] GPS vertical accuracy
605 static inline float mavlink_msg_gps_input_get_vert_accuracy(const mavlink_message_t* msg)
607 return _MAV_RETURN_float(msg, 52);
611 * @brief Get field satellites_visible from gps_input message
613 * @return Number of satellites visible.
615 static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink_message_t* msg)
617 return _MAV_RETURN_uint8_t(msg, 62);
621 * @brief Get field yaw from gps_input message
623 * @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
625 static inline uint16_t mavlink_msg_gps_input_get_yaw(const mavlink_message_t* msg)
627 return _MAV_RETURN_uint16_t(msg, 63);
631 * @brief Decode a gps_input message into a struct
633 * @param msg The message to decode
634 * @param gps_input C-struct to decode the message contents into
636 static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, mavlink_gps_input_t* gps_input)
638 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
639 gps_input->time_usec = mavlink_msg_gps_input_get_time_usec(msg);
640 gps_input->time_week_ms = mavlink_msg_gps_input_get_time_week_ms(msg);
641 gps_input->lat = mavlink_msg_gps_input_get_lat(msg);
642 gps_input->lon = mavlink_msg_gps_input_get_lon(msg);
643 gps_input->alt = mavlink_msg_gps_input_get_alt(msg);
644 gps_input->hdop = mavlink_msg_gps_input_get_hdop(msg);
645 gps_input->vdop = mavlink_msg_gps_input_get_vdop(msg);
646 gps_input->vn = mavlink_msg_gps_input_get_vn(msg);
647 gps_input->ve = mavlink_msg_gps_input_get_ve(msg);
648 gps_input->vd = mavlink_msg_gps_input_get_vd(msg);
649 gps_input->speed_accuracy = mavlink_msg_gps_input_get_speed_accuracy(msg);
650 gps_input->horiz_accuracy = mavlink_msg_gps_input_get_horiz_accuracy(msg);
651 gps_input->vert_accuracy = mavlink_msg_gps_input_get_vert_accuracy(msg);
652 gps_input->ignore_flags = mavlink_msg_gps_input_get_ignore_flags(msg);
653 gps_input->time_week = mavlink_msg_gps_input_get_time_week(msg);
654 gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg);
655 gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg);
656 gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg);
657 gps_input->yaw = mavlink_msg_gps_input_get_yaw(msg);
658 #else
659 uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN;
660 memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN);
661 memcpy(gps_input, _MAV_PAYLOAD(msg), len);
662 #endif