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::close() {
250  if(save_on_shutdown_) {
251  if(saveOnShutdown())
252  ROS_INFO("U-Blox Flash BBR saved");
253  else
254  ROS_INFO("U-Blox Flash BBR failed to save");
255  }
256  worker_.reset();
257  configured_ = false;
258 }
259 
260 void Gps::reset(const boost::posix_time::time_duration& wait) {
261  worker_.reset();
262  configured_ = false;
263  // sleep because of undefined behavior after I/O reset
264  boost::this_thread::sleep(wait);
265  if (host_ == "")
267  else
269 }
270 
271 bool Gps::configReset(uint16_t nav_bbr_mask, uint16_t reset_mode) {
272  ROS_WARN("Resetting u-blox. If device address changes, %s",
273  "node must be relaunched.");
274 
275  CfgRST rst;
276  rst.navBbrMask = nav_bbr_mask;
277  rst.resetMode = reset_mode;
278 
279  // Don't wait for ACK, return if it fails
280  if (!configure(rst, false))
281  return false;
282  return true;
283 }
284 
285 bool Gps::configGnss(CfgGNSS gnss,
286  const boost::posix_time::time_duration& wait) {
287  // Configure the GNSS settingshttps://mail.google.com/mail/u/0/#inbox
288  ROS_DEBUG("Re-configuring GNSS.");
289  if (!configure(gnss))
290  return false;
291  // Cold reset the GNSS
292  ROS_WARN("GNSS re-configured, cold resetting device.");
293  if (!configReset(CfgRST::NAV_BBR_COLD_START, CfgRST::RESET_MODE_GNSS))
294  return false;
295  ros::Duration(1.0).sleep();
296  // Reset the I/O
297  reset(wait);
298  return isConfigured();
299 }
300 
302  // Command the receiver to stop
303  CfgRST rst;
304  rst.navBbrMask = rst.NAV_BBR_HOT_START;
305  rst.resetMode = rst.RESET_MODE_GNSS_STOP;
306  if(!configure(rst))
307  return false;
308  // Command saving the contents of BBR to flash memory
309  // And wait for UBX-UPD-SOS-ACK
310  UpdSOS backup;
311  return configure(backup);
312 }
313 
315  // Command saving the contents of BBR to flash memory
316  // And wait for UBX-UPD-SOS-ACK
317  UpdSOS sos;
318  sos.cmd = sos.CMD_FLASH_BACKUP_CLEAR;
319  return configure(sos);
320 }
321 
322 bool Gps::configUart1(unsigned int baudrate, uint16_t in_proto_mask,
323  uint16_t out_proto_mask) {
324  if (!worker_) return true;
325 
326  ROS_DEBUG("Configuring UART1 baud rate: %u, In/Out Protocol: %u / %u",
327  baudrate, in_proto_mask, out_proto_mask);
328 
329  CfgPRT port;
330  port.portID = CfgPRT::PORT_ID_UART1;
331  port.baudRate = baudrate;
332  port.mode = CfgPRT::MODE_RESERVED1 | CfgPRT::MODE_CHAR_LEN_8BIT |
333  CfgPRT::MODE_PARITY_NO | CfgPRT::MODE_STOP_BITS_1;
334  port.inProtoMask = in_proto_mask;
335  port.outProtoMask = out_proto_mask;
336  return configure(port);
337 }
338 
339 bool Gps::disableUart1(CfgPRT& prev_config) {
340  ROS_DEBUG("Disabling UART1");
341 
342  // Poll UART PRT Config
343  std::vector<uint8_t> payload;
344  payload.push_back(CfgPRT::PORT_ID_UART1);
345  if (!poll(CfgPRT::CLASS_ID, CfgPRT::MESSAGE_ID, payload)) {
346  ROS_ERROR("disableUart: Could not poll UART1 CfgPRT");
347  return false;
348  }
349  if(!read(prev_config, default_timeout_)) {
350  ROS_ERROR("disableUart: Could not read polled UART1 CfgPRT message");
351  return false;
352  }
353  // Keep original settings, but disable in/out
354  CfgPRT port;
355  port.portID = CfgPRT::PORT_ID_UART1;
356  port.mode = prev_config.mode;
357  port.baudRate = prev_config.baudRate;
358  port.inProtoMask = 0;
359  port.outProtoMask = 0;
360  port.txReady = prev_config.txReady;
361  port.flags = prev_config.flags;
362  return configure(port);
363 }
364 
365 bool Gps::configUsb(uint16_t tx_ready,
366  uint16_t in_proto_mask,
367  uint16_t out_proto_mask) {
368  if (!worker_) return true;
369 
370  ROS_DEBUG("Configuring USB tx_ready: %u, In/Out Protocol: %u / %u",
371  tx_ready, in_proto_mask, out_proto_mask);
372 
373  CfgPRT port;
374  port.portID = CfgPRT::PORT_ID_USB;
375  port.txReady = tx_ready;
376  port.inProtoMask = in_proto_mask;
377  port.outProtoMask = out_proto_mask;
378  return configure(port);
379 }
380 
381 bool Gps::configRate(uint16_t meas_rate, uint16_t nav_rate) {
382  ROS_DEBUG("Configuring measurement rate to %u ms and nav rate to %u cycles",
383  meas_rate, nav_rate);
384 
385  CfgRATE rate;
386  rate.measRate = meas_rate;
387  rate.navRate = nav_rate; // must be fixed at 1 for ublox 5 and 6
388  rate.timeRef = CfgRATE::TIME_REF_GPS;
389  return configure(rate);
390 }
391 
392 bool Gps::configRtcm(std::vector<uint8_t> ids, std::vector<uint8_t> rates) {
393  for(size_t i = 0; i < ids.size(); ++i) {
394  ROS_DEBUG("Setting RTCM %d Rate %u", ids[i], rates[i]);
395  if(!setRate(ublox_msgs::Class::RTCM, (uint8_t)ids[i], rates[i])) {
396  ROS_ERROR("Could not set RTCM %d to rate %u", ids[i], rates[i]);
397  return false;
398  }
399  }
400  return true;
401 }
402 
403 bool Gps::configSbas(bool enable, uint8_t usage, uint8_t max_sbas) {
404  ROS_DEBUG("Configuring SBAS: usage %u, max_sbas %u", usage, max_sbas);
405 
406  ublox_msgs::CfgSBAS msg;
407  msg.mode = (enable ? CfgSBAS::MODE_ENABLED : 0);
408  msg.usage = usage;
409  msg.maxSBAS = max_sbas;
410  return configure(msg);
411 }
412 
413 bool Gps::configTmode3Fixed(bool lla_flag,
414  std::vector<float> arp_position,
415  std::vector<int8_t> arp_position_hp,
416  float fixed_pos_acc) {
417  if(arp_position.size() != 3 || arp_position_hp.size() != 3) {
418  ROS_ERROR("Configuring TMODE3 to Fixed: size of position %s",
419  "& arp_position_hp args must be 3");
420  return false;
421  }
422 
423  ROS_DEBUG("Configuring TMODE3 to Fixed");
424 
425  CfgTMODE3 tmode3;
426  tmode3.flags = tmode3.FLAGS_MODE_FIXED & tmode3.FLAGS_MODE_MASK;
427  tmode3.flags |= lla_flag ? tmode3.FLAGS_LLA : 0;
428 
429  // Set position
430  if(lla_flag) {
431  // Convert from [deg] to [deg * 1e-7]
432  tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e7);
433  tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e7);
434  tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e7);
435  } else {
436  // Convert from m to cm
437  tmode3.ecefXOrLat = (int)round(arp_position[0] * 1e2);
438  tmode3.ecefYOrLon = (int)round(arp_position[1] * 1e2);
439  tmode3.ecefZOrAlt = (int)round(arp_position[2] * 1e2);
440  }
441  tmode3.ecefXOrLatHP = arp_position_hp[0];
442  tmode3.ecefYOrLonHP = arp_position_hp[1];
443  tmode3.ecefZOrAltHP = arp_position_hp[2];
444  // Convert from m to [0.1 mm]
445  tmode3.fixedPosAcc = (uint32_t)round(fixed_pos_acc * 1e4);
446  return configure(tmode3);
447 }
448 
449 bool Gps::configTmode3SurveyIn(unsigned int svin_min_dur,
450  float svin_acc_limit) {
451  CfgTMODE3 tmode3;
452  ROS_DEBUG("Setting TMODE3 to Survey In");
453  tmode3.flags = tmode3.FLAGS_MODE_SURVEY_IN & tmode3.FLAGS_MODE_MASK;
454  tmode3.svinMinDur = svin_min_dur;
455  // Convert from m to [0.1 mm]
456  tmode3.svinAccLimit = (int)round(svin_acc_limit * 1e4);
457  return configure(tmode3);
458 }
459 
461  ROS_DEBUG("Disabling TMODE3");
462 
463  CfgTMODE3 tmode3;
464  tmode3.flags = tmode3.FLAGS_MODE_DISABLED & tmode3.FLAGS_MODE_MASK;
465  return configure(tmode3);
466 }
467 
468 bool Gps::setRate(uint8_t class_id, uint8_t message_id, uint8_t rate) {
469  ROS_DEBUG_COND(debug >= 2, "Setting rate 0x%02x, 0x%02x, %u", class_id,
470  message_id, rate);
471  ublox_msgs::CfgMSG msg;
472  msg.msgClass = class_id;
473  msg.msgID = message_id;
474  msg.rate = rate;
475  return configure(msg);
476 }
477 
478 bool Gps::setDynamicModel(uint8_t model) {
479  ROS_DEBUG("Setting dynamic model to %u", model);
480 
481  ublox_msgs::CfgNAV5 msg;
482  msg.dynModel = model;
483  msg.mask = ublox_msgs::CfgNAV5::MASK_DYN;
484  return configure(msg);
485 }
486 
487 bool Gps::setFixMode(uint8_t mode) {
488  ROS_DEBUG("Setting fix mode to %u", mode);
489 
490  ublox_msgs::CfgNAV5 msg;
491  msg.fixMode = mode;
492  msg.mask = ublox_msgs::CfgNAV5::MASK_FIX_MODE;
493  return configure(msg);
494 }
495 
496 bool Gps::setDeadReckonLimit(uint8_t limit) {
497  ROS_DEBUG("Setting DR Limit to %u", limit);
498 
499  ublox_msgs::CfgNAV5 msg;
500  msg.drLimit = limit;
501  msg.mask = ublox_msgs::CfgNAV5::MASK_DR_LIM;
502  return configure(msg);
503 }
504 
505 bool Gps::setPpp(bool enable, float protocol_version) {
506  ROS_DEBUG("%s PPP", (enable ? "Enabling" : "Disabling"));
507 
508  ublox_msgs::CfgNAVX5 msg;
509  msg.usePPP = enable;
510  if(protocol_version >= 18)
511  msg.version = 2;
512  msg.mask1 = ublox_msgs::CfgNAVX5::MASK1_PPP;
513  return configure(msg);
514 }
515 
516 bool Gps::setDgnss(uint8_t mode) {
517  CfgDGNSS cfg;
518  ROS_DEBUG("Setting DGNSS mode to %u", mode);
519  cfg.dgnssMode = mode;
520  return configure(cfg);
521 }
522 
523 bool Gps::setUseAdr(bool enable, float protocol_version) {
524  ROS_DEBUG("%s ADR/UDR", (enable ? "Enabling" : "Disabling"));
525 
526  ublox_msgs::CfgNAVX5 msg;
527  msg.useAdr = enable;
528 
529  if(protocol_version >= 18)
530  msg.version = 2;
531  msg.mask2 = ublox_msgs::CfgNAVX5::MASK2_ADR;
532  return configure(msg);
533 }
534 
535 bool Gps::poll(uint8_t class_id, uint8_t message_id,
536  const std::vector<uint8_t>& payload) {
537  if (!worker_) return false;
538 
539  std::vector<unsigned char> out(kWriterSize);
540  ublox::Writer writer(out.data(), out.size());
541  if (!writer.write(payload.data(), payload.size(), class_id, message_id))
542  return false;
543  worker_->send(out.data(), writer.end() - out.data());
544 
545  return true;
546 }
547 
548 bool Gps::waitForAcknowledge(const boost::posix_time::time_duration& timeout,
549  uint8_t class_id, uint8_t msg_id) {
550  ROS_DEBUG_COND(debug >= 2, "Waiting for ACK 0x%02x / 0x%02x",
551  class_id, msg_id);
552  boost::posix_time::ptime wait_until(
553  boost::posix_time::second_clock::local_time() + timeout);
554 
555  Ack ack = ack_.load(boost::memory_order_seq_cst);
556  while (boost::posix_time::second_clock::local_time() < wait_until
557  && (ack.class_id != class_id
558  || ack.msg_id != msg_id
559  || ack.type == WAIT)) {
560  worker_->wait(timeout);
561  ack = ack_.load(boost::memory_order_seq_cst);
562  }
563  bool result = ack.type == ACK
564  && ack.class_id == class_id
565  && ack.msg_id == msg_id;
566  return result;
567 }
568 
570  if (! worker_) return;
571  worker_->setRawDataCallback(callback);
572 }
573 
575  ROS_DEBUG("Setting time to UTC time");
576 
577  ublox_msgs::CfgNAV5 msg;
578  msg.utcStandard = 3;
579  return configure(msg);
580 }
581 
582 bool Gps::setTimtm2(uint8_t rate) {
583  ROS_DEBUG("TIM-TM2 send rate on current port set to %u", rate );
584  ublox_msgs::CfgMSG msg;
585  msg.msgClass = ublox_msgs::TimTM2::CLASS_ID;
586  msg.msgID = ublox_msgs::TimTM2::MESSAGE_ID;
587  msg.rate = rate;
588  return configure(msg);
589 }
590 } // namespace ublox_gps
int debug
Used to determine which debug messages to display.
Definition: async_worker.h:45
bool isConfigured() const
Definition: gps.h:355
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:285
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
Definition: gps.cpp:249
msg
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:502
boost::atomic< Ack > ack_
Stores last received ACK accessed by multiple threads.
Definition: gps.h:475
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:413
static constexpr int kSetBaudrateSleepMs
Sleep time [ms] after setting the baudrate.
Definition: gps.cpp:38
bool save_on_shutdown_
Whether or not to save Flash BBR on shutdown.
Definition: gps.h:467
void processNack(const ublox_msgs::Ack &m)
Callback handler for UBX-NACK message.
Definition: gps.cpp:82
bool configReset(uint16_t nav_bbr_mask, uint16_t reset_mode)
Send a reset message to the u-blox device.
Definition: gps.cpp:271
bool read(T &message, const boost::posix_time::time_duration &timeout=default_timeout_)
Definition: gps.h:510
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:339
uint8_t class_id
The class ID of the ACK.
Definition: gps.h:417
bool sleep() const
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
Definition: gps.cpp:523
bool setFixMode(uint8_t mode)
Set the device fix mode.
Definition: gps.cpp:487
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
Definition: gps.cpp:381
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
Definition: gps.cpp:403
static constexpr unsigned int kBaudrates[]
Possible baudrates for u-blox devices.
Definition: gps.h:57
void setWorker(const boost::shared_ptr< Worker > &worker)
Set the I/O worker.
Definition: gps.cpp:50
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Definition: gps.cpp:582
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:120
#define ROS_WARN(...)
Stores ACK/NACK messages.
Definition: gps.h:415
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
Definition: gps.cpp:460
boost::function< void(unsigned char *, std::size_t &)> Callback
Definition: worker.h:42
std::string host_
Definition: gps.h:480
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
Definition: gps.cpp:449
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:548
void reset(const boost::posix_time::time_duration &wait)
Reset I/O communications.
Definition: gps.cpp:260
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
bool configUart1(unsigned int baudrate, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the UART1 Port.
Definition: gps.cpp:322
bool config_on_startup_flag_
Flag for enabling configuration on startup.
Definition: node.h:126
bool configured_
Whether or not the I/O port has been configured.
Definition: gps.h:465
static const uint8_t NACK
bool config_on_startup_flag_
Definition: gps.h:469
std::string port_
Definition: gps.h:480
CallbackHandlers callbacks_
Callback handlers for u-blox messages.
Definition: gps.h:478
uint8_t msg_id
The message ID of the ACK.
Definition: gps.h:418
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:468
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
Definition: gps.cpp:569
#define ROS_INFO(...)
AckType type
The ACK type.
Definition: gps.h:416
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
Definition: gps.cpp:516
static constexpr double kDefaultAckTimeout
Default timeout for ACK messages in seconds.
Definition: gps.h:71
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:205
virtual ~Gps()
Definition: gps.cpp:48
bool setPpp(bool enable, float protocol_version)
Enable or disable PPP (precise-point-positioning).
Definition: gps.cpp:505
bool configUsb(uint16_t tx_ready, uint16_t in_proto_mask, uint16_t out_proto_mask)
Configure the USB Port.
Definition: gps.cpp:365
static constexpr int kWriterSize
Size of write buffer for output messages.
Definition: gps.h:73
void resetSerial(std::string port)
Reset the Serial I/O port after u-blox reset.
Definition: gps.cpp:172
void subscribeAcks()
Subscribe to ACK/NACK messages and UPD-SOS-ACK messages.
Definition: gps.cpp:58
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
Definition: node.h:118
void processAck(const ublox_msgs::Ack &m)
Callback handler for UBX-ACK message.
Definition: gps.cpp:70
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
Definition: gps.cpp:496
Handles Asynchronous I/O reading and writing.
Definition: async_worker.h:51
#define ROS_DEBUG_COND(cond,...)
void processUpdSosAck(const ublox_msgs::UpdSOS_Ack &m)
Callback handler for UBX-UPD-SOS-ACK message.
Definition: gps.cpp:93
static const uint8_t ACK
static const uint8_t RTCM
static const boost::posix_time::time_duration default_timeout_
The default timeout for ACK messages.
Definition: gps.h:473
boost::shared_ptr< Worker > worker_
Processes I/O stream data.
Definition: gps.h:463
#define ROS_ERROR(...)
bool saveOnShutdown()
Execute save on shutdown procedure.
Definition: gps.cpp:301
Not acknowledged.
Definition: gps.h:410
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:392
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
Definition: gps.h:516
Acknowledge.
Definition: gps.h:411
bool setDynamicModel(uint8_t model)
Set the device dynamic model.
Definition: gps.cpp:478
bool clearBbr()
Send a message to the receiver to delete the BBR data stored in flash.
Definition: gps.cpp:314
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
Definition: gps.cpp:213
bool setUTCtime()
Configure the U-Blox to UTC time.
Definition: gps.cpp:574
#define ROS_DEBUG(...)


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Jan 28 2021 03:13:52