PX4 Firmware
PX4 Autopilot Software http://px4.io
ubx.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file ubx.h
36  *
37  * U-Blox protocol definition. Following u-blox 6/7/8 Receiver Description
38  * including Prototol Specification.
39  *
40  * @author Thomas Gubler <thomasgubler@student.ethz.ch>
41  * @author Julian Oes <julian@oes.ch>
42  * @author Anton Babushkin <anton.babushkin@me.com>
43  * @author Beat Küng <beat-kueng@gmx.net>
44  *
45  * @author Hannes Delago
46  * (rework, add ubx7+ compatibility)
47  *
48  */
49 
50 #pragma once
51 
52 #include "gps_helper.h"
53 #include "base_station.h"
54 #include "../../definitions.h"
55 
56 #define UBX_SYNC1 0xB5
57 #define UBX_SYNC2 0x62
58 
59 /* Message Classes */
60 #define UBX_CLASS_NAV 0x01
61 #define UBX_CLASS_INF 0x04
62 #define UBX_CLASS_ACK 0x05
63 #define UBX_CLASS_CFG 0x06
64 #define UBX_CLASS_MON 0x0A
65 #define UBX_CLASS_RTCM3 0xF5
66 
67 /* Message IDs */
68 #define UBX_ID_NAV_POSLLH 0x02
69 #define UBX_ID_NAV_DOP 0x04
70 #define UBX_ID_NAV_SOL 0x06
71 #define UBX_ID_NAV_PVT 0x07
72 #define UBX_ID_NAV_VELNED 0x12
73 #define UBX_ID_NAV_TIMEUTC 0x21
74 #define UBX_ID_NAV_SVINFO 0x30
75 #define UBX_ID_NAV_SAT 0x35
76 #define UBX_ID_NAV_SVIN 0x3B
77 #define UBX_ID_NAV_RELPOSNED 0x3C
78 #define UBX_ID_INF_DEBUG 0x04
79 #define UBX_ID_INF_ERROR 0x00
80 #define UBX_ID_INF_NOTICE 0x02
81 #define UBX_ID_INF_WARNING 0x01
82 #define UBX_ID_ACK_NAK 0x00
83 #define UBX_ID_ACK_ACK 0x01
84 #define UBX_ID_CFG_PRT 0x00 // deprecated in protocol version >= 27 -> use CFG_VALSET
85 #define UBX_ID_CFG_MSG 0x01 // deprecated in protocol version >= 27 -> use CFG_VALSET
86 #define UBX_ID_CFG_RATE 0x08 // deprecated in protocol version >= 27 -> use CFG_VALSET
87 #define UBX_ID_CFG_CFG 0x09 // deprecated in protocol version >= 27 -> use CFG_VALSET
88 #define UBX_ID_CFG_NAV5 0x24 // deprecated in protocol version >= 27 -> use CFG_VALSET
89 #define UBX_ID_CFG_RST 0x04
90 #define UBX_ID_CFG_SBAS 0x16
91 #define UBX_ID_CFG_TMODE3 0x71 // deprecated in protocol version >= 27 -> use CFG_VALSET
92 #define UBX_ID_CFG_VALSET 0x8A
93 #define UBX_ID_CFG_VALGET 0x8B
94 #define UBX_ID_CFG_VALDEL 0x8C
95 #define UBX_ID_MON_VER 0x04
96 #define UBX_ID_MON_HW 0x09 // deprecated in protocol version >= 27 -> use MON_RF
97 #define UBX_ID_MON_RF 0x38
98 
99 /* UBX ID for RTCM3 output messages */
100 /* Minimal messages for RTK: 1005, 1077 + (1087 or 1127) */
101 /* Reduced message size using MSM4: 1005, 1074 + (1084 or 1124) */
102 #define UBX_ID_RTCM3_1005 0x05 /**< Stationary RTK reference station ARP */
103 #define UBX_ID_RTCM3_1074 0x4A /**< GPS MSM4 */
104 #define UBX_ID_RTCM3_1077 0x4D /**< GPS MSM7 */
105 #define UBX_ID_RTCM3_1084 0x54 /**< GLONASS MSM4 */
106 #define UBX_ID_RTCM3_1087 0x57 /**< GLONASS MSM7 */
107 #define UBX_ID_RTCM3_1094 0x5E /**< Galileo MSM4 */
108 #define UBX_ID_RTCM3_1097 0x61 /**< Galileo MSM7 */
109 #define UBX_ID_RTCM3_1124 0x7C /**< BeiDou MSM4 */
110 #define UBX_ID_RTCM3_1127 0x7F /**< BeiDou MSM7 */
111 #define UBX_ID_RTCM3_1230 0xE6 /**< GLONASS code-phase biases */
112 #define UBX_ID_RTCM3_4072 0xFE /**< Reference station PVT (u-blox proprietary RTCM Message) - Used for moving baseline */
113 
114 
115 /* Message Classes & IDs */
116 #define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8)
117 #define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8)
118 #define UBX_MSG_NAV_DOP ((UBX_CLASS_NAV) | UBX_ID_NAV_DOP << 8)
119 #define UBX_MSG_NAV_PVT ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8)
120 #define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8)
121 #define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8)
122 #define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8)
123 #define UBX_MSG_NAV_SAT ((UBX_CLASS_NAV) | UBX_ID_NAV_SAT << 8)
124 #define UBX_MSG_NAV_SVIN ((UBX_CLASS_NAV) | UBX_ID_NAV_SVIN << 8)
125 #define UBX_MSG_NAV_RELPOSNED ((UBX_CLASS_NAV) | UBX_ID_NAV_RELPOSNED << 8)
126 #define UBX_MSG_INF_DEBUG ((UBX_CLASS_INF) | UBX_ID_INF_DEBUG << 8)
127 #define UBX_MSG_INF_ERROR ((UBX_CLASS_INF) | UBX_ID_INF_ERROR << 8)
128 #define UBX_MSG_INF_NOTICE ((UBX_CLASS_INF) | UBX_ID_INF_NOTICE << 8)
129 #define UBX_MSG_INF_WARNING ((UBX_CLASS_INF) | UBX_ID_INF_WARNING << 8)
130 #define UBX_MSG_ACK_NAK ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8)
131 #define UBX_MSG_ACK_ACK ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8)
132 #define UBX_MSG_CFG_PRT ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8)
133 #define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
134 #define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
135 #define UBX_MSG_CFG_CFG ((UBX_CLASS_CFG) | UBX_ID_CFG_CFG << 8)
136 #define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
137 #define UBX_MSG_CFG_RST ((UBX_CLASS_CFG) | UBX_ID_CFG_RST << 8)
138 #define UBX_MSG_CFG_SBAS ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)
139 #define UBX_MSG_CFG_TMODE3 ((UBX_CLASS_CFG) | UBX_ID_CFG_TMODE3 << 8)
140 #define UBX_MSG_CFG_VALGET ((UBX_CLASS_CFG) | UBX_ID_CFG_VALGET << 8)
141 #define UBX_MSG_CFG_VALSET ((UBX_CLASS_CFG) | UBX_ID_CFG_VALSET << 8)
142 #define UBX_MSG_CFG_VALDEL ((UBX_CLASS_CFG) | UBX_ID_CFG_VALDEL << 8)
143 #define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
144 #define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
145 #define UBX_MSG_MON_RF ((UBX_CLASS_MON) | UBX_ID_MON_RF << 8)
146 #define UBX_MSG_RTCM3_1005 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1005 << 8)
147 #define UBX_MSG_RTCM3_1077 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1077 << 8)
148 #define UBX_MSG_RTCM3_1087 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1087 << 8)
149 #define UBX_MSG_RTCM3_1074 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1074 << 8)
150 #define UBX_MSG_RTCM3_1084 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1084 << 8)
151 #define UBX_MSG_RTCM3_1094 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1094 << 8)
152 #define UBX_MSG_RTCM3_1097 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1097 << 8)
153 #define UBX_MSG_RTCM3_1124 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1124 << 8)
154 #define UBX_MSG_RTCM3_1127 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1127 << 8)
155 #define UBX_MSG_RTCM3_1230 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1230 << 8)
156 #define UBX_MSG_RTCM3_4072 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_4072 << 8)
157 
158 /* RX NAV-PVT message content details */
159 /* Bitfield "valid" masks */
160 #define UBX_RX_NAV_PVT_VALID_VALIDDATE 0x01 /**< validDate (Valid UTC Date) */
161 #define UBX_RX_NAV_PVT_VALID_VALIDTIME 0x02 /**< validTime (Valid UTC Time) */
162 #define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED 0x04 /**< fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty)) */
163 
164 /* Bitfield "flags" masks */
165 #define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK 0x01 /**< gnssFixOK (A valid fix (i.e within DOP & accuracy masks)) */
166 #define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN 0x02 /**< diffSoln (1 if differential corrections were applied) */
167 #define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C /**< psmState (Power Save Mode state (see Power Management)) */
168 #define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 /**< headVehValid (Heading of vehicle is valid) */
169 #define UBX_RX_NAV_PVT_FLAGS_CARRSOLN 0xC0 /**< Carrier phase range solution (RTK mode) */
170 
171 /* RX NAV-TIMEUTC message content details */
172 /* Bitfield "valid" masks */
173 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW 0x01 /**< validTOW (1 = Valid Time of Week) */
174 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN 0x02 /**< validWKN (1 = Valid Week Number) */
175 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC 0x04 /**< validUTC (1 = Valid UTC Time) */
176 #define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD 0xF0 /**< utcStandard (0..15 = UTC standard identifier) */
177 
178 /* TX CFG-PRT message contents
179  * Note: not used with protocol version 27+ anymore
180  */
181 #define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */
182 #define UBX_TX_CFG_PRT_PORTID_USB 0x03 /**< USB */
183 #define UBX_TX_CFG_PRT_PORTID_SPI 0x04 /**< SPI */
184 #define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
185 #define UBX_TX_CFG_PRT_MODE_SPI 0x00000100
186 #define UBX_TX_CFG_PRT_BAUDRATE 38400 /**< choose 38400 as GPS baudrate (pre M8* boards only) */
187 #define UBX_TX_CFG_PRT_INPROTOMASK_GPS ((1<<5) | 0x01) /**< RTCM3 in and UBX in */
188 #define UBX_TX_CFG_PRT_INPROTOMASK_RTCM (0x01) /**< UBX in */
189 #define UBX_TX_CFG_PRT_OUTPROTOMASK_GPS (0x01) /**< UBX out */
190 #define UBX_TX_CFG_PRT_OUTPROTOMASK_RTCM ((1<<5) | 0x01) /**< RTCM3 out and UBX out */
191 
192 #define UBX_BAUDRATE_M8_AND_NEWER 115200 /**< baudrate for M8+ boards */
193 
194 /* TX CFG-RATE message contents
195  * Note: not used with protocol version 27+ anymore
196  */
197 #define UBX_TX_CFG_RATE_MEASINTERVAL 200 /**< 200ms for 5Hz (F9* boards use 10Hz) */
198 #define UBX_TX_CFG_RATE_NAVRATE 1 /**< cannot be changed */
199 #define UBX_TX_CFG_RATE_TIMEREF 0 /**< 0: UTC, 1: GPS time */
200 
201 /* TX CFG-NAV5 message contents
202  * Note: not used with protocol version 27+ anymore
203  */
204 #define UBX_TX_CFG_NAV5_MASK 0x0005 /**< Only update dynamic model and fix mode */
205 #define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */
206 
207 /* TX CFG-RST message contents
208  */
209 #define UBX_TX_CFG_RST_BBR_MODE_HOT_START 0
210 #define UBX_TX_CFG_RST_BBR_MODE_WARM_START 1
211 #define UBX_TX_CFG_RST_BBR_MODE_COLD_START 0xFFFF
212 #define UBX_TX_CFG_RST_MODE_HARDWARE 0
213 #define UBX_TX_CFG_RST_MODE_SOFTWARE 1
214 
215 /* Key ID's for CFG-VAL{GET,SET,DEL} */
216 #define UBX_CFG_KEY_CFG_UART1_BAUDRATE 0x40520001
217 #define UBX_CFG_KEY_CFG_UART1_STOPBITS 0x20520002
218 #define UBX_CFG_KEY_CFG_UART1_DATABITS 0x20520003
219 #define UBX_CFG_KEY_CFG_UART1_PARITY 0x20520004
220 #define UBX_CFG_KEY_CFG_UART1_ENABLED 0x20520005
221 #define UBX_CFG_KEY_CFG_UART1_REMAP 0x20520006
222 #define UBX_CFG_KEY_CFG_UART1INPROT_UBX 0x10730001
223 #define UBX_CFG_KEY_CFG_UART1INPROT_NMEA 0x10730002
224 #define UBX_CFG_KEY_CFG_UART1INPROT_RTCM3X 0x10730004
225 #define UBX_CFG_KEY_CFG_UART1OUTPROT_UBX 0x10740001
226 #define UBX_CFG_KEY_CFG_UART1OUTPROT_NMEA 0x10740002
227 #define UBX_CFG_KEY_CFG_UART1OUTPROT_RTCM3X 0x10740004
228 
229 #define UBX_CFG_KEY_CFG_UART2_BAUDRATE 0x40530001
230 #define UBX_CFG_KEY_CFG_UART2_STOPBITS 0x20530002
231 #define UBX_CFG_KEY_CFG_UART2_DATABITS 0x20530003
232 #define UBX_CFG_KEY_CFG_UART2_PARITY 0x20530004
233 #define UBX_CFG_KEY_CFG_UART2_ENABLED 0x20530005
234 #define UBX_CFG_KEY_CFG_UART2_REMAP 0x20530006
235 #define UBX_CFG_KEY_CFG_UART2INPROT_UBX 0x10750001
236 #define UBX_CFG_KEY_CFG_UART2INPROT_NMEA 0x10750002
237 #define UBX_CFG_KEY_CFG_UART2INPROT_RTCM3X 0x10750004
238 #define UBX_CFG_KEY_CFG_UART2OUTPROT_UBX 0x10760001
239 #define UBX_CFG_KEY_CFG_UART2OUTPROT_NMEA 0x10760002
240 #define UBX_CFG_KEY_CFG_UART2OUTPROT_RTCM3X 0x10760004
241 
242 #define UBX_CFG_KEY_CFG_USB_ENABLED 0x10650001
243 #define UBX_CFG_KEY_CFG_USBINPROT_UBX 0x10770001
244 #define UBX_CFG_KEY_CFG_USBINPROT_NMEA 0x10770002
245 #define UBX_CFG_KEY_CFG_USBINPROT_RTCM3X 0x10770004
246 #define UBX_CFG_KEY_CFG_USBOUTPROT_UBX 0x10780001
247 #define UBX_CFG_KEY_CFG_USBOUTPROT_NMEA 0x10780002
248 #define UBX_CFG_KEY_CFG_USBOUTPROT_RTCM3X 0x10780004
249 
250 #define UBX_CFG_KEY_CFG_SPIINPROT_UBX 0x10790001
251 #define UBX_CFG_KEY_CFG_SPIINPROT_NMEA 0x10790002
252 #define UBX_CFG_KEY_CFG_SPIINPROT_RTCM3X 0x10790004
253 #define UBX_CFG_KEY_CFG_SPIOUTPROT_UBX 0x107a0001
254 #define UBX_CFG_KEY_CFG_SPIOUTPROT_NMEA 0x107a0002
255 #define UBX_CFG_KEY_CFG_SPIOUTPROT_RTCM3X 0x107a0004
256 
257 #define UBX_CFG_KEY_NAVHPG_DGNSSMODE 0x20140011
258 
259 #define UBX_CFG_KEY_NAVSPG_FIXMODE 0x20110011
260 #define UBX_CFG_KEY_NAVSPG_UTCSTANDARD 0x2011001c
261 #define UBX_CFG_KEY_NAVSPG_DYNMODEL 0x20110021
262 
263 #define UBX_CFG_KEY_ODO_USE_ODO 0x10220001
264 #define UBX_CFG_KEY_ODO_USE_COG 0x10220002
265 #define UBX_CFG_KEY_ODO_OUTLPVEL 0x10220003
266 #define UBX_CFG_KEY_ODO_OUTLPCOG 0x10220004
267 
268 #define UBX_CFG_KEY_RATE_MEAS 0x30210001
269 #define UBX_CFG_KEY_RATE_NAV 0x30210002
270 #define UBX_CFG_KEY_RATE_TIMEREF 0x20210003
271 
272 #define UBX_CFG_KEY_TMODE_MODE 0x20030001
273 #define UBX_CFG_KEY_TMODE_POS_TYPE 0x20030002
274 #define UBX_CFG_KEY_TMODE_LAT 0x40030009
275 #define UBX_CFG_KEY_TMODE_LON 0x4003000a
276 #define UBX_CFG_KEY_TMODE_HEIGHT 0x4003000b
277 #define UBX_CFG_KEY_TMODE_LAT_HP 0x2003000c
278 #define UBX_CFG_KEY_TMODE_LON_HP 0x2003000d
279 #define UBX_CFG_KEY_TMODE_HEIGHT_HP 0x2003000e
280 #define UBX_CFG_KEY_TMODE_FIXED_POS_ACC 0x4003000f
281 #define UBX_CFG_KEY_TMODE_SVIN_MIN_DUR 0x40030010
282 #define UBX_CFG_KEY_TMODE_SVIN_ACC_LIMIT 0x40030011
283 
284 #define UBX_CFG_KEY_MSGOUT_UBX_MON_RF_I2C 0x20910359
285 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_SVIN_I2C 0x20910088
286 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_SAT_I2C 0x20910015
287 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_DOP_I2C 0x20910038
288 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_PVT_I2C 0x20910006
289 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1005_I2C 0x209102bd
290 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1077_I2C 0x209102cc
291 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1087_I2C 0x209102d1
292 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1097_I2C 0x20910318
293 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1127_I2C 0x209102d6
294 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1230_I2C 0x20910303
295 
296 #define UBX_CFG_KEY_SPI_ENABLED 0x10640006
297 #define UBX_CFG_KEY_SPI_MAXFF 0x20640001
298 
299 
300 class RTCMParsing;
301 
302 
303 /*** u-blox protocol binary message and payload definitions ***/
304 #pragma pack(push, 1)
305 
306 /* General: Header */
307 typedef struct {
308  uint8_t sync1;
309  uint8_t sync2;
310  uint16_t msg;
311  uint16_t length;
312 } ubx_header_t;
313 
314 /* General: Checksum */
315 typedef struct {
316  uint8_t ck_a;
317  uint8_t ck_b;
318 } ubx_checksum_t ;
319 
320 /* Rx NAV-POSLLH */
321 typedef struct {
322  uint32_t iTOW; /**< GPS Time of Week [ms] */
323  int32_t lon; /**< Longitude [1e-7 deg] */
324  int32_t lat; /**< Latitude [1e-7 deg] */
325  int32_t height; /**< Height above ellipsoid [mm] */
326  int32_t hMSL; /**< Height above mean sea level [mm] */
327  uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
328  uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
330 
331 /* Rx NAV-DOP */
332 typedef struct {
333  uint32_t iTOW; /**< GPS Time of Week [ms] */
334  uint16_t gDOP; /**< Geometric DOP [0.01] */
335  uint16_t pDOP; /**< Position DOP [0.01] */
336  uint16_t tDOP; /**< Time DOP [0.01] */
337  uint16_t vDOP; /**< Vertical DOP [0.01] */
338  uint16_t hDOP; /**< Horizontal DOP [0.01] */
339  uint16_t nDOP; /**< Northing DOP [0.01] */
340  uint16_t eDOP; /**< Easting DOP [0.01] */
342 
343 /* Rx NAV-SOL */
344 typedef struct {
345  uint32_t iTOW; /**< GPS Time of Week [ms] */
346  int32_t fTOW; /**< Fractional part of iTOW (range: +/-500000) [ns] */
347  int16_t week; /**< GPS week */
348  uint8_t gpsFix; /**< GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */
349  uint8_t flags;
350  int32_t ecefX;
351  int32_t ecefY;
352  int32_t ecefZ;
353  uint32_t pAcc;
354  int32_t ecefVX;
355  int32_t ecefVY;
356  int32_t ecefVZ;
357  uint32_t sAcc;
358  uint16_t pDOP; /**< Position DOP [0.01] */
359  uint8_t reserved1;
360  uint8_t numSV; /**< Number of SVs used in Nav Solution */
361  uint32_t reserved2;
363 
364 /* Rx NAV-PVT (ubx8) */
365 typedef struct {
366  uint32_t iTOW; /**< GPS Time of Week [ms] */
367  uint16_t year; /**< Year (UTC)*/
368  uint8_t month; /**< Month, range 1..12 (UTC) */
369  uint8_t day; /**< Day of month, range 1..31 (UTC) */
370  uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
371  uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
372  uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
373  uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */
374  uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
375  int32_t nano; /**< Fraction of second (UTC) [-1e9...1e9 ns] */
376  uint8_t fixType; /**< GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning, 5 = time only fix */
377  uint8_t flags; /**< Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...) */
378  uint8_t reserved1;
379  uint8_t numSV; /**< Number of SVs used in Nav Solution */
380  int32_t lon; /**< Longitude [1e-7 deg] */
381  int32_t lat; /**< Latitude [1e-7 deg] */
382  int32_t height; /**< Height above ellipsoid [mm] */
383  int32_t hMSL; /**< Height above mean sea level [mm] */
384  uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */
385  uint32_t vAcc; /**< Vertical accuracy estimate [mm] */
386  int32_t velN; /**< NED north velocity [mm/s]*/
387  int32_t velE; /**< NED east velocity [mm/s]*/
388  int32_t velD; /**< NED down velocity [mm/s]*/
389  int32_t gSpeed; /**< Ground Speed (2-D) [mm/s] */
390  int32_t headMot; /**< Heading of motion (2-D) [1e-5 deg] */
391  uint32_t sAcc; /**< Speed accuracy estimate [mm/s] */
392  uint32_t headAcc; /**< Heading accuracy estimate (motion and vehicle) [1e-5 deg] */
393  uint16_t pDOP; /**< Position DOP [0.01] */
394  uint16_t reserved2;
395  uint32_t reserved3;
396  int32_t headVeh; /**< (ubx8+ only) Heading of vehicle (2-D) [1e-5 deg] */
397  uint32_t reserved4; /**< (ubx8+ only) */
399 #define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7 (sizeof(ubx_payload_rx_nav_pvt_t) - 8)
400 #define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8 (sizeof(ubx_payload_rx_nav_pvt_t))
401 
402 /* Rx NAV-TIMEUTC */
403 typedef struct {
404  uint32_t iTOW; /**< GPS Time of Week [ms] */
405  uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */
406  int32_t nano; /**< Fraction of second, range -1e9 .. 1e9 (UTC) [ns] */
407  uint16_t year; /**< Year, range 1999..2099 (UTC) */
408  uint8_t month; /**< Month, range 1..12 (UTC) */
409  uint8_t day; /**< Day of month, range 1..31 (UTC) */
410  uint8_t hour; /**< Hour of day, range 0..23 (UTC) */
411  uint8_t min; /**< Minute of hour, range 0..59 (UTC) */
412  uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */
413  uint8_t valid; /**< Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...) */
415 
416 /* Rx NAV-SVINFO Part 1 */
417 typedef struct {
418  uint32_t iTOW; /**< GPS Time of Week [ms] */
419  uint8_t numCh; /**< Number of channels */
420  uint8_t globalFlags;
421  uint16_t reserved2;
423 
424 /* Rx NAV-SVINFO Part 2 (repeated) */
425 typedef struct {
426  uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */
427  uint8_t svid; /**< Satellite ID */
428  uint8_t flags;
429  uint8_t quality;
430  uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength) [dbHz] */
431  int8_t elev; /**< Elevation [deg] */
432  int16_t azim; /**< Azimuth [deg] */
433  int32_t prRes; /**< Pseudo range residual [cm] */
435 
436 /* Rx NAV-SAT Part 1 */
437 typedef struct {
438  uint32_t iTOW; /**< GPS Time of Week [ms] */
439  uint8_t version; /**< Message version (1) */
440  uint8_t numSvs; /**< Number of Satellites */
441  uint16_t reserved;
443 
444 /* Rx NAV-SAT Part 2 (repeated) */
445 typedef struct {
446  uint8_t gnssId; /**< GNSS identifier */
447  uint8_t svId; /**< Satellite ID */
448  uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength) [dbHz] */
449  int8_t elev; /**< Elevation [deg] range: +/-90 */
450  int16_t azim; /**< Azimuth [deg] range: 0-360 */
451  int16_t prRes; /**< Pseudo range residual [0.1 m] */
452  uint32_t flags;
454 
455 /* Rx NAV-SVIN (survey-in info) */
456 typedef struct {
457  uint8_t version;
458  uint8_t reserved1[3];
459  uint32_t iTOW;
460  uint32_t dur;
461  int32_t meanX;
462  int32_t meanY;
463  int32_t meanZ;
464  int8_t meanXHP;
465  int8_t meanYHP;
466  int8_t meanZHP;
467  int8_t reserved2;
468  uint32_t meanAcc;
469  uint32_t obs;
470  uint8_t valid;
471  uint8_t active;
472  uint8_t reserved3[2];
474 
475 /* Rx NAV-VELNED */
476 typedef struct {
477  uint32_t iTOW; /**< GPS Time of Week [ms] */
478  int32_t velN; /**< North velocity component [cm/s]*/
479  int32_t velE; /**< East velocity component [cm/s]*/
480  int32_t velD; /**< Down velocity component [cm/s]*/
481  uint32_t speed; /**< Speed (3-D) [cm/s] */
482  uint32_t gSpeed; /**< Ground speed (2-D) [cm/s] */
483  int32_t heading; /**< Heading of motion 2-D [1e-5 deg] */
484  uint32_t sAcc; /**< Speed accuracy estimate [cm/s] */
485  uint32_t cAcc; /**< Course / Heading accuracy estimate [1e-5 deg] */
487 
488 /* Rx MON-HW (ubx6) */
489 typedef struct {
490  uint32_t pinSel;
491  uint32_t pinBank;
492  uint32_t pinDir;
493  uint32_t pinVal;
494  uint16_t noisePerMS;
495  uint16_t agcCnt;
496  uint8_t aStatus;
497  uint8_t aPower;
498  uint8_t flags;
499  uint8_t reserved1;
500  uint32_t usedMask;
501  uint8_t VP[25];
502  uint8_t jamInd;
503  uint16_t reserved3;
504  uint32_t pinIrq;
505  uint32_t pullH;
506  uint32_t pullL;
508 
509 /* Rx MON-HW (ubx7+) */
510 typedef struct {
511  uint32_t pinSel;
512  uint32_t pinBank;
513  uint32_t pinDir;
514  uint32_t pinVal;
515  uint16_t noisePerMS;
516  uint16_t agcCnt;
517  uint8_t aStatus;
518  uint8_t aPower;
519  uint8_t flags;
520  uint8_t reserved1;
521  uint32_t usedMask;
522  uint8_t VP[17];
523  uint8_t jamInd;
524  uint16_t reserved3;
525  uint32_t pinIrq;
526  uint32_t pullH;
527  uint32_t pullL;
529 
530 /* Rx MON-RF (replaces MON-HW, protocol 27+) */
531 typedef struct {
532  uint8_t version;
533  uint8_t nBlocks; /**< number of RF blocks included */
534  uint8_t reserved1[2];
535 
537  uint8_t blockId; /**< RF block id */
538  uint8_t flags; /**< jammingState */
539  uint8_t antStatus; /**< Status of the antenna superior state machine */
540  uint8_t antPower; /**< Current power status of antenna */
541  uint32_t postStatus; /**< POST status word */
542  uint8_t reserved2[4];
543  uint16_t noisePerMS; /**< Noise level as measured by the GPS core */
544  uint16_t agcCnt; /**< AGC Monitor (counts SIGI xor SIGLO, range 0 to 8191 */
545  uint8_t jamInd; /**< CW jamming indicator, scaled (0=no CW jamming, 255=strong CW jamming) */
546  int8_t ofsI; /**< Imbalance of I-part of complex signal */
547  uint8_t magI; /**< Magnitude of I-part of complex signal (0=no signal, 255=max magnitude) */
548  int8_t ofsQ; /**< Imbalance of Q-part of complex signal */
549  uint8_t magQ; /**< Magnitude of Q-part of complex signal (0=no signal, 255=max magnitude) */
550  uint8_t reserved3[3];
551  };
552 
553  ubx_payload_rx_mon_rf_block_t block[1]; ///< only read out the first block
555 
556 /* Rx MON-VER Part 1 */
557 typedef struct {
558  uint8_t swVersion[30];
559  uint8_t hwVersion[10];
561 
562 /* Rx MON-VER Part 2 (repeated) */
563 typedef struct {
564  uint8_t extension[30];
566 
567 /* Rx ACK-ACK */
568 typedef union {
569  uint16_t msg;
570  struct {
571  uint8_t clsID;
572  uint8_t msgID;
573  };
575 
576 /* Rx ACK-NAK */
577 typedef union {
578  uint16_t msg;
579  struct {
580  uint8_t clsID;
581  uint8_t msgID;
582  };
584 
585 /* Tx CFG-PRT */
586 typedef struct {
587  uint8_t portID;
588  uint8_t reserved0;
589  uint16_t txReady;
590  uint32_t mode;
591  uint32_t baudRate;
592  uint16_t inProtoMask;
593  uint16_t outProtoMask;
594  uint16_t flags;
595  uint16_t reserved5;
597 
598 /* Tx CFG-RATE */
599 typedef struct {
600  uint16_t measRate; /**< Measurement Rate, GPS measurements are taken every measRate milliseconds */
601  uint16_t navRate; /**< Navigation Rate, in number of measurement cycles. This parameter cannot be changed, and must be set to 1 */
602  uint16_t timeRef; /**< Alignment to reference time: 0 = UTC time, 1 = GPS time */
604 
605 /* Tx CFG-CFG */
606 typedef struct {
607  uint32_t clearMask; /**< Clear settings */
608  uint32_t saveMask; /**< Save settings */
609  uint32_t loadMask; /**< Load settings */
610  uint8_t deviceMask; /**< Storage devices to apply this top */
612 
613 /* Tx CFG-VALSET (protocol version 27+) */
614 typedef struct {
615  uint8_t version; /**< Message version, set to 0 */
616  uint8_t layers; /**< The layers where the configuration should be applied (@see UBX_CFG_LAYER_*) */
617  uint8_t reserved1[2];
618  uint8_t cfgData; /**< configuration data (key and value pairs, max 64) */
620 
621 #define UBX_CFG_LAYER_RAM (1 << 0)
622 #define UBX_CFG_LAYER_BBR (1 << 1)
623 #define UBX_CFG_LAYER_FLASH (1 << 2)
624 
625 /* Tx CFG-NAV5 */
626 typedef struct {
627  uint16_t mask;
628  uint8_t dynModel; /**< Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */
629  uint8_t fixMode; /**< Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D */
630  int32_t fixedAlt;
631  uint32_t fixedAltVar;
632  int8_t minElev;
633  uint8_t drLimit;
634  uint16_t pDop;
635  uint16_t tDop;
636  uint16_t pAcc;
637  uint16_t tAcc;
639  uint8_t dgpsTimeOut;
640  uint8_t cnoThreshNumSVs; /**< (ubx7+ only, else 0) */
641  uint8_t cnoThresh; /**< (ubx7+ only, else 0) */
642  uint16_t reserved;
643  uint16_t staticHoldMaxDist; /**< (ubx8+ only, else 0) */
644  uint8_t utcStandard; /**< (ubx8+ only, else 0) */
645  uint8_t reserved3;
646  uint32_t reserved4;
648 
649 /* tx cfg-rst */
650 typedef struct {
651  uint16_t navBbrMask;
652  uint8_t resetMode;
653  uint8_t reserved1;
655 
656 /* tx cfg-sbas */
657 typedef struct {
658  uint8_t mode;
659  uint8_t usage;
660  uint8_t maxSBAS;
661  uint8_t scanmode2;
662  uint32_t scanmode1;
664 
665 /* Tx CFG-MSG */
666 typedef struct {
667  union {
668  uint16_t msg;
669  struct {
670  uint8_t msgClass;
671  uint8_t msgID;
672  };
673  };
674  uint8_t rate;
676 
677 /* CFG-TMODE3 ublox 8 (protocol version >= 20) */
678 typedef struct {
679  uint8_t version;
680  uint8_t reserved1;
681  uint16_t flags;
682  int32_t ecefXOrLat;
683  int32_t ecefYOrLon;
684  int32_t ecefZOrAlt;
685  int8_t ecefXOrLatHP;
686  int8_t ecefYOrLonHP;
687  int8_t ecefZOrAltHP;
688  uint8_t reserved2;
689  uint32_t fixedPosAcc;
690  uint32_t svinMinDur;
691  uint32_t svinAccLimit;
692  uint8_t reserved3[8];
694 
695 /* General message and payload buffer union */
696 typedef union {
724 } ubx_buf_t;
725 
726 #pragma pack(pop)
727 /*** END OF u-blox protocol binary message and payload definitions ***/
728 
729 /* Decoder state */
730 typedef enum {
740 
743 
744 /* Rx message state */
745 typedef enum {
751 
752 /* ACK state */
753 typedef enum {
759 
760 
762 {
763 public:
764  GPSDriverUBX(Interface gpsInterface, GPSCallbackPtr callback, void *callback_user,
765  struct vehicle_gps_position_s *gps_position,
766  struct satellite_info_s *satellite_info,
767  uint8_t dynamic_model = 7);
768 
769  virtual ~GPSDriverUBX();
770 
771  int receive(unsigned timeout) override;
772  int configure(unsigned &baudrate, OutputMode output_mode) override;
773  int reset(GPSRestartType restart_type) override;
774 
775 private:
776 
777  /**
778  * Start or restart the survey-in procees. This is only used in RTCM ouput mode.
779  * It will be called automatically after configuring.
780  * @return 0 on success, <0 on error
781  */
782  int restartSurveyIn();
783 
784  /**
785  * restartSurveyIn for protocol version < 27 (_proto_ver_27_or_higher == false)
786  */
787  int restartSurveyInPreV27();
788 
789  /**
790  * Parse the binary UBX packet
791  */
792  int parseChar(const uint8_t b);
793 
794  /**
795  * Start payload rx
796  */
797  int payloadRxInit(void);
798 
799  /**
800  * Add payload rx byte
801  */
802  int payloadRxAdd(const uint8_t b);
803  int payloadRxAddNavSvinfo(const uint8_t b);
804  int payloadRxAddNavSat(const uint8_t b);
805  int payloadRxAddMonVer(const uint8_t b);
806 
807  /**
808  * Finish payload rx
809  */
810  int payloadRxDone(void);
811 
812  /**
813  * Reset the parse state machine for a fresh start
814  */
815  void decodeInit(void);
816 
817  /**
818  * While parsing add every byte (except the sync bytes) to the checksum
819  */
820  void addByteToChecksum(const uint8_t);
821 
822  /**
823  * Send a message
824  * @return true on success, false on write error (errno set)
825  */
826  bool sendMessage(const uint16_t msg, const uint8_t *payload, const uint16_t length);
827 
828  /**
829  * Configure message rate.
830  * Note: this is deprecated with protocol version >= 27
831  * @return true on success, false on write error
832  */
833  bool configureMessageRate(const uint16_t msg, const uint8_t rate);
834 
835  /**
836  * Calculate & add checksum for given buffer
837  */
838  void calcChecksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum);
839 
840  /**
841  * Wait for message acknowledge
842  */
843  int waitForAck(const uint16_t msg, const unsigned timeout, const bool report);
844 
845  /**
846  * Combines the configure_message_rate & wait_for_ack calls.
847  * Note: this is deprecated with protocol version >= 27
848  * @return true on success
849  */
850  inline bool configureMessageRateAndAck(uint16_t msg, uint8_t rate, bool report_ack_error = false);
851 
852  /**
853  * Send configuration values and desired message rates
854  * @return 0 on success, <0 on error
855  */
856  int configureDevice();
857  /**
858  * Send configuration values and desired message rates (for protocol version < 27)
859  * @return 0 on success, <0 on error
860  */
861  int configureDevicePreV27();
862 
863  /**
864  * Init _buf as CFG-VALSET
865  * @return size of the message (without any config values)
866  */
867  int initCfgValset();
868 
869  /**
870  * Add a configuration value to _buf and increase the message size msg_size as needed
871  * @param key_id one of the UBX_CFG_KEY_* constants
872  * @param value configuration value
873  * @param msg_size CFG-VALSET message size: this is an input & output param
874  * @return true on success, false if buffer too small
875  */
876  template<typename T>
877  bool cfgValset(uint32_t key_id, T value, int &msg_size);
878 
879  /**
880  * Add a configuration value that is port-specific (MSGOUT messages).
881  * Note: Key ID must be the one for I2C, and the implementation assumes the
882  * Key ID's are in increasing order for the other ports: I2C, UART1, UART2, USB, SPI
883  * (this is a safe assumption for all MSGOUT messages according to u-blox).
884  *
885  * @param key_id I2C key ID
886  * @param value configuration value
887  * @param msg_size CFG-VALSET message size: this is an input & output param
888  * @return true on success, false if buffer too small
889  */
890  bool cfgValsetPort(uint32_t key_id, uint8_t value, int &msg_size);
891 
892  int activateRTCMOutput();
893 
894  /**
895  * Calculate FNV1 hash
896  */
897  uint32_t fnv1_32_str(uint8_t *str, uint32_t hval);
898 
899  enum class Board : uint8_t {
900  unknown = 0,
901  u_blox5 = 5,
902  u_blox6 = 6,
903  u_blox7 = 7,
904  u_blox8 = 8, ///< M8N or M8P
905  u_blox9 = 9, ///< F9P
906  };
907 
908  struct vehicle_gps_position_s *_gps_position {nullptr};
909  struct satellite_info_s *_satellite_info {nullptr};
910  uint64_t _last_timestamp_time{0};
911  bool _configured{false};
913  bool _got_posllh{false};
914  bool _got_velned{false};
916  uint16_t _rx_msg{};
918  uint16_t _rx_payload_length{};
919  uint16_t _rx_payload_index{};
920  uint8_t _rx_ck_a{};
921  uint8_t _rx_ck_b{};
922  gps_abstime _disable_cmd_last{0};
923  uint16_t _ack_waiting_msg{0};
925  uint32_t _ubx_version{0};
926  bool _use_nav_pvt{false};
927  bool _proto_ver_27_or_higher{false}; ///< true if protocol version 27 or higher detected
928  OutputMode _output_mode{OutputMode::GPS};
929 
930  RTCMParsing *_rtcm_parsing{nullptr};
931 
933  Board _board{Board::unknown};
934 
935  // ublox Dynamic platform model default 7: airborne with <2g acceleration
936  uint8_t _dyn_model{7};
937 };
938 
939 
uint16_t agcCnt
AGC Monitor (counts SIGI xor SIGLO, range 0 to 8191.
Definition: ubx.h:544
uint16_t tDOP
Time DOP [0.01].
Definition: ubx.h:336
uint32_t cAcc
Course / Heading accuracy estimate [1e-5 deg].
Definition: ubx.h:485
ubx_payload_tx_cfg_rst_t payload_tx_cfg_rst
Definition: ubx.h:718
uint8_t magI
Magnitude of I-part of complex signal (0=no signal, 255=max magnitude)
Definition: ubx.h:547
const Interface _interface
Definition: ubx.h:932
uint32_t sAcc
Speed accuracy estimate [cm/s].
Definition: ubx.h:484
ubx_payload_rx_nav_svinfo_part2_t payload_rx_nav_svinfo_part2
Definition: ubx.h:703
uint32_t hAcc
Horizontal accuracy estimate [mm].
Definition: ubx.h:327
uint8_t ck_b
Definition: ubx.h:317
uint8_t min
Minute of hour, range 0..59 (UTC)
Definition: ubx.h:411
ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6
Definition: ubx.h:708
uint16_t pDOP
Position DOP [0.01].
Definition: ubx.h:393
uint16_t timeRef
Alignment to reference time: 0 = UTC time, 1 = GPS time.
Definition: ubx.h:602
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:333
uint8_t dynModel
Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g.
Definition: ubx.h:628
uint8_t ck_a
Definition: ubx.h:316
uint16_t navBbrMask
Definition: ubx.h:651
GPSRestartType
Definition: gps_helper.h:101
uint16_t txReady
Definition: ubx.h:589
uint8_t numCh
Number of channels.
Definition: ubx.h:419
int32_t height
Height above ellipsoid [mm].
Definition: ubx.h:325
ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh
Definition: ubx.h:698
uint8_t version
Message version, set to 0.
Definition: ubx.h:615
uint32_t hAcc
Horizontal accuracy estimate [mm].
Definition: ubx.h:384
uint16_t navRate
Navigation Rate, in number of measurement cycles.
Definition: ubx.h:601
uint32_t vAcc
Vertical accuracy estimate [mm].
Definition: ubx.h:328
int8_t ofsQ
Imbalance of Q-part of complex signal.
Definition: ubx.h:548
uint8_t gpsFix
GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning...
Definition: ubx.h:348
uint8_t month
Month, range 1..12 (UTC)
Definition: ubx.h:408
ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7
Definition: ubx.h:709
uint8_t valid
Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...)
Definition: ubx.h:413
uint16_t year
Year, range 1999..2099 (UTC)
Definition: ubx.h:407
ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc
Definition: ubx.h:701
uint16_t msg
Definition: ubx.h:310
ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg
Definition: ubx.h:720
ubx_payload_tx_cfg_cfg_t payload_tx_cfg_cfg
Definition: ubx.h:722
uint32_t tAcc
Time accuracy estimate (UTC) [ns].
Definition: ubx.h:405
ubx_payload_rx_mon_rf_t payload_rx_mon_rf
Definition: ubx.h:710
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:477
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:345
uint32_t sAcc
Speed accuracy estimate [mm/s].
Definition: ubx.h:391
ubx_payload_rx_nav_sol_t payload_rx_nav_sol
Definition: ubx.h:699
int32_t velN
North velocity component [cm/s].
Definition: ubx.h:478
uint8_t gnssId
GNSS identifier.
Definition: ubx.h:446
uint8_t day
Day of month, range 1..31 (UTC)
Definition: ubx.h:369
ubx_payload_rx_nav_pvt_t payload_rx_nav_pvt
Definition: ubx.h:697
uint32_t loadMask
Load settings.
Definition: ubx.h:609
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:438
ubx_payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1
Definition: ubx.h:711
uint8_t antPower
Current power status of antenna.
Definition: ubx.h:540
int32_t lat
Latitude [1e-7 deg].
Definition: ubx.h:324
uint32_t fixedAltVar
Definition: ubx.h:631
ubx_payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2
Definition: ubx.h:712
void reset()
reset the parsing state
Definition: rtcm.cpp:49
int8_t elev
Elevation [deg] range: +/-90.
Definition: ubx.h:449
int32_t lon
Longitude [1e-7 deg].
Definition: ubx.h:380
uint8_t sec
Seconds of minute, range 0..60 (UTC)
Definition: ubx.h:412
uint16_t eDOP
Easting DOP [0.01].
Definition: ubx.h:340
uint8_t numSvs
Number of Satellites.
Definition: ubx.h:440
ubx_payload_rx_nav_sat_part1_t payload_rx_nav_sat_part1
Definition: ubx.h:704
uint32_t reserved4
(ubx8+ only)
Definition: ubx.h:397
hrt_abstime gps_abstime
Definition: definitions.h:58
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:322
uint16_t inProtoMask
Definition: ubx.h:592
int16_t week
GPS week.
Definition: ubx.h:347
ubx_payload_tx_cfg_tmode3_t payload_tx_cfg_tmode3
Definition: ubx.h:721
ubx_rxmsg_state_t
Definition: ubx.h:745
uint16_t outProtoMask
Definition: ubx.h:593
int32_t height
Height above ellipsoid [mm].
Definition: ubx.h:382
static enum ST24_DECODE_STATE _decode_state
Definition: st24.cpp:66
uint8_t cnoThreshNumSVs
(ubx7+ only, else 0)
Definition: ubx.h:640
uint32_t tAcc
Time accuracy estimate (UTC) [ns].
Definition: ubx.h:374
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:366
uint32_t speed
Speed (3-D) [cm/s].
Definition: ubx.h:481
uint32_t saveMask
Save settings.
Definition: ubx.h:608
int32_t gSpeed
Ground Speed (2-D) [mm/s].
Definition: ubx.h:389
uint8_t valid
Validity flags (see UBX_RX_NAV_PVT_VALID_...)
Definition: ubx.h:373
uint32_t clearMask
Clear settings.
Definition: ubx.h:607
int32_t nano
Fraction of second, range -1e9 .
Definition: ubx.h:406
uint8_t cno
Carrier to Noise Ratio (Signal Strength) [dbHz].
Definition: ubx.h:448
uint8_t antStatus
Status of the antenna superior state machine.
Definition: ubx.h:539
uint8_t min
Minute of hour, range 0..59 (UTC)
Definition: ubx.h:371
uint8_t cnoThresh
(ubx7+ only, else 0)
Definition: ubx.h:641
uint32_t reserved2
Definition: ubx.h:361
int16_t prRes
Pseudo range residual [0.1 m].
Definition: ubx.h:451
int32_t velD
NED down velocity [mm/s].
Definition: ubx.h:388
int32_t velE
NED east velocity [mm/s].
Definition: ubx.h:387
uint8_t fixMode
Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D.
Definition: ubx.h:629
int(* GPSCallbackPtr)(GPSCallbackType type, void *data1, int data2, void *user)
Callback function for platform-specific stuff.
Definition: gps_helper.h:132
ubx_payload_rx_nav_dop_t payload_rx_nav_dop
Definition: ubx.h:700
ubx_payload_tx_cfg_valset_t payload_tx_cfg_valset
Definition: ubx.h:723
uint8_t utcStandard
(ubx8+ only, else 0)
Definition: ubx.h:644
uint8_t nBlocks
number of RF blocks included
Definition: ubx.h:533
uint32_t reserved4
Definition: ubx.h:646
uint16_t gDOP
Geometric DOP [0.01].
Definition: ubx.h:334
ubx_payload_rx_ack_ack_t payload_rx_ack_ack
Definition: ubx.h:713
uint8_t cfgData
configuration data (key and value pairs, max 64)
Definition: ubx.h:618
uint8_t sec
Seconds of minute, range 0..60 (UTC)
Definition: ubx.h:372
uint8_t magQ
Magnitude of Q-part of complex signal (0=no signal, 255=max magnitude)
Definition: ubx.h:549
int32_t velN
NED north velocity [mm/s].
Definition: ubx.h:386
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:404
ubx_decode_state_t
Definition: ubx.h:730
ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5
Definition: ubx.h:717
int32_t fTOW
Fractional part of iTOW (range: +/-500000) [ns].
Definition: ubx.h:346
uint16_t reserved5
Definition: ubx.h:595
uint8_t svid
Satellite ID.
Definition: ubx.h:427
uint16_t year
Year (UTC)
Definition: ubx.h:367
uint16_t vDOP
Vertical DOP [0.01].
Definition: ubx.h:337
uint8_t svId
Satellite ID.
Definition: ubx.h:447
int8_t elev
Elevation [deg].
Definition: ubx.h:431
Definition: reflect.c:56
uint32_t baudRate
Definition: ubx.h:591
uint8_t chn
Channel number, 255 for SVs not assigned to a channel.
Definition: ubx.h:426
ubx_ack_state_t
Definition: ubx.h:753
uint8_t day
Day of month, range 1..31 (UTC)
Definition: ubx.h:409
int32_t velD
Down velocity component [cm/s].
Definition: ubx.h:480
uint8_t staticHoldThresh
Definition: ubx.h:638
int32_t lon
Longitude [1e-7 deg].
Definition: ubx.h:323
uint16_t noisePerMS
Noise level as measured by the GPS core.
Definition: ubx.h:543
int32_t hMSL
Height above mean sea level [mm].
Definition: ubx.h:383
Definition: ubx.h:696
uint16_t hDOP
Horizontal DOP [0.01].
Definition: ubx.h:338
uint32_t vAcc
Vertical accuracy estimate [mm].
Definition: ubx.h:385
ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt
Definition: ubx.h:715
ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate
Definition: ubx.h:716
uint16_t measRate
Measurement Rate, GPS measurements are taken every measRate milliseconds.
Definition: ubx.h:600
uint8_t numSV
Number of SVs used in Nav Solution.
Definition: ubx.h:360
int16_t azim
Azimuth [deg].
Definition: ubx.h:432
int16_t azim
Azimuth [deg] range: 0-360.
Definition: ubx.h:450
uint16_t nDOP
Northing DOP [0.01].
Definition: ubx.h:339
GPS driver base class with Base Station Support.
Definition: base_station.h:49
ubx_payload_rx_nav_svinfo_part1_t payload_rx_nav_svinfo_part1
Definition: ubx.h:702
int32_t headVeh
(ubx8+ only) Heading of vehicle (2-D) [1e-5 deg]
Definition: ubx.h:396
ubx_payload_tx_cfg_sbas_t payload_tx_cfg_sbas
Definition: ubx.h:719
int32_t lat
Latitude [1e-7 deg].
Definition: ubx.h:381
uint8_t version
Message version (1)
Definition: ubx.h:439
uint8_t numSV
Number of SVs used in Nav Solution.
Definition: ubx.h:379
uint16_t staticHoldMaxDist
(ubx8+ only, else 0)
Definition: ubx.h:643
uint16_t pDOP
Position DOP [0.01].
Definition: ubx.h:335
uint8_t fixType
GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning...
Definition: ubx.h:376
uint8_t month
Month, range 1..12 (UTC)
Definition: ubx.h:368
int32_t prRes
Pseudo range residual [cm].
Definition: ubx.h:433
uint32_t reserved3
Definition: ubx.h:395
uint8_t sync2
Definition: ubx.h:309
int32_t nano
Fraction of second (UTC) [-1e9...1e9 ns].
Definition: ubx.h:375
uint32_t iTOW
GPS Time of Week [ms].
Definition: ubx.h:418
int8_t ofsI
Imbalance of I-part of complex signal.
Definition: ubx.h:546
uint8_t flags
Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...)
Definition: ubx.h:377
int32_t headMot
Heading of motion (2-D) [1e-5 deg].
Definition: ubx.h:390
uint16_t length
Definition: ubx.h:311
uint16_t reserved2
Definition: ubx.h:394
uint8_t hour
Hour of day, range 0..23 (UTC)
Definition: ubx.h:410
uint8_t sync1
Definition: ubx.h:308
uint32_t scanmode1
Definition: ubx.h:662
ubx_payload_rx_ack_nak_t payload_rx_ack_nak
Definition: ubx.h:714
uint8_t cno
Carrier to Noise Ratio (Signal Strength) [dbHz].
Definition: ubx.h:430
uint8_t hour
Hour of day, range 0..23 (UTC)
Definition: ubx.h:370
int32_t hMSL
Height above mean sea level [mm].
Definition: ubx.h:326
uint8_t layers
The layers where the configuration should be applied (.
Definition: ubx.h:616
uint8_t deviceMask
Storage devices to apply this top.
Definition: ubx.h:610
ubx_payload_rx_nav_sat_part2_t payload_rx_nav_sat_part2
Definition: ubx.h:705
int32_t velE
East velocity component [cm/s].
Definition: ubx.h:479
uint32_t gSpeed
Ground speed (2-D) [cm/s].
Definition: ubx.h:482
ubx_payload_rx_nav_velned_t payload_rx_nav_velned
Definition: ubx.h:707
uint32_t headAcc
Heading accuracy estimate (motion and vehicle) [1e-5 deg].
Definition: ubx.h:392
uint8_t jamInd
CW jamming indicator, scaled (0=no CW jamming, 255=strong CW jamming)
Definition: ubx.h:545
ubx_payload_rx_nav_svin_t payload_rx_nav_svin
Definition: ubx.h:706
uint16_t pDOP
Position DOP [0.01].
Definition: ubx.h:358
int32_t heading
Heading of motion 2-D [1e-5 deg].
Definition: ubx.h:483