APM:Libraries
AP_GPS_UBLOX.cpp
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 GPS driver for ArduPilot
18 // Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
19 // Substantially rewritten for new GPS driver structure by Andrew Tridgell
20 //
21 #include "AP_GPS.h"
22 #include "AP_GPS_UBLOX.h"
23 #include <AP_HAL/Util.h>
24 #include <DataFlash/DataFlash.h>
25 #include <GCS_MAVLink/GCS.h>
26 
27 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
28  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH
29  #define UBLOX_SPEED_CHANGE 1
30 #else
31  #define UBLOX_SPEED_CHANGE 0
32 #endif
33 
34 
35 #define UBLOX_DEBUGGING 0
36 #define UBLOX_FAKE_3DLOCK 0
37 
38 extern const AP_HAL::HAL& hal;
39 
40 #if UBLOX_DEBUGGING
41  # define Debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); hal.scheduler->delay(1); } while(0)
42 #else
43  # define Debug(fmt, args ...)
44 #endif
45 
47  AP_GPS_Backend(_gps, _state, _port),
48  _next_message(STEP_PVT),
49  _ublox_port(255),
50  _unconfigured_messages(CONFIG_ALL),
51  _hardware_generation(UBLOX_UNKNOWN_HARDWARE_GENERATION),
52  next_fix(AP_GPS::NO_FIX),
53  noReceivedHdop(true)
54 {
55  // stop any config strings that are pending
56  gps.send_blob_start(state.instance, nullptr, 0);
57 
58  // start the process of updating the GPS rates
60 }
61 
62 void
64 {
65  // don't request config if we shouldn't configure the GPS
67  return;
68  }
69 
70  // Ensure there is enough space for the largest possible outgoing message
71  if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_nav_rate)+2)) {
72  // not enough space - do it next time
73  return;
74  }
75 
76  Debug("Unconfigured messages: %d Current message: %d\n", _unconfigured_messages, _next_message);
77 
78  // check AP_GPS_UBLOX.h for the enum that controls the order.
79  // This switch statement isn't maintained against the enum in order to reduce code churn
80  switch (_next_message++) {
81  case STEP_PVT:
83  _next_message--;
84  }
85  break;
86  case STEP_PORT:
87  _request_port();
88  break;
89  case STEP_POLL_SVINFO:
90  // not required once we know what generation we are on
92  if (!_send_message(CLASS_NAV, MSG_NAV_SVINFO, 0, 0)) {
93  _next_message--;
94  }
95  }
96  break;
97  case STEP_POLL_SBAS:
98  if (gps._sbas_mode != 2) {
99  _send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0);
100  } else {
102  }
103  break;
104  case STEP_POLL_NAV:
105  if (!_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0)) {
106  _next_message--;
107  }
108  break;
109  case STEP_POLL_GNSS:
110  if (!_send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0)) {
111  _next_message--;
112  }
113  break;
114  case STEP_NAV_RATE:
115  if (!_send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0)) {
116  _next_message--;
117  }
118  break;
119  case STEP_POSLLH:
121  _next_message--;
122  }
123  break;
124  case STEP_STATUS:
126  _next_message--;
127  }
128  break;
129  case STEP_SOL:
131  _next_message--;
132  }
133  break;
134  case STEP_VELNED:
136  _next_message--;
137  }
138  break;
139  case STEP_DOP:
141  _next_message--;
142  }
143  break;
144  case STEP_MON_HW:
146  _next_message--;
147  }
148  break;
149  case STEP_MON_HW2:
151  _next_message--;
152  }
153  break;
154  case STEP_RAW:
155 #if UBLOX_RXM_RAW_LOGGING
156  if(gps._raw_data == 0) {
159  _next_message--;
160  }
161 #else
163 #endif
164  break;
165  case STEP_RAWX:
166 #if UBLOX_RXM_RAW_LOGGING
167  if(gps._raw_data == 0) {
170  _next_message--;
171  }
172 #else
174 #endif
175  break;
176  case STEP_VERSION:
177  if(!_have_version && !hal.util->get_soft_armed()) {
179  } else {
181  }
182  // no need to send the initial rates, move to checking only
184  break;
185  default:
186  // this case should never be reached, do a full reset if it is hit
188  break;
189  }
190 }
191 
192 void
193 AP_GPS_UBLOX::_verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) {
194  uint8_t desired_rate;
195 
196  switch(msg_class) {
197  case CLASS_NAV:
198  switch(msg_id) {
199  case MSG_POSLLH:
200  desired_rate = havePvtMsg ? 0 : RATE_POSLLH;
201  if(rate == desired_rate) {
203  } else {
204  _configure_message_rate(msg_class, msg_id, desired_rate);
206  _cfg_needs_save = true;
207  }
208  break;
209  case MSG_STATUS:
210  desired_rate = havePvtMsg ? 0 : RATE_STATUS;
211  if(rate == desired_rate) {
213  } else {
214  _configure_message_rate(msg_class, msg_id, desired_rate);
216  _cfg_needs_save = true;
217  }
218  break;
219  case MSG_SOL:
220  if(rate == RATE_SOL) {
222  } else {
223  _configure_message_rate(msg_class, msg_id, RATE_SOL);
225  _cfg_needs_save = true;
226  }
227  break;
228  case MSG_PVT:
229  if(rate == RATE_PVT) {
231  } else {
232  _configure_message_rate(msg_class, msg_id, RATE_PVT);
234  _cfg_needs_save = true;
235  }
236  break;
237  case MSG_VELNED:
238  desired_rate = havePvtMsg ? 0 : RATE_VELNED;
239  if(rate == desired_rate) {
241  } else {
242  _configure_message_rate(msg_class, msg_id, desired_rate);
244  _cfg_needs_save = true;
245  }
246  break;
247  case MSG_DOP:
248  if(rate == RATE_DOP) {
250  } else {
251  _configure_message_rate(msg_class, msg_id, RATE_DOP);
253  _cfg_needs_save = true;
254  }
255  break;
256  }
257  break;
258  case CLASS_MON:
259  switch(msg_id) {
260  case MSG_MON_HW:
261  if(rate == RATE_HW) {
263  } else {
264  _configure_message_rate(msg_class, msg_id, RATE_HW);
266  _cfg_needs_save = true;
267  }
268  break;
269  case MSG_MON_HW2:
270  if(rate == RATE_HW2) {
272  } else {
273  _configure_message_rate(msg_class, msg_id, RATE_HW2);
275  _cfg_needs_save = true;
276  }
277  break;
278  }
279  break;
280 #if UBLOX_RXM_RAW_LOGGING
281  case CLASS_RXM:
282  switch(msg_id) {
283  case MSG_RXM_RAW:
284  if(rate == gps._raw_data) {
286  } else {
287  _configure_message_rate(msg_class, msg_id, gps._raw_data);
289  _cfg_needs_save = true;
290  }
291  break;
292  case MSG_RXM_RAWX:
293  if(rate == gps._raw_data) {
295  } else {
296  _configure_message_rate(msg_class, msg_id, gps._raw_data);
298  _cfg_needs_save = true;
299  }
300  break;
301  }
302  break;
303 #endif // UBLOX_RXM_RAW_LOGGING
304  }
305 }
306 
307 // Requests the ublox driver to identify what port we are using to communicate
308 void
310 {
311  if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+2)) {
312  // not enough space - do it next time
313  return;
314  }
315  _send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0);
316 }
317  // Ensure there is enough space for the largest possible outgoing message
318 // Process bytes available from the stream
319 //
320 // The stream is assumed to contain only messages we recognise. If it
321 // contains other messages, and those messages contain the preamble
322 // bytes, it is possible for this code to fail to synchronise to the
323 // stream immediately. Without buffering the entire message and
324 // re-processing it from the top, this is unavoidable. The parser
325 // attempts to avoid this when possible.
326 //
327 bool
329 {
330  uint8_t data;
331  int16_t numc;
332  bool parsed = false;
333  uint32_t millis_now = AP_HAL::millis();
334 
335  // walk through the gps configuration at 1 message per second
336  if (millis_now - _last_config_time >= _delay_time) {
338  _last_config_time = millis_now;
339  if (_unconfigured_messages) { // send the updates faster until fully configured
341  _delay_time = 300;
342  } else {
343  _delay_time = 750;
344  }
345  } else {
346  _delay_time = 2000;
347  }
348  }
349 
351  _num_cfg_save_tries < 5 && (millis_now - _last_cfg_sent_time) > 5000 &&
352  !hal.util->get_soft_armed()) {
353  //save the configuration sent until now
354  if (gps._save_config == 1 ||
355  (gps._save_config == 2 && _cfg_needs_save)) {
356  _save_cfg();
357  }
358  }
359 
360  numc = port->available();
361  for (int16_t i = 0; i < numc; i++) { // Process bytes received
362 
363  // read the next byte
364  data = port->read();
365 
366  reset:
367  switch(_step) {
368 
369  // Message preamble detection
370  //
371  // If we fail to match any of the expected bytes, we reset
372  // the state machine and re-consider the failed byte as
373  // the first byte of the preamble. This improves our
374  // chances of recovering from a mismatch and makes it less
375  // likely that we will be fooled by the preamble appearing
376  // as data in some other message.
377  //
378  case 1:
379  if (PREAMBLE2 == data) {
380  _step++;
381  break;
382  }
383  _step = 0;
384  Debug("reset %u", __LINE__);
385  FALLTHROUGH;
386  case 0:
387  if(PREAMBLE1 == data)
388  _step++;
389  break;
390 
391  // Message header processing
392  //
393  // We sniff the class and message ID to decide whether we
394  // are going to gather the message bytes or just discard
395  // them.
396  //
397  // We always collect the length so that we can avoid being
398  // fooled by preamble bytes in messages.
399  //
400  case 2:
401  _step++;
402  _class = data;
403  _ck_b = _ck_a = data; // reset the checksum accumulators
404  break;
405  case 3:
406  _step++;
407  _ck_b += (_ck_a += data); // checksum byte
408  _msg_id = data;
409  break;
410  case 4:
411  _step++;
412  _ck_b += (_ck_a += data); // checksum byte
413  _payload_length = data; // payload length low byte
414  break;
415  case 5:
416  _step++;
417  _ck_b += (_ck_a += data); // checksum byte
418 
419  _payload_length += (uint16_t)(data<<8);
420  if (_payload_length > sizeof(_buffer)) {
421  Debug("large payload %u", (unsigned)_payload_length);
422  // assume any payload bigger then what we know about is noise
423  _payload_length = 0;
424  _step = 0;
425  goto reset;
426  }
427  _payload_counter = 0; // prepare to receive payload
428  break;
429 
430  // Receive message data
431  //
432  case 6:
433  _ck_b += (_ck_a += data); // checksum byte
434  if (_payload_counter < sizeof(_buffer)) {
435  _buffer[_payload_counter] = data;
436  }
438  _step++;
439  break;
440 
441  // Checksum and message processing
442  //
443  case 7:
444  _step++;
445  if (_ck_a != data) {
446  Debug("bad cka %x should be %x", data, _ck_a);
447  _step = 0;
448  goto reset;
449  }
450  break;
451  case 8:
452  _step = 0;
453  if (_ck_b != data) {
454  Debug("bad ckb %x should be %x", data, _ck_b);
455  break; // bad checksum
456  }
457 
458  if (_parse_gps()) {
459  parsed = true;
460  }
461  break;
462  }
463  }
464  return parsed;
465 }
466 
467 // Private Methods /////////////////////////////////////////////////////////////
469 {
470  if (!should_df_log()) {
471  return;
472  }
473  struct log_Ubx1 pkt = {
482  };
483  if (_payload_length == 68) {
488  }
489  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
490 }
491 
493 {
494  if (!should_df_log()) {
495  return;
496  }
497 
498  struct log_Ubx2 pkt = {
506  };
507  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
508 }
509 
510 #if UBLOX_RXM_RAW_LOGGING
511 void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
512 {
513  if (!should_df_log()) {
514  return;
515  }
516 
517  uint64_t now = AP_HAL::micros64();
518  for (uint8_t i=0; i<raw.numSV; i++) {
519  struct log_GPS_RAW pkt = {
521  time_us : now,
522  iTOW : raw.iTOW,
523  week : raw.week,
524  numSV : raw.numSV,
525  sv : raw.svinfo[i].sv,
526  cpMes : raw.svinfo[i].cpMes,
527  prMes : raw.svinfo[i].prMes,
528  doMes : raw.svinfo[i].doMes,
529  mesQI : raw.svinfo[i].mesQI,
530  cno : raw.svinfo[i].cno,
531  lli : raw.svinfo[i].lli
532  };
533  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
534  }
535 }
536 
538 {
539  if (!should_df_log()) {
540  return;
541  }
542 
543  uint64_t now = AP_HAL::micros64();
544 
545  struct log_GPS_RAWH header = {
547  time_us : now,
548  rcvTow : raw.rcvTow,
549  week : raw.week,
550  leapS : raw.leapS,
551  numMeas : raw.numMeas,
552  recStat : raw.recStat
553  };
554  DataFlash_Class::instance()->WriteBlock(&header, sizeof(header));
555 
556  for (uint8_t i=0; i<raw.numMeas; i++) {
557  struct log_GPS_RAWS pkt = {
559  time_us : now,
560  prMes : raw.svinfo[i].prMes,
561  cpMes : raw.svinfo[i].cpMes,
562  doMes : raw.svinfo[i].doMes,
563  gnssId : raw.svinfo[i].gnssId,
564  svId : raw.svinfo[i].svId,
565  freqId : raw.svinfo[i].freqId,
566  locktime : raw.svinfo[i].locktime,
567  cno : raw.svinfo[i].cno,
568  prStdev : raw.svinfo[i].prStdev,
569  cpStdev : raw.svinfo[i].cpStdev,
570  doStdev : raw.svinfo[i].doStdev,
571  trkStat : raw.svinfo[i].trkStat
572  };
573  DataFlash_Class::instance()->WriteBlock(&pkt, sizeof(pkt));
574  }
575 }
576 #endif // UBLOX_RXM_RAW_LOGGING
577 
579 {
580  Debug("Unexpected message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
581  if (++_disable_counter == 0) {
582  // disable future sends of this message id, but
583  // only do this every 256 messages, as some
584  // message types can't be disabled and we don't
585  // want to get into an ack war
586  Debug("Disabling message 0x%02x 0x%02x", (unsigned)_class, (unsigned)_msg_id);
587  _configure_message_rate(_class, _msg_id, 0);
588  }
589 }
590 
591 bool
593 {
594  if (_class == CLASS_ACK) {
595  Debug("ACK %u", (unsigned)_msg_id);
596 
597  if(_msg_id == MSG_ACK_ACK) {
598  switch(_buffer.ack.clsID) {
599  case CLASS_CFG:
600  switch(_buffer.ack.msgID) {
601  case MSG_CFG_CFG:
602  _cfg_saved = true;
603  _cfg_needs_save = false;
604  break;
605  case MSG_CFG_GNSS:
607  break;
608  case MSG_CFG_MSG:
609  // There is no way to know what MSG config was ack'ed, assume it was the last
610  // one requested. To verify it rerequest the last config we sent. If we miss
611  // the actual ack we will catch it next time through the poll loop, but that
612  // will be a good chunk of time later.
613  break;
616  break;
617  case MSG_CFG_RATE:
618  // The GPS will ACK a update rate that is invalid. in order to detect this
619  // only accept the rate as configured by reading the settings back and
620  // validating that they all match the target values
621  break;
622  case MSG_CFG_SBAS:
624  break;
625  }
626  break;
627  case CLASS_MON:
628  switch(_buffer.ack.msgID) {
629  case MSG_MON_HW:
631  break;
632  case MSG_MON_HW2:
634  break;
635  }
636  }
637  }
638  return false;
639  }
640 
641  if (_class == CLASS_CFG) {
642  switch(_msg_id) {
644  Debug("Got settings %u min_elev %d drLimit %u\n",
645  (unsigned)_buffer.nav_settings.dynModel,
647  (unsigned)_buffer.nav_settings.drLimit);
651  // we've received the current nav settings, change the engine
652  // settings and send them back
653  Debug("Changing engine setting from %u to %u\n",
654  (unsigned)_buffer.nav_settings.dynModel, (unsigned)gps._navfilter);
657  }
658  if (gps._min_elevation != -100 &&
660  Debug("Changing min elevation to %d\n", (int)gps._min_elevation);
663  }
664  if (_buffer.nav_settings.mask != 0) {
667  sizeof(_buffer.nav_settings));
669  _cfg_needs_save = true;
670  } else {
672  }
673  return false;
674 
675 #if UBLOX_GNSS_SETTINGS
676  case MSG_CFG_GNSS:
677  if (gps._gnss_mode[state.instance] != 0) {
678  struct ubx_cfg_gnss start_gnss = _buffer.gnss;
679  uint8_t gnssCount = 0;
680  Debug("Got GNSS Settings %u %u %u %u:\n",
681  (unsigned)_buffer.gnss.msgVer,
682  (unsigned)_buffer.gnss.numTrkChHw,
683  (unsigned)_buffer.gnss.numTrkChUse,
684  (unsigned)_buffer.gnss.numConfigBlocks);
685 #if UBLOX_DEBUGGING
686  for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
687  Debug(" %u %u %u 0x%08x\n",
688  (unsigned)_buffer.gnss.configBlock[i].gnssId,
689  (unsigned)_buffer.gnss.configBlock[i].resTrkCh,
690  (unsigned)_buffer.gnss.configBlock[i].maxTrkCh,
691  (unsigned)_buffer.gnss.configBlock[i].flags);
692  }
693 #endif
694 
695  for(int i = 0; i < UBLOX_MAX_GNSS_CONFIG_BLOCKS; i++) {
696  if((gps._gnss_mode[state.instance] & (1 << i)) && i != GNSS_SBAS) {
697  gnssCount++;
698  }
699  }
700 
701  for(int i = 0; i < _buffer.gnss.numConfigBlocks; i++) {
702  // Reserve an equal portion of channels for all enabled systems
703  if(gps._gnss_mode[state.instance] & (1 << _buffer.gnss.configBlock[i].gnssId)) {
704  if(GNSS_SBAS !=_buffer.gnss.configBlock[i].gnssId) {
705  _buffer.gnss.configBlock[i].resTrkCh = (_buffer.gnss.numTrkChHw - 3) / (gnssCount * 2);
707  } else {
708  _buffer.gnss.configBlock[i].resTrkCh = 1;
709  _buffer.gnss.configBlock[i].maxTrkCh = 3;
710  }
711  _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags | 0x00000001;
712  } else {
713  _buffer.gnss.configBlock[i].resTrkCh = 0;
714  _buffer.gnss.configBlock[i].maxTrkCh = 0;
715  _buffer.gnss.configBlock[i].flags = _buffer.gnss.configBlock[i].flags & 0xFFFFFFFE;
716  }
717  }
718  if (!memcmp(&start_gnss, &_buffer.gnss, sizeof(start_gnss))) {
721  _cfg_needs_save = true;
722  } else {
724  }
725  } else {
727  }
728  return false;
729 #endif
730 
731  case MSG_CFG_SBAS:
732  if (gps._sbas_mode != 2) {
733  Debug("Got SBAS settings %u %u %u 0x%x 0x%x\n",
734  (unsigned)_buffer.sbas.mode,
735  (unsigned)_buffer.sbas.usage,
736  (unsigned)_buffer.sbas.maxSBAS,
737  (unsigned)_buffer.sbas.scanmode2,
738  (unsigned)_buffer.sbas.scanmode1);
739  if (_buffer.sbas.mode != gps._sbas_mode) {
742  &_buffer.sbas,
743  sizeof(_buffer.sbas));
745  _cfg_needs_save = true;
746  } else {
748  }
749  } else {
751  }
752  return false;
753  case MSG_CFG_MSG:
754  if(_payload_length == sizeof(ubx_cfg_msg_rate_6)) {
755  // can't verify the setting without knowing the port
756  // request the port again
758  _request_port();
759  return false;
760  }
763  } else {
766  }
767  return false;
768  case MSG_CFG_PRT:
770  return false;
771  case MSG_CFG_RATE:
773  _buffer.nav_rate.nav_rate != 1 ||
774  _buffer.nav_rate.timeref != 0) {
775  _configure_rate();
777  _cfg_needs_save = true;
778  } else {
780  }
781  return false;
782  }
783 
784  }
785 
786  if (_class == CLASS_MON) {
787  switch(_msg_id) {
788  case MSG_MON_HW:
789  if (_payload_length == 60 || _payload_length == 68) {
790  log_mon_hw();
791  }
792  break;
793  case MSG_MON_HW2:
794  if (_payload_length == 28) {
795  log_mon_hw2();
796  }
797  break;
798  case MSG_MON_VER:
799  _have_version = true;
802  gcs().send_text(MAV_SEVERITY_INFO,
803  "u-blox %d HW: %s SW: %s",
804  state.instance + 1,
807  break;
808  default:
810  }
811  return false;
812  }
813 
814 #if UBLOX_RXM_RAW_LOGGING
815  if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAW && gps._raw_data != 0) {
817  return false;
818  } else if (_class == CLASS_RXM && _msg_id == MSG_RXM_RAWX && gps._raw_data != 0) {
820  return false;
821  }
822 #endif // UBLOX_RXM_RAW_LOGGING
823 
824  if (_class != CLASS_NAV) {
826  return false;
827  }
828 
829  switch (_msg_id) {
830  case MSG_POSLLH:
831  Debug("MSG_POSLLH next_fix=%u", next_fix);
832  if (havePvtMsg) {
834  break;
835  }
841  _new_position = true;
846 #if UBLOX_FAKE_3DLOCK
847  state.location.lng = 1491652300L;
848  state.location.lat = -353632610L;
849  state.location.alt = 58400;
852 #endif
853  break;
854  case MSG_STATUS:
855  Debug("MSG_STATUS fix_status=%u fix_type=%u",
858  if (havePvtMsg) {
860  break;
861  }
870  }else{
873  }
874  }else{
877  }
878 #if UBLOX_FAKE_3DLOCK
881 #endif
882  break;
883  case MSG_DOP:
884  Debug("MSG_DOP");
885  noReceivedHdop = false;
888 #if UBLOX_FAKE_3DLOCK
889  state.hdop = 130;
890  state.hdop = 170;
891 #endif
892  break;
893  case MSG_SOL:
894  Debug("MSG_SOL fix_status=%u fix_type=%u",
897  if (havePvtMsg) {
899  break;
900  }
909  }else{
912  }
913  }else{
916  }
917  if(noReceivedHdop) {
919  }
925  }
926 #if UBLOX_FAKE_3DLOCK
928  state.num_sats = 10;
929  state.time_week = 1721;
930  state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
932  state.hdop = 130;
933 #endif
934  break;
935  case MSG_PVT:
936  Debug("MSG_PVT");
937  havePvtMsg = true;
938  // position
943  switch (_buffer.pvt.fix_type)
944  {
945  case 0:
947  break;
948  case 1:
950  break;
951  case 2:
953  break;
954  case 3:
956  if (_buffer.pvt.flags & 0b00000010) // diffsoln
958  if (_buffer.pvt.flags & 0b01000000) // carrsoln - float
960  if (_buffer.pvt.flags & 0b10000000) // carrsoln - fixed
962  break;
963  case 4:
964  gcs().send_text(MAV_SEVERITY_INFO,
965  "Unexpected state %d", _buffer.pvt.flags);
967  break;
968  case 5:
970  break;
971  default:
973  break;
974  }
976  _new_position = true;
981  // SVs
983  // velocity
985  state.ground_speed = _buffer.pvt.gspeed*0.001f; // m/s
986  state.ground_course = wrap_360(_buffer.pvt.head_mot * 1.0e-5f); // Heading 2D deg * 100000
988  state.velocity.x = _buffer.pvt.velN * 0.001f;
989  state.velocity.y = _buffer.pvt.velE * 0.001f;
990  state.velocity.z = _buffer.pvt.velD * 0.001f;
991  state.have_speed_accuracy = true;
993  _new_speed = true;
994  // dop
995  if(noReceivedHdop) {
998  }
999 
1001 
1002  // time
1004 #if UBLOX_FAKE_3DLOCK
1005  state.location.lng = 1491652300L;
1006  state.location.lat = -353632610L;
1007  state.location.alt = 58400;
1011  state.num_sats = 10;
1012  state.time_week = 1721;
1013  state.time_week_ms = AP_HAL::millis() + 3*60*60*1000 + 37000;
1015  state.hdop = 130;
1016  next_fix = state.status;
1017 #endif
1018  break;
1019  case MSG_VELNED:
1020  Debug("MSG_VELNED");
1021  if (havePvtMsg) {
1023  break;
1024  }
1026  state.ground_speed = _buffer.velned.speed_2d*0.01f; // m/s
1027  state.ground_course = wrap_360(_buffer.velned.heading_2d * 1.0e-5f); // Heading 2D deg * 100000
1029  state.velocity.x = _buffer.velned.ned_north * 0.01f;
1030  state.velocity.y = _buffer.velned.ned_east * 0.01f;
1031  state.velocity.z = _buffer.velned.ned_down * 0.01f;
1034  state.have_speed_accuracy = true;
1036 #if UBLOX_FAKE_3DLOCK
1037  state.speed_accuracy = 0;
1038 #endif
1039  _new_speed = true;
1040  break;
1041  case MSG_NAV_SVINFO:
1042  {
1043  Debug("MSG_NAV_SVINFO\n");
1044  static const uint8_t HardwareGenerationMask = 0x07;
1045  _hardware_generation = _buffer.svinfo_header.globalFlags & HardwareGenerationMask;
1046  switch (_hardware_generation) {
1047  case UBLOX_5:
1048  case UBLOX_6:
1049  // only 7 and newer support CONFIG_GNSS
1051  break;
1052  case UBLOX_7:
1053  case UBLOX_M8:
1054 #if UBLOX_SPEED_CHANGE
1055  port->begin(4000000U);
1056  Debug("Changed speed to 4Mhz for SPI-driven UBlox\n");
1057 #endif
1058  break;
1059  default:
1060  hal.console->printf("Wrong Ublox Hardware Version%u\n", _hardware_generation);
1061  break;
1062  };
1064  /* We don't need that anymore */
1066  break;
1067  }
1068  default:
1069  Debug("Unexpected NAV message 0x%02x", (unsigned)_msg_id);
1070  if (++_disable_counter == 0) {
1071  Debug("Disabling NAV message 0x%02x", (unsigned)_msg_id);
1072  _configure_message_rate(CLASS_NAV, _msg_id, 0);
1073  }
1074  return false;
1075  }
1076 
1077  // we only return true when we get new position and speed data
1078  // this ensures we don't use stale data
1080  _new_speed = _new_position = false;
1081  return true;
1082  }
1083  return false;
1084 }
1085 
1086 
1087 // UBlox auto configuration
1088 
1089 /*
1090  * update checksum for a set of bytes
1091  */
1092 void
1093 AP_GPS_UBLOX::_update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b)
1094 {
1095  while (len--) {
1096  ck_a += *data;
1097  ck_b += ck_a;
1098  data++;
1099  }
1100 }
1101 
1102 
1103 /*
1104  * send a ublox message
1105  */
1106 bool
1107 AP_GPS_UBLOX::_send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size)
1108 {
1109  if (port->txspace() < (sizeof(struct ubx_header) + 2 + size)) {
1110  return false;
1111  }
1112  struct ubx_header header;
1113  uint8_t ck_a=0, ck_b=0;
1114  header.preamble1 = PREAMBLE1;
1115  header.preamble2 = PREAMBLE2;
1116  header.msg_class = msg_class;
1117  header.msg_id = msg_id;
1118  header.length = size;
1119 
1120  _update_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b);
1121  _update_checksum((uint8_t *)msg, size, ck_a, ck_b);
1122 
1123  port->write((const uint8_t *)&header, sizeof(header));
1124  port->write((const uint8_t *)msg, size);
1125  port->write((const uint8_t *)&ck_a, 1);
1126  port->write((const uint8_t *)&ck_b, 1);
1127  return true;
1128 }
1129 
1130 /*
1131  * requests the given message rate for a specific message class
1132  * and msg_id
1133  * returns true if it sent the request, false if waiting on knowing the port
1134  */
1135 bool
1136 AP_GPS_UBLOX::_request_message_rate(uint8_t msg_class, uint8_t msg_id)
1137 {
1138  // Without knowing what communication port is being used it isn't possible to verify
1139  // always ensure we have a port before sending the request
1140  if(_ublox_port >= UBLOX_MAX_PORTS) {
1141  _request_port();
1142  return false;
1143  } else {
1144  struct ubx_cfg_msg msg;
1145  msg.msg_class = msg_class;
1146  msg.msg_id = msg_id;
1147  return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
1148  }
1149 }
1150 
1151 /*
1152  * configure a UBlox GPS for the given message rate for a specific
1153  * message class and msg_id
1154  */
1155 bool
1156 AP_GPS_UBLOX::_configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
1157 {
1158  if (port->txspace() < (int16_t)(sizeof(struct ubx_header)+sizeof(struct ubx_cfg_msg_rate)+2)) {
1159  return false;
1160  }
1161 
1162  struct ubx_cfg_msg_rate msg;
1163  msg.msg_class = msg_class;
1164  msg.msg_id = msg_id;
1165  msg.rate = rate;
1166  return _send_message(CLASS_CFG, MSG_CFG_MSG, &msg, sizeof(msg));
1167 }
1168 
1169 /*
1170  * save gps configurations to non-volatile memory sent until the call of
1171  * this message
1172  */
1173 void
1175 {
1176  ubx_cfg_cfg save_cfg;
1177  save_cfg.clearMask = 0;
1178  save_cfg.saveMask = SAVE_CFG_ALL;
1179  save_cfg.loadMask = 0;
1180  _send_message(CLASS_CFG, MSG_CFG_CFG, &save_cfg, sizeof(save_cfg));
1183  gcs().send_text(MAV_SEVERITY_INFO,
1184  "GPS: u-blox %d saving config",
1185  state.instance + 1);
1186 }
1187 
1188 /*
1189  detect a Ublox GPS. Adds one byte, and returns true if the stream
1190  matches a UBlox
1191  */
1192 bool
1194 {
1195 reset:
1196  switch (state.step) {
1197  case 1:
1198  if (PREAMBLE2 == data) {
1199  state.step++;
1200  break;
1201  }
1202  state.step = 0;
1203  FALLTHROUGH;
1204  case 0:
1205  if (PREAMBLE1 == data)
1206  state.step++;
1207  break;
1208  case 2:
1209  state.step++;
1210  state.ck_b = state.ck_a = data;
1211  break;
1212  case 3:
1213  state.step++;
1214  state.ck_b += (state.ck_a += data);
1215  break;
1216  case 4:
1217  state.step++;
1218  state.ck_b += (state.ck_a += data);
1219  state.payload_length = data;
1220  break;
1221  case 5:
1222  state.step++;
1223  state.ck_b += (state.ck_a += data);
1224  state.payload_counter = 0;
1225  break;
1226  case 6:
1227  state.ck_b += (state.ck_a += data);
1228  if (++state.payload_counter == state.payload_length)
1229  state.step++;
1230  break;
1231  case 7:
1232  state.step++;
1233  if (state.ck_a != data) {
1234  state.step = 0;
1235  goto reset;
1236  }
1237  break;
1238  case 8:
1239  state.step = 0;
1240  if (state.ck_b == data) {
1241  // a valid UBlox packet
1242  return true;
1243  } else {
1244  goto reset;
1245  }
1246  }
1247  return false;
1248 }
1249 
1250 void
1252 {
1253  _send_message(CLASS_MON, MSG_MON_VER, nullptr, 0);
1254 }
1255 
1256 void
1258 {
1259  struct ubx_cfg_nav_rate msg;
1260  // require a minimum measurement rate of 5Hz
1262  msg.nav_rate = 1;
1263  msg.timeref = 0; // UTC time
1264  _send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));
1265 }
1266 
1267 static const char *reasons[] = {"navigation rate",
1268  "posllh rate",
1269  "status rate",
1270  "solution rate",
1271  "velned rate",
1272  "dop rate",
1273  "hw monitor rate",
1274  "hw2 monitor rate",
1275  "raw rate",
1276  "version",
1277  "navigation settings",
1278  "GNSS settings",
1279  "SBAS settings",
1280  "PVT rate"};
1281 
1282 
1283 void
1285  for (uint8_t i = 0; i < ARRAY_SIZE(reasons); i++) {
1286  if (_unconfigured_messages & (1 << i)) {
1287  gcs().send_text(MAV_SEVERITY_INFO, "GPS %d: u-blox %s configuration 0x%02x",
1289  break;
1290  }
1291  }
1292 }
1293 
1294 /*
1295  return velocity lag in seconds
1296  */
1297 bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
1298 {
1299  switch (_hardware_generation) {
1301  lag_sec = 0.22f;
1302  // always bail out in this case, it's used to indicate we have yet to receive a valid
1303  // hardware generation, however the user may have inhibited us detecting the generation
1304  // so if we aren't allowed to do configuration, we will accept this as the default delay
1306  case UBLOX_5:
1307  case UBLOX_6:
1308  default:
1309  lag_sec = 0.22f;
1310  break;
1311  case UBLOX_7:
1312  case UBLOX_M8:
1313  // based on flight logs the 7 and 8 series seem to produce about 120ms lag
1314  lag_sec = 0.12f;
1315  break;
1316  };
1317  return true;
1318 }
1319 
1321 {
1323 
1324  if (_have_version) {
1325  DataFlash_Class::instance()->Log_Write_MessageF("u-blox %d HW: %s SW: %s",
1326  state.instance+1,
1329  }
1330 }
ubx_cfg_msg_rate_6 msg_rate_6
Definition: AP_GPS_UBLOX.h:404
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
bool get_soft_armed() const
Definition: Util.h:15
Definition: AP_GPS.h:48
#define CONFIG_RATE_RAW
Definition: AP_GPS_UBLOX.h:69
uint32_t time_week_ms
GPS time (milliseconds from start of GPS week)
Definition: AP_GPS.h:133
void Log_Write_MessageF(const char *fmt,...)
Definition: DataFlash.cpp:391
void send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
Definition: AP_GPS.cpp:371
#define CONFIG_RATE_STATUS
Definition: AP_GPS_UBLOX.h:63
PACKED struct AP_GPS_UBLOX::ubx_cfg_gnss::configBlock configBlock[UBLOX_MAX_GNSS_CONFIG_BLOCKS]
#define Debug(fmt, args ...)
AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
uint32_t config
Definition: LogStructure.h:757
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
bool _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size)
uint8_t doStdev
Definition: LogStructure.h:808
void Write_DataFlash_Log_Startup_messages() const override
uint64_t time_us
Definition: LogStructure.h:787
#define RATE_STATUS
Definition: AP_GPS_UBLOX.h:53
int8_t ofsQ
Definition: LogStructure.h:766
#define CONFIG_RATE_VELNED
Definition: AP_GPS_UBLOX.h:65
#define UBLOX_MAX_PORTS
Definition: AP_GPS_UBLOX.h:50
uint8_t _class
Definition: AP_GPS_UBLOX.h:516
void _save_cfg(void)
#define RATE_DOP
Definition: AP_GPS_UBLOX.h:57
ubx_nav_velned velned
Definition: AP_GPS_UBLOX.h:402
uint8_t instance
Definition: AP_GPS.h:129
uint64_t time_us
Definition: LogStructure.h:797
#define FALLTHROUGH
Definition: AP_Common.h:50
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual void begin(uint32_t baud)=0
uint8_t magQ
Definition: LogStructure.h:767
#define UBLOX_MAX_GNSS_CONFIG_BLOCKS
Definition: AP_GPS_UBLOX.h:47
#define CONFIG_RATE_DOP
Definition: AP_GPS_UBLOX.h:66
uint8_t prStdev
Definition: LogStructure.h:806
void _request_port(void)
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
PACKED struct AP_GPS_UBLOX::ubx_rxm_rawx::ubx_rxm_rawx_sv svinfo[UBLOX_MAX_RXM_RAWX_SATS]
AP_Int8 _min_elevation
Definition: AP_GPS.h:430
uint8_t _msg_id
Definition: AP_GPS_UBLOX.h:512
Interface definition for the various Ground Control System.
bool have_vertical_velocity
does GPS give vertical velocity? Set to true only once available.
Definition: AP_GPS.h:145
Vector3f velocity
3D velocity in m/s, in NED format
Definition: AP_GPS.h:141
double cpMes
Definition: LogStructure.h:777
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
void reset()
AP_HAL::Util * util
Definition: HAL.h:115
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
virtual uint32_t txspace()=0
#define RATE_HW2
Definition: AP_GPS_UBLOX.h:59
int8_t mesQI
Definition: LogStructure.h:780
AP_Int8 _navfilter
Definition: AP_GPS.h:423
GCS & gcs()
uint32_t _last_cfg_sent_time
Definition: AP_GPS_UBLOX.h:521
static const char * reasons[]
uint32_t _unconfigured_messages
Definition: AP_GPS_UBLOX.h:529
ubx_cfg_msg_rate msg_rate
Definition: AP_GPS_UBLOX.h:403
#define CONFIG_NAV_SETTINGS
Definition: AP_GPS_UBLOX.h:71
uint16_t _payload_length
Definition: AP_GPS_UBLOX.h:513
#define RATE_HW
Definition: AP_GPS_UBLOX.h:58
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define CONFIG_RATE_SOL
Definition: AP_GPS_UBLOX.h:64
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
int8_t ofsI
Definition: LogStructure.h:764
uint16_t locktime
Definition: LogStructure.h:804
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
#define CONFIG_RATE_POSLLH
Definition: AP_GPS_UBLOX.h:62
AP_GPS & gps
access to frontend (for parameters)
Definition: GPS_Backend.h:70
#define RATE_POSLLH
Definition: AP_GPS_UBLOX.h:52
#define CONFIG_GNSS
Definition: AP_GPS_UBLOX.h:72
uint8_t aPower
Definition: LogStructure.h:755
uint64_t time_us
Definition: LogStructure.h:751
ubx_nav_status status
Definition: AP_GPS_UBLOX.h:398
uint8_t magI
Definition: LogStructure.h:765
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
#define CONFIG_RATE_MON_HW2
Definition: AP_GPS_UBLOX.h:68
#define CONFIG_VERSION
Definition: AP_GPS_UBLOX.h:70
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
AP_Int8 _sbas_mode
Definition: AP_GPS.h:429
void unexpected_message(void)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
uint16_t noisePerMS
Definition: LogStructure.h:753
uint8_t lli
Definition: LogStructure.h:782
#define f(i)
bool _request_message_rate(uint8_t msg_class, uint8_t msg_id)
uint8_t _disable_counter
Definition: AP_GPS_UBLOX.h:538
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
#define RATE_PVT
Definition: AP_GPS_UBLOX.h:55
#define RATE_SOL
Definition: AP_GPS_UBLOX.h:54
T y
Definition: vector3.h:67
virtual size_t write(uint8_t)=0
uint32_t millis()
Definition: system.cpp:157
uint8_t svId
Definition: LogStructure.h:802
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
uint8_t recStat
Definition: LogStructure.h:792
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
void broadcast_configuration_failure_reason(void) const override
uint64_t micros64()
Definition: system.cpp:162
static bool _detect(struct UBLOX_detect_state &state, uint8_t data)
#define RATE_VELNED
Definition: AP_GPS_UBLOX.h:56
void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
AP_Int16 _rate_ms[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:433
uint16_t time_week
GPS week number.
Definition: AP_GPS.h:134
Receiving valid messages and 2D lock.
Definition: AP_GPS.h:99
uint8_t numMeas
Definition: LogStructure.h:791
uint16_t week
Definition: LogStructure.h:789
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
void log_mon_hw(void)
virtual int16_t read()=0
uint64_t time_us
Definition: LogStructure.h:772
struct ubx_mon_ver _version
Definition: AP_GPS_UBLOX.h:528
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
bool should_df_log() const
uint8_t jamInd
Definition: LogStructure.h:754
void _request_next_config(void)
AP_Int8 _save_config
Definition: AP_GPS.h:434
uint64_t time_us
Definition: LogStructure.h:762
uint16_t _payload_counter
Definition: AP_GPS_UBLOX.h:514
void _configure_rate(void)
uint8_t instance
Definition: LogStructure.h:752
uint16_t vdop
vertical dilution of precision in cm
Definition: AP_GPS.h:139
virtual uint32_t available()=0
void log_mon_hw2(void)
Location location
last fix location
Definition: AP_GPS.h:135
int16_t week
Definition: LogStructure.h:774
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
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
AP_Int8 _gnss_mode[GPS_MAX_RECEIVERS]
Definition: AP_GPS.h:432
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
#define CONFIG_RATE_NAV
Definition: AP_GPS_UBLOX.h:61
AP_Int8 _raw_data
Definition: AP_GPS.h:431
ubx_nav_svinfo_header svinfo_header
Definition: AP_GPS_UBLOX.h:416
AP_Int8 _auto_config
Definition: AP_GPS.h:435
uint16_t agcCnt
Definition: LogStructure.h:756
uint16_t _delay_time
Definition: AP_GPS_UBLOX.h:524
int32_t iTOW
Definition: LogStructure.h:773
uint8_t freqId
Definition: LogStructure.h:803
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool have_vertical_accuracy
does GPS give vertical position accuracy? Set to true only once available.
Definition: AP_GPS.h:148
float speed_accuracy
3D velocity RMS accuracy estimate in m/s
Definition: AP_GPS.h:142
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
double prMes
Definition: LogStructure.h:778
uint8_t _hardware_generation
Definition: AP_GPS_UBLOX.h:530
uint8_t numSV
Definition: LogStructure.h:775
uint8_t instance
Definition: LogStructure.h:763
uint8_t _ck_a
Definition: AP_GPS_UBLOX.h:507
bool have_horizontal_accuracy
does GPS give horizontal position accuracy? Set to true only once available.
Definition: AP_GPS.h:147
float horizontal_accuracy
horizontal RMS accuracy estimate in m
Definition: AP_GPS.h:143
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate)
#define SAVE_CFG_ALL
Definition: AP_GPS_UBLOX.h:90
virtual void Write_DataFlash_Log_Startup_messages() const
ubx_nav_solution solution
Definition: AP_GPS_UBLOX.h:400
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
#define CONFIG_REQUIRED_INITIAL
Definition: AP_GPS_UBLOX.h:76
#define degrees(x)
Definition: moduletest.c:23
float vertical_accuracy
vertical RMS accuracy estimate in m
Definition: AP_GPS.h:144
uint16_t get_rate_ms(uint8_t instance) const
Definition: AP_GPS.cpp:1153
#define CONFIG_RATE_PVT
Definition: AP_GPS_UBLOX.h:74
#define CONFIG_ALL
Definition: AP_GPS_UBLOX.h:78
uint8_t cpStdev
Definition: LogStructure.h:807
uint8_t sv
Definition: LogStructure.h:776
bool noReceivedHdop
Definition: AP_GPS_UBLOX.h:548
uint32_t _last_vel_time
Definition: AP_GPS_UBLOX.h:519
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
AP_GPS::GPS_Status next_fix
Definition: AP_GPS_UBLOX.h:544
struct AP_GPS_UBLOX::ubx_rxm_raw::ubx_rxm_raw_sv svinfo[UBLOX_MAX_RXM_RAW_SATS]
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
#define CONFIG_RATE_MON_HW
Definition: AP_GPS_UBLOX.h:67
#define CONFIG_SBAS
Definition: AP_GPS_UBLOX.h:73
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
T x
Definition: vector3.h:67
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
bool _cfg_needs_save
Definition: AP_GPS_UBLOX.h:546
bool have_speed_accuracy
does GPS give speed accuracy? Set to true only once available.
Definition: AP_GPS.h:146
float ground_course
ground course in degrees
Definition: AP_GPS.h:137
uint8_t trkStat
Definition: LogStructure.h:809
uint8_t gnssId
Definition: LogStructure.h:801