gps.cpp
Go to the documentation of this file.
1 //==============================================================================
2 // Copyright (c) 2012, Johannes Meyer, TU Darmstadt
3 // 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 are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND
19 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
20 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
22 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
25 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 //==============================================================================
29 
30 #include <ublox_gps/gps.h>
31 #include <boost/version.hpp>
32 
33 namespace ublox_gps {
34 
35 using namespace ublox_msgs;
36 
38 constexpr static int kSetBaudrateSleepMs = 500;
39 
40 const boost::posix_time::time_duration Gps::default_timeout_ =
41  boost::posix_time::milliseconds(
42  static_cast<int>(Gps::kDefaultAckTimeout * 1000));
43 
44 Gps::Gps() : configured_(false), config_on_startup_flag_(true) {
45  subscribeAcks();
46 }
47 
48 Gps::~Gps() { close(); }
49 
51  if (worker_) return;
52  worker_ = worker;
53  worker_->setCallback(boost::bind(&CallbackHandlers::readCallback,
54  &callbacks_, _1, _2));
55  configured_ = static_cast<bool>(worker);
56 }
57 
59  // Set NACK handler
60  subscribeId<ublox_msgs::Ack>(boost::bind(&Gps::processNack, this, _1),
62  // Set ACK handler
63  subscribeId<ublox_msgs::Ack>(boost::bind(&Gps::processAck, this, _1),
65  // Set UPD-SOS-ACK handler
66  subscribe<ublox_msgs::UpdSOS_Ack>(
67  boost::bind(&Gps::processUpdSosAck, this, _1));
68 }
69 
70 void Gps::processAck(const ublox_msgs::Ack &m) {
71  // Process ACK/NACK messages
72  Ack ack;
73  ack.type = ACK;
74  ack.class_id = m.clsID;
75  ack.msg_id = m.msgID;
76  // store the ack atomically
77  ack_.store(ack, boost::memory_order_seq_cst);
78  ROS_DEBUG_COND(debug >= 2, "U-blox: received ACK: 0x%02x / 0x%02x",
79  m.clsID, m.msgID);
80 }
81 
82 void Gps::processNack(const ublox_msgs::Ack &m) {
83  // Process ACK/NACK messages
84  Ack ack;
85  ack.type = NACK;
86  ack.class_id = m.clsID;
87  ack.msg_id = m.msgID;
88  // store the ack atomically
89  ack_.store(ack, boost::memory_order_seq_cst);
90  ROS_ERROR("U-blox: received NACK: 0x%02x / 0x%02x", m.clsID, m.msgID);
91 }
92 
93 void Gps::processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m) {
94  if (m.cmd == UpdSOS_Ack::CMD_BACKUP_CREATE_ACK) {
95  Ack ack;
96  ack.type = (m.response == m.BACKUP_CREATE_ACK) ? ACK : NACK;
97  ack.class_id = m.CLASS_ID;
98  ack.msg_id = m.MESSAGE_ID;
99  // store the ack atomically
100  ack_.store(ack, boost::memory_order_seq_cst);
101  ROS_DEBUG_COND(ack.type == ACK && debug >= 2,
102  "U-blox: received UPD SOS Backup ACK");
103  if(ack.type == NACK)
104  ROS_ERROR("U-blox: received UPD SOS Backup NACK");
105  }
106 }
107 
108 void Gps::initializeSerial(std::string port, unsigned int baudrate,
109  uint16_t uart_in, uint16_t uart_out) {
110  port_ = port;
112  new boost::asio::io_service);
114  new boost::asio::serial_port(*io_service));
115 
116  // open serial port
117  try {
118  serial->open(port);
119  } catch (std::runtime_error& e) {
120  throw std::runtime_error("U-Blox: Could not open serial port :"
121  + port + " " + e.what());
122  }
123 
124  ROS_INFO("U-Blox: Opened serial port %s", port.c_str());
125 
126  if(BOOST_VERSION < 106600)
127  {
128  // NOTE(Kartik): Set serial port to "raw" mode. This is done in Boost but
129  // until v1.66.0 there was a bug which didn't enable the relevant code,
130  // fixed by commit: https://github.com/boostorg/asio/commit/619cea4356
131  int fd = serial->native_handle();
132  termios tio;
133  tcgetattr(fd, &tio);
134  cfmakeraw(&tio);
135  tcsetattr(fd, TCSANOW, &tio);
136  }
137 
138  // Set the I/O worker
139  if (worker_) return;
141  new AsyncWorker<boost::asio::serial_port>(serial, io_service)));
142 
143  configured_ = false;
144 
145  // Set the baudrate
146  boost::asio::serial_port_base::baud_rate current_baudrate;
147  serial->get_option(current_baudrate);
148  // Incrementally increase the baudrate to the desired value
149  for (int i = 0; i < sizeof(kBaudrates)/sizeof(kBaudrates[0]); i++) {
150  if (current_baudrate.value() == baudrate)
151  break;
152  // Don't step down, unless the desired baudrate is lower
153  if(current_baudrate.value() > kBaudrates[i] && baudrate > kBaudrates[i])
154  continue;
155  serial->set_option(
156  boost::asio::serial_port_base::baud_rate(kBaudrates[i]));
157  boost::this_thread::sleep(
158  boost::posix_time::milliseconds(kSetBaudrateSleepMs));
159  serial->get_option(current_baudrate);
160  ROS_DEBUG("U-Blox: Set ASIO baudrate to %u", current_baudrate.value());
161  }
163  configured_ = configUart1(baudrate, uart_in, uart_out);
164  if(!configured_ || current_baudrate.value() != baudrate) {
165  throw std::runtime_error("Could not configure serial baud rate");
166  }
167  } else {
168  configured_ = true;
169  }
170 }
171 
172 void Gps::resetSerial(std::string port) {
174  new boost::asio::io_service);
176  new boost::asio::serial_port(*io_service));
177 
178  // open serial port
179  try {
180  serial->open(port);
181  } catch (std::runtime_error& e) {
182  throw std::runtime_error("U-Blox: Could not open serial port :"
183  + port + " " + e.what());
184  }
185 
186  ROS_INFO("U-Blox: Reset serial port %s", port.c_str());
187 
188  // Set the I/O worker
189  if (worker_) return;
191  new AsyncWorker<boost::asio::serial_port>(serial, io_service)));
192  configured_ = false;
193 
194  // Poll UART PRT Config
195  std::vector<uint8_t> payload;
196  payload.push_back(CfgPRT::PORT_ID_UART1);
197  if (!poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
198  ROS_ERROR("Resetting Serial Port: Could not poll UART1 CfgPRT");
199  return;
200  }
201  CfgPRT prt;
202  if(!read(prt, default_timeout_)) {
203  ROS_ERROR("Resetting Serial Port: Could not read polled UART1 CfgPRT %s",
204  "message");
205  return;
206  }
207 
208  // Set the baudrate
209  serial->set_option(boost::asio::serial_port_base::baud_rate(prt.baudRate));
210  configured_ = true;
211 }
212 
213 void Gps::initializeTcp(std::string host, std::string port) {
214  host_ = host;
215  port_ = port;
217  new boost::asio::io_service);
218  boost::asio::ip::tcp::resolver::iterator endpoint;
219 
220  try {
221  boost::asio::ip::tcp::resolver resolver(*io_service);
222  endpoint =
223  resolver.resolve(boost::asio::ip::tcp::resolver::query(host, port));
224  } catch (std::runtime_error& e) {
225  throw std::runtime_error("U-Blox: Could not resolve" + host + " " +
226  port + " " + e.what());
227  }
228 
230  new boost::asio::ip::tcp::socket(*io_service));
231 
232  try {
233  socket->connect(*endpoint);
234  } catch (std::runtime_error& e) {
235  throw std::runtime_error("U-Blox: Could not connect to " +
236  endpoint->host_name() + ":" +
237  endpoint->service_name() + ": " + e.what());
238  }
239 
240  ROS_INFO("U-Blox: Connected to %s:%s.", endpoint->host_name().c_str(),
241  endpoint->service_name().c_str());
242 
243  if (worker_) return;
246  io_service)));
247 }
248 
249 void Gps::initializeUdp(std::string host, std::string port) {
250  host_ = host;
251  port_ = port;
253  new boost::asio::io_service);
254  boost::asio::ip::udp::resolver::iterator endpoint;
255 
256  try {
257  boost::asio::ip::udp::resolver resolver(*io_service);
258  endpoint =
259  resolver.resolve(boost::asio::ip::udp::resolver::query(host, port));
260  } catch (std::runtime_error& e) {
261  throw std::runtime_error("U-Blox: Could not resolve" + host + " " +
262  port + " " + e.what());
263  }
264 
266  new boost::asio::ip::udp::socket(*io_service));
267 
268  try {
269  socket->connect(*endpoint);
270  } catch (std::runtime_error& e) {
271  throw std::runtime_error("U-Blox: Could not connect to " +
272  endpoint->host_name() + ":" +
273  endpoint->service_name() + ": " + e.what());
274  }
275 
276  ROS_INFO("U-Blox: Connected to %s:%s.", endpoint->host_name().c_str(),
277  endpoint->service_name().c_str());
278 
279  if (worker_) return;
282  io_service)));
283 }
284 
285 void Gps::close() {
286  if(save_on_shutdown_) {
287  if(saveOnShutdown())
288  ROS_INFO("U-Blox Flash BBR saved");
289  else
290  ROS_INFO("U-Blox Flash BBR failed to save");
291  }
292  worker_.reset();
293  configured_ = false;
294 }
295 
296 void Gps::reset(const boost::posix_time::time_duration& wait) {
297  worker_.reset();
298  configured_ = false;
299  // sleep because of undefined behavior after I/O reset
300  boost::this_thread::sleep(wait);
301  if (host_ == "")
303  else
305 }
306 
307 bool Gps::configReset(uint16_t nav_bbr_mask, uint16_t reset_mode) {
308  ROS_WARN("Resetting u-blox. If device address changes, %s",
309  "node must be relaunched.");
310 
311  CfgRST rst;
312  rst.navBbrMask = nav_bbr_mask;
313  rst.resetMode = reset_mode;
314 
315  // Don't wait for ACK, return if it fails
316  if (!configure(rst, false))
317  return false;
318  return true;
319 }
320 
321 bool Gps::configGnss(CfgGNSS gnss,
322  const boost::posix_time::time_duration& wait) {
323  // Configure the GNSS settingshttps://mail.google.com/mail/u/0/#inbox
324  ROS_DEBUG("Re-configuring GNSS.");
325  if (!configure(gnss))
326  return false;
327  // Cold reset the GNSS
328  ROS_WARN("GNSS re-configured, cold resetting device.");
329  if (!configReset(CfgRST::NAV_BBR_COLD_START, CfgRST::RESET_MODE_GNSS))
330  return false;
331  ros::Duration(1.0).sleep();
332  // Reset the I/O
333  reset(wait);
334  return isConfigured();
335 }
336 
338  // Command the receiver to stop
339  CfgRST rst;
340  rst.navBbrMask = rst.NAV_BBR_HOT_START;
341  rst.resetMode = rst.RESET_MODE_GNSS_STOP;
342  if(!configure(rst))
343  return false;
344  // Command saving the contents of BBR to flash memory
345  // And wait for UBX-UPD-SOS-ACK
346  UpdSOS backup;
347  return configure(backup);
348 }
349 
351  // Command saving the contents of BBR to flash memory
352  // And wait for UBX-UPD-SOS-ACK
353  UpdSOS sos;
354  sos.cmd = sos.CMD_FLASH_BACKUP_CLEAR;
355  return configure(sos);
356 }
357 
358 bool Gps::configUart1(unsigned int baudrate, uint16_t in_proto_mask,
359  uint16_t out_proto_mask) {
360  if (!worker_) return true;
361 
362  ROS_DEBUG("Configuring UART1 baud rate: %u, In/Out Protocol: %u / %u",
363  baudrate, in_proto_mask, out_proto_mask);
364 
365  CfgPRT port;
366  port.portID = CfgPRT::PORT_ID_UART1;
367  port.baudRate = baudrate;
368  port.mode = CfgPRT::MODE_RESERVED1 | CfgPRT::MODE_CHAR_LEN_8BIT |
369  CfgPRT::MODE_PARITY_NO | CfgPRT::MODE_STOP_BITS_1;
370  port.inProtoMask = in_proto_mask;
371  port.outProtoMask = out_proto_mask;
372  return configure(port);
373 }
374 
375 bool Gps::disableUart1(CfgPRT& prev_config) {
376  ROS_DEBUG("Disabling UART1");
377 
378  // Poll UART PRT Config
379  std::vector<uint8_t> payload;
380  payload.push_back(CfgPRT::PORT_ID_UART1);
381  if (!poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
382  ROS_ERROR("disableUart: Could not poll UART1 CfgPRT");
383  return false;
384  }
385  if(!read(prev_config, default_timeout_)) {
386  ROS_ERROR("disableUart: Could not read polled UART1 CfgPRT message");
387  return false;
388  }
389  // Keep original settings, but disable in/out
390  CfgPRT port;
391  port.portID = CfgPRT::PORT_ID_UART1;
392  port.mode = prev_config.mode;
393  port.baudRate = prev_config.baudRate;
394  port.inProtoMask = 0;
395  port.outProtoMask = 0;
396  port.txReady = prev_config.txReady;
397  port.flags = prev_config.flags;
398  return configure(port);
399 }
400 
401 bool Gps::configUsb(uint16_t tx_ready,
402  uint16_t in_proto_mask,
403  uint16_t out_proto_mask) {
404  if (!worker_) return true;
405 
406  ROS_DEBUG("Configuring USB tx_ready: %u, In/Out Protocol: %u / %u",
407  tx_ready, in_proto_mask, out_proto_mask);
408 
409  CfgPRT port;
410  port.portID = CfgPRT::PORT_ID_USB;
411  port.txReady = tx_ready;
412  port.inProtoMask = in_proto_mask;
413  port.outProtoMask = out_proto_mask;
414  return configure(port);
415 }
416 
417 bool Gps::configRate(uint16_t meas_rate, uint16_t nav_rate) {
418  ROS_DEBUG("Configuring measurement rate to %u ms and nav rate to %u cycles",
420 
421  CfgRATE rate;
422  rate.measRate = meas_rate;
423  rate.navRate = nav_rate; // must be fixed at 1 for ublox 5 and 6
424  rate.timeRef = CfgRATE::TIME_REF_GPS;
425  return configure(rate);
426 }
427 
428 bool Gps::configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates) {
429  for(size_t i = 0; i < ids.size(); ++i) {
430  ROS_DEBUG("Setting RTCM %d Rate %u", ids[i], rates[i]);
431  if(!setRate(ublox_msgs::Class::RTCM, (uint8_t)ids[i], rates[i])) {
432  ROS_ERROR("Could not set RTCM %d to rate %u", ids[i], rates[i]);
433  return false;
434  }
435  }
436  return true;
437 }
438 
439 bool Gps::configSbas(bool enable, uint8_t usage, uint8_t max_sbas) {
440  ROS_DEBUG("Configuring SBAS: usage %u, max_sbas %u", usage, max_sbas);
441 
442  ublox_msgs::CfgSBAS msg;
443  msg.mode = (enable ? CfgSBAS::MODE_ENABLED : 0);
444  msg.usage = usage;
445  msg.maxSBAS = max_sbas;
446  return configure(msg);
447 }
448 
449 bool Gps::configTmode3Fixed(bool lla_flag,
450  std::vector<float> arp_position,
451  std::vector<int8_t> arp_position_hp,
452  float fixed_pos_acc) {
453  if(arp_position.size() != 3 || arp_position_hp.size() != 3) {
454  ROS_ERROR("Configuring TMODE3 to Fixed: size of position %s",
455  "& arp_position_hp args must be 3");
456  return false;
457  }
458 
459  ROS_DEBUG("Configuring TMODE3 to Fixed");
460 
461  CfgTMODE3 tmode3;
462  tmode3.flags = tmode3.FLAGS_MODE_FIXED & tmode3.FLAGS_MODE_MASK;
463  tmode3.flags |= lla_flag ? tmode3.FLAGS_LLA : 0;
464 
465  // Set position
466  if(lla_flag) {
467  // Convert from [deg] to [deg * 1e-7]
468  tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e7);
469  tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e7);
470  tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e7);
471  } else {
472  // Convert from m to cm
473  tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e2);
474  tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e2);
475  tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e2);
476  }
477  tmode3.ecefXOrLatHP = arp_position_hp[0];
478  tmode3.ecefYOrLonHP = arp_position_hp[1];
479  tmode3.ecefZOrAltHP = arp_position_hp[2];
480  // Convert from m to [0.1 mm]
481  tmode3.fixedPosAcc = (uint32_t)round(fixed_pos_acc * 1e4);
482  return configure(tmode3);
483 }
484 
485 bool Gps::configTmode3SurveyIn(unsigned int svin_min_dur,
486  float svin_acc_limit) {
487  CfgTMODE3 tmode3;
488  ROS_DEBUG("Setting TMODE3 to Survey In");
489  tmode3.flags = tmode3.FLAGS_MODE_SURVEY_IN & tmode3.FLAGS_MODE_MASK;
490  tmode3.svinMinDur = svin_min_dur;
491  // Convert from m to [0.1 mm]
492  tmode3.svinAccLimit = (int)round(svin_acc_limit * 1e4);
493  return configure(tmode3);
494 }
495 
497  ROS_DEBUG("Disabling TMODE3");
498 
499  CfgTMODE3 tmode3;
500  tmode3.flags = tmode3.FLAGS_MODE_DISABLED & tmode3.FLAGS_MODE_MASK;
501  return configure(tmode3);
502 }
503 
504 bool Gps::setRate(uint8_t class_id, uint8_t message_id, uint8_t rate) {
505  ROS_DEBUG_COND(debug >= 2, "Setting rate 0x%02x, 0x%02x, %u", class_id,
506  message_id, rate);
507  ublox_msgs::CfgMSG msg;
508  msg.msgClass = class_id;
509  msg.msgID = message_id;
510  msg.rate = rate;
511  return configure(msg);
512 }
513 
514 bool Gps::setDynamicModel(uint8_t model) {
515  ROS_DEBUG("Setting dynamic model to %u", model);
516 
517  ublox_msgs::CfgNAV5 msg;
518  msg.dynModel = model;
519  msg.mask = ublox_msgs::CfgNAV5::MASK_DYN;
520  return configure(msg);
521 }
522 
523 bool Gps::setFixMode(uint8_t mode) {
524  ROS_DEBUG("Setting fix mode to %u", mode);
525 
526  ublox_msgs::CfgNAV5 msg;
527  msg.fixMode = mode;
528  msg.mask = ublox_msgs::CfgNAV5::MASK_FIX_MODE;
529  return configure(msg);
530 }
531 
532 bool Gps::setDeadReckonLimit(uint8_t limit) {
533  ROS_DEBUG("Setting DR Limit to %u", limit);
534 
535  ublox_msgs::CfgNAV5 msg;
536  msg.drLimit = limit;
537  msg.mask = ublox_msgs::CfgNAV5::MASK_DR_LIM;
538  return configure(msg);
539 }
540 
541 bool Gps::setPpp(bool enable, float protocol_version) {
542  ROS_DEBUG("%s PPP", (enable ? "Enabling" : "Disabling"));
543 
544  ublox_msgs::CfgNAVX5 msg;
545  msg.usePPP = enable;
546  if(protocol_version >= 18)
547  msg.version = 2;
548  msg.mask1 = ublox_msgs::CfgNAVX5::MASK1_PPP;
549  return configure(msg);
550 }
551 
552 bool Gps::setDgnss(uint8_t mode) {
553  CfgDGNSS cfg;
554  ROS_DEBUG("Setting DGNSS mode to %u", mode);
555  cfg.dgnssMode = mode;
556  return configure(cfg);
557 }
558 
559 bool Gps::setUseAdr(bool enable, float protocol_version) {
560  ROS_DEBUG("%s ADR/UDR", (enable ? "Enabling" : "Disabling"));
561 
562  ublox_msgs::CfgNAVX5 msg;
563  msg.useAdr = enable;
564 
565  if(protocol_version >= 18)
566  msg.version = 2;
567  msg.mask2 = ublox_msgs::CfgNAVX5::MASK2_ADR;
568  return configure(msg);
569 }
570 
571 bool Gps::sendRtcm(const std::vector<uint8_t>& rtcm){
572  worker_->send(rtcm.data(), rtcm.size());
573  return true;
574 }
575 
576 bool Gps::poll(uint8_t class_id, uint8_t message_id,
577  const std::vector<uint8_t>& payload) {
578  if (!worker_) return false;
579 
580  std::vector<unsigned char> out(kWriterSize);
581  ublox::Writer writer(out.data(), out.size());
582  if (!writer.write(payload.data(), payload.size(), class_id, message_id))
583  return false;
584  worker_->send(out.data(), writer.end() - out.data());
585 
586  return true;
587 }
588 
589 bool Gps::waitForAcknowledge(const boost::posix_time::time_duration& timeout,
590  uint8_t class_id, uint8_t msg_id) {
591  ROS_DEBUG_COND(debug >= 2, "Waiting for ACK 0x%02x / 0x%02x",
592  class_id, msg_id);
593  boost::posix_time::ptime wait_until(
594  boost::posix_time::second_clock::local_time() + timeout);
595 
596  Ack ack = ack_.load(boost::memory_order_seq_cst);
597  while (boost::posix_time::second_clock::local_time() < wait_until
598  && (ack.class_id != class_id
599  || ack.msg_id != msg_id
600  || ack.type == WAIT)) {
601  worker_->wait(timeout);
602  ack = ack_.load(boost::memory_order_seq_cst);
603  }
604  bool result = ack.type == ACK
605  && ack.class_id == class_id
606  && ack.msg_id == msg_id;
607  return result;
608 }
609 
611  if (! worker_) return;
612  worker_->setRawDataCallback(callback);
613 }
614 
616  ROS_DEBUG("Setting time to UTC time");
617 
618  ublox_msgs::CfgNAV5 msg;
619  msg.utcStandard = 3;
620  return configure(msg);
621 }
622 
623 bool Gps::setTimtm2(uint8_t rate) {
624  ROS_DEBUG("TIM-TM2 send rate on current port set to %u", rate );
625  ublox_msgs::CfgMSG msg;
626  msg.msgClass = ublox_msgs::TimTM2::CLASS_ID;
627  msg.msgID = ublox_msgs::TimTM2::MESSAGE_ID;
628  msg.rate = rate;
629  return configure(msg);
630 }
631 } // namespace ublox_gps
ublox_gps::Gps::save_on_shutdown_
bool save_on_shutdown_
Whether or not to save Flash BBR on shutdown.
Definition: gps.h:486
ublox_gps::Gps::reset
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
Definition: gps.cpp:296
ublox_gps::Gps::kWriterSize
constexpr static int kWriterSize
Size of write buffer for output messages.
Definition: gps.h:74
ublox_gps::Gps::ACK
@ ACK
Not acknowledged.
Definition: gps.h:429
msg
msg
ublox_gps::Gps::NACK
@ NACK
Definition: gps.h:428
ublox_gps::Gps::host_
std::string host_
Definition: gps.h:499
ublox_gps::Gps::configRtcm
bool configRtcm(std::vector< uint8_t > ids, std::vector< uint8_t > rates)
Configure the RTCM messages with the given IDs to the set rate.
Definition: gps.cpp:428
boost::shared_ptr
ublox_gps::Gps::configured_
bool configured_
Whether or not the I/O port has been configured.
Definition: gps.h:484
ublox_gps::Gps::setTimtm2
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Definition: gps.cpp:623
ublox_gps::Gps::processAck
void processAck(const ublox_msgs::Ack &m)
Callback handler for UBX-ACK message.
Definition: gps.cpp:70
ublox_gps::Gps::~Gps
virtual ~Gps()
Definition: gps.cpp:48
ublox_gps::Gps::configGnss
bool configGnss(ublox_msgs::CfgGNSS gnss, const boost::posix_time::time_duration &wait)
Configure the GNSS, cold reset the device, and reset the I/O.
Definition: gps.cpp:321
ublox_gps::Gps::ack_
boost::atomic< Ack > ack_
Stores last received ACK accessed by multiple threads.
Definition: gps.h:494
ublox_gps::AsyncWorker
Handles Asynchronous I/O reading and writing.
Definition: async_worker.h:51
ublox_gps::Gps::setRate
bool setRate(uint8_t class_id, uint8_t message_id, uint8_t rate)
Set the rate at which the U-Blox device sends the given message.
Definition: gps.cpp:504
ublox_gps::Gps::clearBbr
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
Definition: gps.cpp:350
ublox_node::config_on_startup_flag_
bool config_on_startup_flag_
Flag for enabling configuration on startup.
Definition: node.h:129
ublox_gps::Gps::WAIT
@ WAIT
Acknowledge.
Definition: gps.h:430
ROS_DEBUG_COND
#define ROS_DEBUG_COND(cond,...)
ublox_gps::Gps::callbacks_
CallbackHandlers callbacks_
Callback handlers for u-blox messages.
Definition: gps.h:497
ublox_gps::Gps::configUsb
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
Definition: gps.cpp:401
ublox_gps::Gps::setDynamicModel
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
Definition: gps.cpp:514
wait
void wait(int seconds)
ublox_gps::Gps::setFixMode
bool setFixMode(uint8_t mode)
Set the device fix mode.
Definition: gps.cpp:523
ublox_gps::Gps::Ack::msg_id
uint8_t msg_id
The message ID of the ACK.
Definition: gps.h:437
ublox_gps::Gps::configUart1
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
Definition: gps.cpp:358
ublox_gps::Gps::setUseAdr
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
Definition: gps.cpp:559
ublox_gps::Gps::configTmode3Fixed
bool configTmode3Fixed(bool lla_flag, std::vector< float > arp_position, std::vector< int8_t > arp_position_hp, float fixed_pos_acc)
Set the TMODE3 settings to fixed.
Definition: gps.cpp:449
ublox_gps::Gps::config_on_startup_flag_
bool config_on_startup_flag_
Definition: gps.h:488
ublox_gps
Definition: async_worker.h:43
ublox_gps::Gps::disableUart1
bool disableUart1(ublox_msgs::CfgPRT &prev_cfg)
Disable the UART Port. Sets in/out protocol masks to 0. Does not modify other values.
Definition: gps.cpp:375
ublox_msgs::Message::ACK::NACK
static const uint8_t NACK
ublox_gps::Gps::Gps
Gps()
Definition: gps.cpp:44
gps.h
ublox_gps::Gps::initializeUdp
void initializeUdp(std::string host, std::string port)
Initialize UDP I/O.
Definition: gps.cpp:249
ROS_DEBUG
#define ROS_DEBUG(...)
ublox_gps::Gps::initializeTcp
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
Definition: gps.cpp:213
ublox_gps::Gps::setDeadReckonLimit
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
Definition: gps.cpp:532
ublox_gps::Gps::subscribeAcks
void subscribeAcks()
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.
Definition: gps.cpp:58
ublox_gps::Gps::read
bool read(T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
Definition: gps.h:529
ublox::Writer
ublox_gps::Gps::kDefaultAckTimeout
constexpr static double kDefaultAckTimeout
Default timeout for ACK messages in seconds.
Definition: gps.h:72
ublox_gps::Gps::port_
std::string port_
Definition: gps.h:499
ublox_gps::Gps::worker_
boost::shared_ptr< Worker > worker_
Processes I/O stream data.
Definition: gps.h:482
ublox_gps::Gps::sendRtcm
bool sendRtcm(const std::vector< uint8_t > &message)
Send rtcm correction message.
Definition: gps.cpp:571
ublox_node::meas_rate
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
Definition: node.h:121
ROS_WARN
#define ROS_WARN(...)
ublox_gps::kBaudrates
constexpr static unsigned int kBaudrates[]
Possible baudrates for u-blox devices.
Definition: gps.h:58
ublox_gps::kSetBaudrateSleepMs
constexpr static int kSetBaudrateSleepMs
Sleep time [ms] after setting the baudrate.
Definition: gps.cpp:38
ublox_gps::Gps::setUTCtime
bool setUTCtime()
Configure the U-Blox to UTC time.
Definition: gps.cpp:615
ublox::Writer::write
bool write(const T &message, uint8_t class_id=T::CLASS_ID, uint8_t message_id=T::MESSAGE_ID)
ublox_gps::Gps::Ack::class_id
uint8_t class_id
The class ID of the ACK.
Definition: gps.h:436
ublox_gps::Gps::setPpp
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
Definition: gps.cpp:541
ublox_gps::Gps::disableTmode3
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices,...
Definition: gps.cpp:496
ublox_gps::Gps::initializeSerial
void initializeSerial(std::string port, unsigned int baudrate, uint16_t uart_in, uint16_t uart_out)
Initialize the Serial I/O port.
Definition: gps.cpp:108
ublox_gps::Gps::setWorker
void setWorker(const boost::shared_ptr< Worker > &worker)
Set the I/O worker.
Definition: gps.cpp:50
ublox_gps::Gps::isConfigured
bool isConfigured() const
Definition: gps.h:374
ublox_gps::Worker::Callback
boost::function< void(unsigned char *, std::size_t &)> Callback
Definition: worker.h:42
ublox::Writer::end
iterator end()
ublox_gps::Gps::Ack::type
AckType type
The ACK type.
Definition: gps.h:435
ublox_gps::Gps::configTmode3SurveyIn
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
Definition: gps.cpp:485
ublox_gps::Gps::poll
bool poll(ConfigT &message, const std::vector< uint8_t > &payload=std::vector< uint8_t >(), const boost::posix_time::time_duration &timeout=default_timeout_)
Definition: gps.h:521
ublox_gps::Gps::resetSerial
void resetSerial(std::string port)
Reset the Serial I/O port after u-blox reset.
Definition: gps.cpp:172
ublox_gps::Gps::configSbas
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
Definition: gps.cpp:439
ublox_msgs::Class::RTCM
static const uint8_t RTCM
ROS_ERROR
#define ROS_ERROR(...)
ublox_gps::Gps::default_timeout_
static const boost::posix_time::time_duration default_timeout_
The default timeout for ACK messages.
Definition: gps.h:492
ublox_gps::Gps::processUpdSosAck
void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m)
Callback handler for UBX-UPD-SOS-ACK message.
Definition: gps.cpp:93
ublox_node::nav_rate
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:123
ublox_gps::Gps::saveOnShutdown
bool saveOnShutdown()
Execute save on shutdown procedure.
Definition: gps.cpp:337
ublox_gps::Gps::setDgnss
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
Definition: gps.cpp:552
ublox_gps::Gps::Ack
Stores ACK/NACK messages.
Definition: gps.h:434
ublox_gps::Gps::setRawDataCallback
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
Definition: gps.cpp:610
ros::Duration::sleep
bool sleep() const
ublox_msgs::Message::ACK::ACK
static const uint8_t ACK
ublox_gps::Gps::configure
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
Definition: gps.h:535
ublox_gps::CallbackHandlers::readCallback
void readCallback(unsigned char *data, std::size_t &size)
Processes u-blox messages in the given buffer & clears the read messages from the buffer.
Definition: callback.h:235
ublox_gps::Gps::waitForAcknowledge
bool waitForAcknowledge(const boost::posix_time::time_duration &timeout, uint8_t class_id, uint8_t msg_id)
Wait for an acknowledge message until the timeout.
Definition: gps.cpp:589
ublox_gps::Gps::processNack
void processNack(const ublox_msgs::Ack &m)
Callback handler for UBX-NACK message.
Definition: gps.cpp:82
ROS_INFO
#define ROS_INFO(...)
ublox_msgs
ublox_gps::Gps::configReset
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
Definition: gps.cpp:307
ros::Duration
ublox_gps::Gps::close
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
Definition: gps.cpp:285
ublox_gps::Gps::configRate
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
Definition: gps.cpp:417
ublox_gps::debug
int debug
Used to determine which debug messages to display.
Definition: async_worker.h:45
usage
def usage(progname)


ublox_gps
Author(s): Johannes Meyer
autogenerated on Wed Dec 7 2022 03:47:53