APM:Libraries
AP_GPS_UBLOX.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 //
17 // u-blox UBX GPS driver for ArduPilot and ArduPilotMega.
18 // Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
19 //
20 // UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
21 #pragma once
22 
23 #include <AP_HAL/AP_HAL.h>
24 
25 #include "AP_GPS.h"
26 #include "GPS_Backend.h"
27 
28 /*
29  * try to put a UBlox into binary mode. This is in two parts.
30  *
31  * First we send a ubx binary message that enables the NAV_SOL message
32  * at rate 1. Then we send a NMEA message to set the baud rate to our
33  * desired rate. The reason for doing the NMEA message second is if we
34  * send it first the second message will be ignored for a baud rate
35  * change.
36  * The reason we need the NAV_SOL rate message at all is some uBlox
37  * modules are configured with all ubx binary messages off, which
38  * would mean we would never detect it.
39  */
40 #define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n"
41 
42 #define UBLOX_RXM_RAW_LOGGING 1
43 #define UBLOX_MAX_RXM_RAW_SATS 22
44 #define UBLOX_MAX_RXM_RAWX_SATS 32
45 #define UBLOX_GNSS_SETTINGS 1
46 
47 #define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7
48 #define UBX_MSG_TYPES 2
49 
50 #define UBLOX_MAX_PORTS 6
51 
52 #define RATE_POSLLH 1
53 #define RATE_STATUS 1
54 #define RATE_SOL 1
55 #define RATE_PVT 1
56 #define RATE_VELNED 1
57 #define RATE_DOP 1
58 #define RATE_HW 5
59 #define RATE_HW2 5
60 
61 #define CONFIG_RATE_NAV (1<<0)
62 #define CONFIG_RATE_POSLLH (1<<1)
63 #define CONFIG_RATE_STATUS (1<<2)
64 #define CONFIG_RATE_SOL (1<<3)
65 #define CONFIG_RATE_VELNED (1<<4)
66 #define CONFIG_RATE_DOP (1<<5)
67 #define CONFIG_RATE_MON_HW (1<<6)
68 #define CONFIG_RATE_MON_HW2 (1<<7)
69 #define CONFIG_RATE_RAW (1<<8)
70 #define CONFIG_VERSION (1<<9)
71 #define CONFIG_NAV_SETTINGS (1<<10)
72 #define CONFIG_GNSS (1<<11)
73 #define CONFIG_SBAS (1<<12)
74 #define CONFIG_RATE_PVT (1<<13)
75 
76 #define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED)
77 
78 #define CONFIG_ALL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_SOL | CONFIG_RATE_VELNED \
79  | CONFIG_RATE_DOP | CONFIG_RATE_MON_HW | CONFIG_RATE_MON_HW2 | CONFIG_RATE_RAW | CONFIG_VERSION \
80  | CONFIG_NAV_SETTINGS | CONFIG_GNSS | CONFIG_SBAS)
81 
82 //Configuration Sub-Sections
83 #define SAVE_CFG_IO (1<<0)
84 #define SAVE_CFG_MSG (1<<1)
85 #define SAVE_CFG_INF (1<<2)
86 #define SAVE_CFG_NAV (1<<3)
87 #define SAVE_CFG_RXM (1<<4)
88 #define SAVE_CFG_RINV (1<<9)
89 #define SAVE_CFG_ANT (1<<10)
90 #define SAVE_CFG_ALL (SAVE_CFG_IO|SAVE_CFG_MSG|SAVE_CFG_INF|SAVE_CFG_NAV|SAVE_CFG_RXM|SAVE_CFG_RINV|SAVE_CFG_ANT)
91 
93 {
94 public:
96 
97  // Methods
98  bool read();
99 
101 
102  static bool _detect(struct UBLOX_detect_state &state, uint8_t data);
103 
104  bool is_configured(void) {
105 #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
106  if (!gps._auto_config) {
107  return true;
108  } else {
109  return !_unconfigured_messages;
110  }
111 #else
112  return true;
113 #endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
114  }
115 
116  void broadcast_configuration_failure_reason(void) const override;
117  void Write_DataFlash_Log_Startup_messages() const override;
118 
119  // get the velocity lag, returns true if the driver is confident in the returned value
120  bool get_lag(float &lag_sec) const override;
121 
122  const char *name() const override { return "u-blox"; }
123 
124 private:
125  // u-blox UBX protocol essentials
127  uint8_t preamble1;
128  uint8_t preamble2;
129  uint8_t msg_class;
130  uint8_t msg_id;
131  uint16_t length;
132  };
133 #if UBLOX_GNSS_SETTINGS
135  uint8_t msgVer;
136  uint8_t numTrkChHw;
137  uint8_t numTrkChUse;
140  uint8_t gnssId;
141  uint8_t resTrkCh;
142  uint8_t maxTrkCh;
143  uint8_t reserved1;
144  uint32_t flags;
146  };
147 #endif
149  uint16_t measure_rate_ms;
150  uint16_t nav_rate;
151  uint16_t timeref;
152  };
154  uint8_t msg_class;
155  uint8_t msg_id;
156  };
158  uint8_t msg_class;
159  uint8_t msg_id;
160  uint8_t rate;
161  };
163  uint8_t msg_class;
164  uint8_t msg_id;
165  uint8_t rates[6];
166  };
168  uint16_t mask;
169  uint8_t dynModel;
170  uint8_t fixMode;
171  int32_t fixedAlt;
172  uint32_t fixedAltVar;
173  int8_t minElev;
174  uint8_t drLimit;
175  uint16_t pDop;
176  uint16_t tDop;
177  uint16_t pAcc;
178  uint16_t tAcc;
180  uint8_t res1;
181  uint32_t res2;
182  uint32_t res3;
183  uint32_t res4;
184  };
186  uint8_t portID;
187  };
189  uint8_t mode;
190  uint8_t usage;
191  uint8_t maxSBAS;
192  uint8_t scanmode2;
193  uint32_t scanmode1;
194  };
196  uint32_t time; // GPS msToW
197  int32_t longitude;
198  int32_t latitude;
200  int32_t altitude_msl;
203  };
205  uint32_t time; // GPS msToW
206  uint8_t fix_type;
207  uint8_t fix_status;
209  uint8_t res;
211  uint32_t uptime; // milliseconds
212  };
214  uint32_t time; // GPS msToW
215  uint16_t gDOP;
216  uint16_t pDOP;
217  uint16_t tDOP;
218  uint16_t vDOP;
219  uint16_t hDOP;
220  uint16_t nDOP;
221  uint16_t eDOP;
222  };
224  uint32_t time;
225  int32_t time_nsec;
226  uint16_t week;
227  uint8_t fix_type;
228  uint8_t fix_status;
229  int32_t ecef_x;
230  int32_t ecef_y;
231  int32_t ecef_z;
236  uint32_t speed_accuracy;
237  uint16_t position_DOP;
238  uint8_t res;
239  uint8_t satellites;
240  uint32_t res2;
241  };
243  uint32_t itow;
244  uint16_t year;
245  uint8_t month, day, hour, min, sec;
246  uint8_t valid;
247  uint32_t t_acc;
248  int32_t nano;
249  uint8_t fix_type;
250  uint8_t flags;
251  uint8_t flags2;
252  uint8_t num_sv;
253  int32_t lon, lat;
254  int32_t height, h_msl;
255  uint32_t h_acc, v_acc;
256  int32_t velN, velE, velD, gspeed;
257  int32_t head_mot;
258  uint32_t s_acc;
259  uint32_t head_acc;
260  uint16_t p_dop;
261  uint8_t reserved1[6];
262  uint32_t headVeh;
263  uint8_t reserved2[4];
264  };
266  uint32_t time; // GPS msToW
267  int32_t ned_north;
268  int32_t ned_east;
269  int32_t ned_down;
270  uint32_t speed_3d;
271  uint32_t speed_2d;
272  int32_t heading_2d;
273  uint32_t speed_accuracy;
275  };
276 
277  // Lea6 uses a 60 byte message
279  uint32_t pinSel;
280  uint32_t pinBank;
281  uint32_t pinDir;
282  uint32_t pinVal;
283  uint16_t noisePerMS;
284  uint16_t agcCnt;
285  uint8_t aStatus;
286  uint8_t aPower;
287  uint8_t flags;
288  uint8_t reserved1;
289  uint32_t usedMask;
290  uint8_t VP[17];
291  uint8_t jamInd;
292  uint16_t reserved3;
293  uint32_t pinIrq;
294  uint32_t pullH;
295  uint32_t pullL;
296  };
297  // Neo7 uses a 68 byte message
299  uint32_t pinSel;
300  uint32_t pinBank;
301  uint32_t pinDir;
302  uint32_t pinVal;
303  uint16_t noisePerMS;
304  uint16_t agcCnt;
305  uint8_t aStatus;
306  uint8_t aPower;
307  uint8_t flags;
308  uint8_t reserved1;
309  uint32_t usedMask;
310  uint8_t VP[25];
311  uint8_t jamInd;
312  uint16_t reserved3;
313  uint32_t pinIrq;
314  uint32_t pullH;
315  uint32_t pullL;
316  };
318  int8_t ofsI;
319  uint8_t magI;
320  int8_t ofsQ;
321  uint8_t magQ;
322  uint8_t cfgSource;
323  uint8_t reserved0[3];
324  uint32_t lowLevCfg;
325  uint32_t reserved1[2];
326  uint32_t postStatus;
327  uint32_t reserved2;
328  };
330  char swVersion[30];
331  char hwVersion[10];
332  char extension; // extensions are not enabled
333  };
335  uint32_t itow;
336  uint8_t numCh;
337  uint8_t globalFlags;
338  uint16_t reserved;
339  };
340 #if UBLOX_RXM_RAW_LOGGING
342  int32_t iTOW;
343  int16_t week;
344  uint8_t numSV;
345  uint8_t reserved1;
346  struct ubx_rxm_raw_sv {
347  double cpMes;
348  double prMes;
349  float doMes;
350  uint8_t sv;
351  int8_t mesQI;
352  int8_t cno;
353  uint8_t lli;
354  } svinfo[UBLOX_MAX_RXM_RAW_SATS];
355  };
357  double rcvTow;
358  uint16_t week;
359  int8_t leapS;
360  uint8_t numMeas;
361  uint8_t recStat;
362  uint8_t reserved1[3];
364  double prMes;
365  double cpMes;
366  float doMes;
367  uint8_t gnssId;
368  uint8_t svId;
369  uint8_t reserved2;
370  uint8_t freqId;
371  uint16_t locktime;
372  uint8_t cno;
373  uint8_t prStdev;
374  uint8_t cpStdev;
375  uint8_t doStdev;
376  uint8_t trkStat;
377  uint8_t reserved3;
378  } svinfo[UBLOX_MAX_RXM_RAWX_SATS];
379  };
380 #endif
381 
383  uint8_t clsID;
384  uint8_t msgID;
385  };
386 
387 
389  uint32_t clearMask;
390  uint32_t saveMask;
391  uint32_t loadMask;
392  };
393 
394  // Receive buffer
395  union PACKED {
412 #if UBLOX_GNSS_SETTINGS
414 #endif
417 #if UBLOX_RXM_RAW_LOGGING
420 #endif
422  } _buffer;
423 
425  PREAMBLE1 = 0xb5,
426  PREAMBLE2 = 0x62,
427  CLASS_NAV = 0x01,
428  CLASS_ACK = 0x05,
429  CLASS_CFG = 0x06,
430  CLASS_MON = 0x0A,
431  CLASS_RXM = 0x02,
432  MSG_ACK_NACK = 0x00,
433  MSG_ACK_ACK = 0x01,
434  MSG_POSLLH = 0x2,
435  MSG_STATUS = 0x3,
436  MSG_DOP = 0x4,
437  MSG_SOL = 0x6,
438  MSG_PVT = 0x7,
439  MSG_VELNED = 0x12,
440  MSG_CFG_CFG = 0x09,
441  MSG_CFG_RATE = 0x08,
442  MSG_CFG_MSG = 0x01,
444  MSG_CFG_PRT = 0x00,
445  MSG_CFG_SBAS = 0x16,
446  MSG_CFG_GNSS = 0x3E,
447  MSG_MON_HW = 0x09,
448  MSG_MON_HW2 = 0x0B,
449  MSG_MON_VER = 0x04,
451  MSG_RXM_RAW = 0x10,
453  };
455  GNSS_GPS = 0x00,
456  GNSS_SBAS = 0x01,
457  GNSS_GALILEO = 0x02,
458  GNSS_BEIDOU = 0x03,
459  GNSS_IMES = 0x04,
460  GNSS_QZSS = 0x05,
462  };
464  FIX_NONE = 0,
466  FIX_2D = 2,
467  FIX_3D = 3,
470  };
474  };
476  ANTARIS = 0,
481  UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
482  // flagging state in the driver
483  };
484 
485  enum config_step {
486  STEP_PVT = 0,
487  STEP_NAV_RATE, // poll NAV rate
493  STEP_POLL_SVINFO, // poll svinfo
494  STEP_POLL_SBAS, // poll SBAS
495  STEP_POLL_NAV, // poll NAV settings
496  STEP_POLL_GNSS, // poll GNSS
504  };
505 
506  // Packet checksum accumulators
507  uint8_t _ck_a;
508  uint8_t _ck_b;
509 
510  // State machine state
511  uint8_t _step;
512  uint8_t _msg_id;
513  uint16_t _payload_length;
515 
516  uint8_t _class;
518 
519  uint32_t _last_vel_time;
520  uint32_t _last_pos_time;
524  uint16_t _delay_time;
525  uint8_t _next_message;
526  uint8_t _ublox_port;
531 
532 
533  // do we have new position information?
535  // do we have new speed information?
536  bool _new_speed:1;
537 
539 
540  // Buffer parse & GPS state update
541  bool _parse_gps();
542 
543  // used to update fix between status and position packets
545 
547 
549 
551 
552  bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
553  void _configure_rate(void);
554  void _configure_sbas(bool enable);
555  void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);
556  bool _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size);
557  void send_next_rate_update(void);
558  bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);
559  void _request_next_config(void);
560  void _request_port(void);
561  void _request_version(void);
562  void _save_cfg(void);
563  void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
564 
565  void unexpected_message(void);
566  void log_mon_hw(void);
567  void log_mon_hw2(void);
568  void log_rxm_raw(const struct ubx_rxm_raw &raw);
569  void log_rxm_rawx(const struct ubx_rxm_rawx &raw);
570 
571  // Calculates the correct log message ID based on what GPS instance is being logged
572  uint8_t _ubx_msg_log_index(uint8_t ubx_msg) {
573  return (uint8_t)(ubx_msg + (state.instance * UBX_MSG_TYPES));
574  }
575 };
ubx_cfg_msg_rate_6 msg_rate_6
Definition: AP_GPS_UBLOX.h:404
Definition: AP_GPS.h:48
AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
bool _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size)
void Write_DataFlash_Log_Startup_messages() const override
uint8_t _class
Definition: AP_GPS_UBLOX.h:516
void _save_cfg(void)
ubx_nav_velned velned
Definition: AP_GPS_UBLOX.h:402
#define UBLOX_MAX_GNSS_CONFIG_BLOCKS
Definition: AP_GPS_UBLOX.h:47
void _request_port(void)
#define DEFINE_BYTE_ARRAY_METHODS
Definition: AP_Common.h:58
uint8_t _msg_id
Definition: AP_GPS_UBLOX.h:512
uint8_t _ck_b
Definition: AP_GPS_UBLOX.h:508
ubx_rxm_rawx rxm_rawx
Definition: AP_GPS_UBLOX.h:419
void log_rxm_raw(const struct ubx_rxm_raw &raw)
uint32_t _last_pos_time
Definition: AP_GPS_UBLOX.h:520
void log_rxm_rawx(const struct ubx_rxm_rawx &raw)
uint32_t _last_config_time
Definition: AP_GPS_UBLOX.h:523
#define UBLOX_MAX_RXM_RAW_SATS
Definition: AP_GPS_UBLOX.h:43
uint32_t _last_cfg_sent_time
Definition: AP_GPS_UBLOX.h:521
void send_next_rate_update(void)
uint32_t _unconfigured_messages
Definition: AP_GPS_UBLOX.h:529
ubx_cfg_msg_rate msg_rate
Definition: AP_GPS_UBLOX.h:403
bool is_configured(void)
Definition: AP_GPS_UBLOX.h:104
uint16_t _payload_length
Definition: AP_GPS_UBLOX.h:513
bool _have_version
Definition: AP_GPS_UBLOX.h:527
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
bool _new_position
Definition: AP_GPS_UBLOX.h:534
#define UBX_MSG_TYPES
Definition: AP_GPS_UBLOX.h:48
void _configure_sbas(bool enable)
union AP_GPS_UBLOX::PACKED _buffer
uint8_t _step
Definition: AP_GPS_UBLOX.h:511
ubx_cfg_nav_rate nav_rate
Definition: AP_GPS_UBLOX.h:406
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
GPS_Status
GPS status codes.
Definition: AP_GPS.h:96
ubx_nav_status status
Definition: AP_GPS_UBLOX.h:398
void unexpected_message(void)
bool _request_message_rate(uint8_t msg_class, uint8_t msg_id)
uint8_t _disable_counter
Definition: AP_GPS_UBLOX.h:538
void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b)
DEFINE_BYTE_ARRAY_METHODS ubx_nav_posllh posllh
Definition: AP_GPS_UBLOX.h:397
void broadcast_configuration_failure_reason(void) const override
static bool _detect(struct UBLOX_detect_state &state, uint8_t data)
const char * name() const override
Definition: AP_GPS_UBLOX.h:122
void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
void log_mon_hw(void)
struct ubx_mon_ver _version
Definition: AP_GPS_UBLOX.h:528
void _request_next_config(void)
uint16_t _payload_counter
Definition: AP_GPS_UBLOX.h:514
void _configure_rate(void)
AP_GPS::GPS_Status highest_supported_status(void)
Definition: AP_GPS_UBLOX.h:100
void log_mon_hw2(void)
#define UBLOX_MAX_RXM_RAWX_SATS
Definition: AP_GPS_UBLOX.h:44
uint8_t _next_message
Definition: AP_GPS_UBLOX.h:525
bool get_lag(float &lag_sec) const override
ubx_cfg_nav_settings nav_settings
Definition: AP_GPS_UBLOX.h:405
uint8_t _ubx_msg_log_index(uint8_t ubx_msg)
Definition: AP_GPS_UBLOX.h:572
ubx_nav_svinfo_header svinfo_header
Definition: AP_GPS_UBLOX.h:416
AP_Int8 _auto_config
Definition: AP_GPS.h:435
uint16_t _delay_time
Definition: AP_GPS_UBLOX.h:524
uint8_t _hardware_generation
Definition: AP_GPS_UBLOX.h:530
uint8_t _ck_a
Definition: AP_GPS_UBLOX.h:507
bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
ubx_nav_solution solution
Definition: AP_GPS_UBLOX.h:400
bool noReceivedHdop
Definition: AP_GPS_UBLOX.h:548
uint32_t _last_vel_time
Definition: AP_GPS_UBLOX.h:519
AP_GPS::GPS_Status next_fix
Definition: AP_GPS_UBLOX.h:544
uint8_t _num_cfg_save_tries
Definition: AP_GPS_UBLOX.h:522
ubx_mon_hw_60 mon_hw_60
Definition: AP_GPS_UBLOX.h:408
uint8_t _ublox_port
Definition: AP_GPS_UBLOX.h:526
void _request_version(void)
ubx_mon_hw_68 mon_hw_68
Definition: AP_GPS_UBLOX.h:409
bool _cfg_needs_save
Definition: AP_GPS_UBLOX.h:546