node.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/node.h"
31 #include <cmath>
32 #include <string>
33 #include <sstream>
34 
35 using namespace ublox_node;
36 
38 constexpr static int kResetWait = 10;
39 
40 //
41 // ublox_node namespace
42 //
43 uint8_t ublox_node::modelFromString(const std::string& model) {
44  std::string lower = model;
45  std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
46  if(lower == "portable") {
47  return ublox_msgs::CfgNAV5::DYN_MODEL_PORTABLE;
48  } else if(lower == "stationary") {
49  return ublox_msgs::CfgNAV5::DYN_MODEL_STATIONARY;
50  } else if(lower == "pedestrian") {
51  return ublox_msgs::CfgNAV5::DYN_MODEL_PEDESTRIAN;
52  } else if(lower == "automotive") {
53  return ublox_msgs::CfgNAV5::DYN_MODEL_AUTOMOTIVE;
54  } else if(lower == "sea") {
55  return ublox_msgs::CfgNAV5::DYN_MODEL_SEA;
56  } else if(lower == "airborne1") {
57  return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_1G;
58  } else if(lower == "airborne2") {
59  return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_2G;
60  } else if(lower == "airborne4") {
61  return ublox_msgs::CfgNAV5::DYN_MODEL_AIRBORNE_4G;
62  } else if(lower == "wristwatch") {
63  return ublox_msgs::CfgNAV5::DYN_MODEL_WRIST_WATCH;
64  } else if(lower == "bike") {
65  return ublox_msgs::CfgNAV5::DYN_MODEL_BIKE;
66  }
67 
68  throw std::runtime_error("Invalid settings: " + lower +
69  " is not a valid dynamic model.");
70 }
71 
72 uint8_t ublox_node::fixModeFromString(const std::string& mode) {
73  std::string lower = mode;
74  std::transform(lower.begin(), lower.end(), lower.begin(), ::tolower);
75  if (lower == "2d") {
76  return ublox_msgs::CfgNAV5::FIX_MODE_2D_ONLY;
77  } else if (lower == "3d") {
78  return ublox_msgs::CfgNAV5::FIX_MODE_3D_ONLY;
79  } else if (lower == "auto") {
80  return ublox_msgs::CfgNAV5::FIX_MODE_AUTO;
81  }
82 
83  throw std::runtime_error("Invalid settings: " + mode +
84  " is not a valid fix mode.");
85 }
86 
87 //
88 // u-blox ROS Node
89 //
91  initialize();
92 }
93 
95  int ublox_version;
96  if (protocol_version_ < 14) {
97  components_.push_back(ComponentPtr(new UbloxFirmware6));
98  ublox_version = 6;
99  } else if (protocol_version_ >= 14 && protocol_version_ <= 15) {
100  components_.push_back(ComponentPtr(new UbloxFirmware7));
101  ublox_version = 7;
102  } else if (protocol_version_ > 15 && protocol_version_ <= 23) {
103  components_.push_back(ComponentPtr(new UbloxFirmware8));
104  ublox_version = 8;
105  } else {
106  components_.push_back(ComponentPtr(new UbloxFirmware9));
107  ublox_version = 9;
108  }
109 
110  ROS_INFO("U-Blox Firmware Version: %d", ublox_version);
111 }
112 
113 
114 void UbloxNode::addProductInterface(std::string product_category,
115  std::string ref_rov) {
116  if (product_category.compare("HPG") == 0 && ref_rov.compare("REF") == 0)
117  components_.push_back(ComponentPtr(new HpgRefProduct));
118  else if (product_category.compare("HPG") == 0 && ref_rov.compare("ROV") == 0)
119  components_.push_back(ComponentPtr(new HpgRovProduct));
120  else if (product_category.compare("HPG") == 0)
121  components_.push_back(ComponentPtr(new HpPosRecProduct));
122  else if (product_category.compare("TIM") == 0)
123  components_.push_back(ComponentPtr(new TimProduct));
124  else if (product_category.compare("ADR") == 0 ||
125  product_category.compare("UDR") == 0)
127  else if (product_category.compare("FTS") == 0)
128  components_.push_back(ComponentPtr(new FtsProduct));
129  else if(product_category.compare("SPG") != 0)
130  ROS_WARN("Product category %s %s from MonVER message not recognized %s",
131  product_category.c_str(), ref_rov.c_str(),
132  "options are HPG REF, HPG ROV, HPG #.#, TIM, ADR, UDR, FTS, SPG");
133 }
134 
136  nh->param("device", device_, std::string("/dev/ttyACM0"));
137  nh->param("frame_id", frame_id, std::string("gps"));
138 
139  // Save configuration parameters
140  getRosUint("load/mask", load_.loadMask, 0);
141  getRosUint("load/device", load_.deviceMask, 0);
142  getRosUint("save/mask", save_.saveMask, 0);
143  getRosUint("save/device", save_.deviceMask, 0);
144 
145  // UART 1 params
146  getRosUint("uart1/baudrate", baudrate_, 9600);
147  getRosUint("uart1/in", uart_in_, ublox_msgs::CfgPRT::PROTO_UBX
148  | ublox_msgs::CfgPRT::PROTO_NMEA
149  | ublox_msgs::CfgPRT::PROTO_RTCM);
150  getRosUint("uart1/out", uart_out_, ublox_msgs::CfgPRT::PROTO_UBX);
151  // USB params
152  set_usb_ = false;
153  if (nh->hasParam("usb/in") || nh->hasParam("usb/out")) {
154  set_usb_ = true;
155  if(!getRosUint("usb/in", usb_in_)) {
156  throw std::runtime_error(std::string("usb/out is set, therefore ") +
157  "usb/in must be set");
158  }
159  if(!getRosUint("usb/out", usb_out_)) {
160  throw std::runtime_error(std::string("usb/in is set, therefore ") +
161  "usb/out must be set");
162  }
163  getRosUint("usb/tx_ready", usb_tx_, 0);
164  }
165  // Measurement rate params
166  nh->param("rate", rate_, 4.0); // in Hz
167  getRosUint("nav_rate", nav_rate, 1); // # of measurement rate cycles
168  // RTCM params
169  getRosUint("rtcm/ids", rtcm_ids); // RTCM output message IDs
170  getRosUint("rtcm/rates", rtcm_rates); // RTCM output message rates
171  // PPP: Advanced Setting
172  nh->param("enable_ppp", enable_ppp_, false);
173  // SBAS params, only for some devices
174  nh->param("sbas", enable_sbas_, false);
175  getRosUint("sbas/max", max_sbas_, 0); // Maximum number of SBAS channels
176  getRosUint("sbas/usage", sbas_usage_, 0);
177  nh->param("dynamic_model", dynamic_model_, std::string("portable"));
178  nh->param("fix_mode", fix_mode_, std::string("auto"));
179  getRosUint("dr_limit", dr_limit_, 0); // Dead reckoning limit
180 
181  if (enable_ppp_)
182  ROS_WARN("Warning: PPP is enabled - this is an expert setting.");
183 
184  checkMin(rate_, 0, "rate");
185 
186  if(rtcm_ids.size() != rtcm_rates.size())
187  throw std::runtime_error(std::string("Invalid settings: size of rtcm_ids") +
188  " must match size of rtcm_rates");
189 
192 
193  nh->param("dat/set", set_dat_, false);
194  if(set_dat_) {
195  std::vector<float> shift, rot;
196  if (!nh->getParam("dat/majA", cfg_dat_.majA)
197  || nh->getParam("dat/flat", cfg_dat_.flat)
198  || nh->getParam("dat/shift", shift)
199  || nh->getParam("dat/rot", rot)
200  || nh->getParam("dat/scale", cfg_dat_.scale))
201  throw std::runtime_error(std::string("dat/set is true, therefore ") +
202  "dat/majA, dat/flat, dat/shift, dat/rot, & dat/scale must be set");
203  if(shift.size() != 3 || rot.size() != 3)
204  throw std::runtime_error(std::string("size of dat/shift & dat/rot ") +
205  "must be 3");
206  checkRange(cfg_dat_.majA, 6300000.0, 6500000.0, "dat/majA");
207  checkRange(cfg_dat_.flat, 0.0, 500.0, "dat/flat");
208 
209  checkRange(shift, 0.0, 500.0, "dat/shift");
210  cfg_dat_.dX = shift[0];
211  cfg_dat_.dY = shift[1];
212  cfg_dat_.dZ = shift[2];
213 
214  checkRange(rot, -5000.0, 5000.0, "dat/rot");
215  cfg_dat_.rotX = rot[0];
216  cfg_dat_.rotY = rot[1];
217  cfg_dat_.rotZ = rot[2];
218 
219  checkRange(cfg_dat_.scale, 0.0, 50.0, "scale");
220  }
221 
222  // measurement period [ms]
223  meas_rate = 1000 / rate_;
224 
225  // activate/deactivate any config
226  nh->param("config_on_startup", config_on_startup_flag_, true);
227 
228  // raw data stream logging
230 }
231 
233  static std::vector<uint8_t> payload(1, 1);
234  if (enabled["aid_alm"])
236  if (enabled["aid_eph"])
238  if (enabled["aid_hui"])
240 
241  payload[0]++;
242  if (payload[0] > 32) {
243  payload[0] = 1;
244  }
245 }
246 
247 void UbloxNode::printInf(const ublox_msgs::Inf &m, uint8_t id) {
249  ROS_ERROR_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
250  else if (id == ublox_msgs::Message::INF::WARNING)
251  ROS_WARN_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
252  else if (id == ublox_msgs::Message::INF::DEBUG)
253  ROS_DEBUG_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
254  else
255  ROS_INFO_STREAM("INF: " << std::string(m.str.begin(), m.str.end()));
256 }
257 
259  ROS_DEBUG("Subscribing to U-Blox messages");
260  // subscribe messages
261  nh->param("publish/all", enabled["all"], false);
262  nh->param("inf/all", enabled["inf"], true);
263  nh->param("publish/nav/all", enabled["nav"], enabled["all"]);
264  nh->param("publish/rxm/all", enabled["rxm"], enabled["all"]);
265  nh->param("publish/aid/all", enabled["aid"], enabled["all"]);
266  nh->param("publish/mon/all", enabled["mon"], enabled["all"]);
267 
268  // Nav Messages
269  nh->param("publish/nav/status", enabled["nav_status"], enabled["nav"]);
270  if (enabled["nav_status"])
271  gps.subscribe<ublox_msgs::NavSTATUS>(boost::bind(
272  publish<ublox_msgs::NavSTATUS>, _1, "navstatus"), kSubscribeRate);
273 
274  nh->param("publish/nav/posecef", enabled["nav_posecef"], enabled["nav"]);
275  if (enabled["nav_posecef"])
276  gps.subscribe<ublox_msgs::NavPOSECEF>(boost::bind(
277  publish<ublox_msgs::NavPOSECEF>, _1, "navposecef"), kSubscribeRate);
278 
279  nh->param("publish/nav/clock", enabled["nav_clock"], enabled["nav"]);
280  if (enabled["nav_clock"])
281  gps.subscribe<ublox_msgs::NavCLOCK>(boost::bind(
282  publish<ublox_msgs::NavCLOCK>, _1, "navclock"), kSubscribeRate);
283 
284  // INF messages
285  nh->param("inf/debug", enabled["inf_debug"], false);
286  if (enabled["inf_debug"])
287  gps.subscribeId<ublox_msgs::Inf>(
288  boost::bind(&UbloxNode::printInf, this, _1,
291 
292  nh->param("inf/error", enabled["inf_error"], enabled["inf"]);
293  if (enabled["inf_error"])
294  gps.subscribeId<ublox_msgs::Inf>(
295  boost::bind(&UbloxNode::printInf, this, _1,
298 
299  nh->param("inf/notice", enabled["inf_notice"], enabled["inf"]);
300  if (enabled["inf_notice"])
301  gps.subscribeId<ublox_msgs::Inf>(
302  boost::bind(&UbloxNode::printInf, this, _1,
305 
306  nh->param("inf/test", enabled["inf_test"], enabled["inf"]);
307  if (enabled["inf_test"])
308  gps.subscribeId<ublox_msgs::Inf>(
309  boost::bind(&UbloxNode::printInf, this, _1,
312 
313  nh->param("inf/warning", enabled["inf_warning"], enabled["inf"]);
314  if (enabled["inf_warning"])
315  gps.subscribeId<ublox_msgs::Inf>(
316  boost::bind(&UbloxNode::printInf, this, _1,
319 
320  // AID messages
321  nh->param("publish/aid/alm", enabled["aid_alm"], enabled["aid"]);
322  if (enabled["aid_alm"])
323  gps.subscribe<ublox_msgs::AidALM>(boost::bind(
324  publish<ublox_msgs::AidALM>, _1, "aidalm"), kSubscribeRate);
325 
326  nh->param("publish/aid/eph", enabled["aid_eph"], enabled["aid"]);
327  if (enabled["aid_eph"])
328  gps.subscribe<ublox_msgs::AidEPH>(boost::bind(
329  publish<ublox_msgs::AidEPH>, _1, "aideph"), kSubscribeRate);
330 
331  nh->param("publish/aid/hui", enabled["aid_hui"], enabled["aid"]);
332  if (enabled["aid_hui"])
333  gps.subscribe<ublox_msgs::AidHUI>(boost::bind(
334  publish<ublox_msgs::AidHUI>, _1, "aidhui"), kSubscribeRate);
335 
336  for(int i = 0; i < components_.size(); i++)
337  components_[i]->subscribe();
338 }
339 
341  if (!nh->hasParam("diagnostic_period"))
342  nh->setParam("diagnostic_period", kDiagnosticPeriod);
343 
345  updater->setHardwareID("ublox");
346 
347  // configure diagnostic updater for frequency
348  freq_diag.reset(new FixDiagnostic(std::string("fix"), kFixFreqTol,
350  for(int i = 0; i < components_.size(); i++)
352 }
353 
354 
356  ublox_msgs::MonVER monVer;
357  if (!gps.poll(monVer))
358  throw std::runtime_error("Failed to poll MonVER & set relevant settings");
359 
360  ROS_DEBUG("%s, HW VER: %s", monVer.swVersion.c_array(),
361  monVer.hwVersion.c_array());
362  // Convert extension to vector of strings
363  std::vector<std::string> extension;
364  extension.reserve(monVer.extension.size());
365  for(std::size_t i = 0; i < monVer.extension.size(); ++i) {
366  ROS_DEBUG("%s", monVer.extension[i].field.c_array());
367  // Find the end of the string (null character)
368  unsigned char* end = std::find(monVer.extension[i].field.begin(),
369  monVer.extension[i].field.end(), '\0');
370  extension.push_back(std::string(monVer.extension[i].field.begin(), end));
371  }
372 
373  // Get the protocol version
374  for(std::size_t i = 0; i < extension.size(); ++i) {
375  std::size_t found = extension[i].find("PROTVER");
376  if (found != std::string::npos) {
377  protocol_version_ = ::atof(
378  extension[i].substr(8, extension[i].size()-8).c_str());
379  break;
380  }
381  }
382  if (protocol_version_ == 0)
383  ROS_WARN("Failed to parse MonVER and determine protocol version. %s",
384  "Defaulting to firmware version 6.");
386 
387  if(protocol_version_ < 18) {
388  // Final line contains supported GNSS delimited by ;
389  std::vector<std::string> strs;
390  if(extension.size() > 0)
391  boost::split(strs, extension[extension.size()-1], boost::is_any_of(";"));
392  for(size_t i = 0; i < strs.size(); i++)
393  supported.insert(strs[i]);
394  } else {
395  for(std::size_t i = 0; i < extension.size(); ++i) {
396  std::vector<std::string> strs;
397  // Up to 2nd to last line
398  if(i <= extension.size() - 2) {
399  boost::split(strs, extension[i], boost::is_any_of("="));
400  if(strs.size() > 1) {
401  if (strs[0].compare(std::string("FWVER")) == 0) {
402  if(strs[1].length() > 8)
403  addProductInterface(strs[1].substr(0, 3), strs[1].substr(8, 10));
404  else
405  addProductInterface(strs[1].substr(0, 3));
406  continue;
407  }
408  }
409  }
410  // Last 1-2 lines contain supported GNSS
411  if(i >= extension.size() - 2) {
412  boost::split(strs, extension[i], boost::is_any_of(";"));
413  for(size_t i = 0; i < strs.size(); i++)
414  supported.insert(strs[i]);
415  }
416  }
417  }
418 }
419 
421  try {
422  if (!gps.isInitialized())
423  throw std::runtime_error("Failed to initialize.");
424  if (load_.loadMask != 0) {
425  ROS_DEBUG("Loading u-blox configuration from memory. %u", load_.loadMask);
426  if (!gps.configure(load_))
427  throw std::runtime_error(std::string("Failed to load configuration ") +
428  "from memory");
429  if (load_.loadMask & load_.MASK_IO_PORT) {
430  ROS_DEBUG("Loaded I/O configuration from memory, resetting serial %s",
431  "communications.");
432  boost::posix_time::seconds wait(kResetWait);
433  gps.reset(wait);
434  if (!gps.isConfigured())
435  throw std::runtime_error(std::string("Failed to reset serial I/O") +
436  "after loading I/O configurations from device memory.");
437  }
438  }
439 
441  if (set_usb_) {
443  }
444  if (!gps.configRate(meas_rate, nav_rate)) {
445  std::stringstream ss;
446  ss << "Failed to set measurement rate to " << meas_rate
447  << "ms and navigation rate to " << nav_rate;
448  throw std::runtime_error(ss.str());
449  }
450  // If device doesn't have SBAS, will receive NACK (causes exception)
451  if(supportsGnss("SBAS")) {
453  throw std::runtime_error(std::string("Failed to ") +
454  ((enable_sbas_) ? "enable" : "disable") +
455  " SBAS.");
456  }
457  }
459  throw std::runtime_error(std::string("Failed to ") +
460  ((enable_ppp_) ? "enable" : "disable")
461  + " PPP.");
463  throw std::runtime_error("Failed to set model: " + dynamic_model_ + ".");
464  if (!gps.setFixMode(fmode_))
465  throw std::runtime_error("Failed to set fix mode: " + fix_mode_ + ".");
467  std::stringstream ss;
468  ss << "Failed to set dead reckoning limit: " << dr_limit_ << ".";
469  throw std::runtime_error(ss.str());
470  }
471  if (set_dat_ && !gps.configure(cfg_dat_))
472  throw std::runtime_error("Failed to set user-defined datum.");
473  // Configure each component
474  for (int i = 0; i < components_.size(); i++) {
475  if(!components_[i]->configureUblox())
476  return false;
477  }
478  }
479  if (save_.saveMask != 0) {
480  ROS_DEBUG("Saving the u-blox configuration, mask %u, device %u",
481  save_.saveMask, save_.deviceMask);
482  if(!gps.configure(save_))
483  ROS_ERROR("u-blox unable to save configuration to non-volatile memory");
484  }
485  } catch (std::exception& e) {
486  ROS_FATAL("Error configuring u-blox: %s", e.what());
487  return false;
488  }
489  return true;
490 }
491 
493  ublox_msgs::CfgINF msg;
494  // Subscribe to UBX INF messages
495  ublox_msgs::CfgINF_Block block;
496  block.protocolID = block.PROTOCOL_ID_UBX;
497  // Enable desired INF messages on each UBX port
498  uint8_t mask = (enabled["inf_error"] ? block.INF_MSG_ERROR : 0) |
499  (enabled["inf_warning"] ? block.INF_MSG_WARNING : 0) |
500  (enabled["inf_notice"] ? block.INF_MSG_NOTICE : 0) |
501  (enabled["inf_test"] ? block.INF_MSG_TEST : 0) |
502  (enabled["inf_debug"] ? block.INF_MSG_DEBUG : 0);
503  for (int i = 0; i < block.infMsgMask.size(); i++)
504  block.infMsgMask[i] = mask;
505 
506  msg.blocks.push_back(block);
507 
508  // IF NMEA is enabled
509  if (uart_in_ & ublox_msgs::CfgPRT::PROTO_NMEA) {
510  ublox_msgs::CfgINF_Block block;
511  block.protocolID = block.PROTOCOL_ID_NMEA;
512  // Enable desired INF messages on each NMEA port
513  for (int i = 0; i < block.infMsgMask.size(); i++)
514  block.infMsgMask[i] = mask;
515  msg.blocks.push_back(block);
516  }
517 
518  ROS_DEBUG("Configuring INF messages");
519  if (!gps.configure(msg))
520  ROS_WARN("Failed to configure INF messages");
521 }
522 
525 
526  boost::smatch match;
527  if (boost::regex_match(device_, match,
528  boost::regex("(tcp|udp)://(.+):(\\d+)"))) {
529  std::string proto(match[1]);
530  if (proto == "tcp") {
531  std::string host(match[2]);
532  std::string port(match[3]);
533  ROS_INFO("Connecting to %s://%s:%s ...", proto.c_str(), host.c_str(),
534  port.c_str());
535  gps.initializeTcp(host, port);
536  } else {
537  throw std::runtime_error("Protocol '" + proto + "' is unsupported");
538  }
539  } else {
541  }
542 
543  // raw data stream logging
544  if (rawDataStreamPa_.isEnabled()) {
546  boost::bind(&RawDataStreamPa::ubloxCallback,&rawDataStreamPa_, _1, _2));
548  }
549 }
550 
552  // Params must be set before initializing IO
553  getRosParams();
554  initializeIo();
555  // Must process Mon VER before setting firmware/hardware params
556  processMonVer();
557  if(protocol_version_ <= 14) {
558  if(nh->param("raw_data", false))
559  components_.push_back(ComponentPtr(new RawDataProduct));
560  }
561  // Must set firmware & hardware params before initializing diagnostics
562  for (int i = 0; i < components_.size(); i++)
564  // Do this last
566 
567  if (configureUblox()) {
568  ROS_INFO("U-Blox configured successfully.");
569  // Subscribe to all U-Blox messages
570  subscribe();
571  // Configure INF messages (needs INF params, call after subscribing)
572  configureInf();
573 
574  ros::Timer poller;
575  poller = nh->createTimer(ros::Duration(kPollDuration),
577  this);
578  poller.start();
579  ros::spin();
580  }
581  shutdown();
582 }
583 
585  if (gps.isInitialized()) {
586  gps.close();
587  ROS_INFO("Closed connection to %s.", device_.c_str());
588  }
589 }
590 
591 //
592 // U-Blox Firmware (all versions)
593 //
595  updater->add("fix", this, &UbloxFirmware::fixDiagnostic);
596  updater->force_update();
597 }
598 
599 //
600 // U-Blox Firmware Version 6
601 //
603 
605  // Fix Service type, used when publishing fix status messages
606  fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS;
607 
608  nh->param("nmea/set", set_nmea_, false);
609  if (set_nmea_) {
610  bool compat, consider;
611 
612  if (!getRosUint("nmea/version", cfg_nmea_.version))
613  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
614  "true, therefore nmea/version must be set");
615  if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
616  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
617  "true, therefore nmea/num_sv must be set");
618  if (!nh->getParam("nmea/compat", compat))
619  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
620  "true, therefore nmea/compat must be set");
621  if (!nh->getParam("nmea/consider", consider))
622  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
623  "true, therefore nmea/consider must be set");
624 
625  // set flags
626  cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
627  cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
628 
629  // set filter
630  bool temp;
631  nh->param("nmea/filter/pos", temp, false);
632  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
633  nh->param("nmea/filter/msk_pos", temp, false);
634  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
635  nh->param("nmea/filter/time", temp, false);
636  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
637  nh->param("nmea/filter/date", temp, false);
638  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
639  nh->param("nmea/filter/sbas", temp, false);
640  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_SBAS_FILT : 0;
641  nh->param("nmea/filter/track", temp, false);
642  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
643  }
644 }
645 
647  ROS_WARN("ublox_version < 7, ignoring GNSS settings");
648 
649  if (set_nmea_ && !gps.configure(cfg_nmea_))
650  throw std::runtime_error("Failed to configure NMEA");
651 
652  return true;
653 }
654 
656  // Whether or not to publish Nav POS LLH (always subscribes)
657  nh->param("publish/nav/posllh", enabled["nav_posllh"], enabled["nav"]);
658  nh->param("publish/nav/sol", enabled["nav_sol"], enabled["nav"]);
659  nh->param("publish/nav/velned", enabled["nav_velned"], enabled["nav"]);
660 
661  // Always subscribes to these messages, but may not publish to ROS topic
662  // Subscribe to Nav POSLLH
663  gps.subscribe<ublox_msgs::NavPOSLLH>(boost::bind(
665  gps.subscribe<ublox_msgs::NavSOL>(boost::bind(
666  // Subscribe to Nav SOL
668  // Subscribe to Nav VELNED
669  gps.subscribe<ublox_msgs::NavVELNED>(boost::bind(
671 
672  // Subscribe to Nav SVINFO
673  nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
674  if (enabled["nav_svinfo"])
675  gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
676  publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"),
678 
679  // Subscribe to Mon HW
680  nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
681  if (enabled["mon_hw"])
682  gps.subscribe<ublox_msgs::MonHW6>(boost::bind(
683  publish<ublox_msgs::MonHW6>, _1, "monhw"), kSubscribeRate);
684 }
685 
688  // Set the diagnostic level based on the fix status
689  if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_DEAD_RECKONING_ONLY) {
690  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
691  stat.message = "Dead reckoning only";
692  } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_2D_FIX) {
693  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
694  stat.message = "2D fix";
695  } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_3D_FIX) {
696  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
697  stat.message = "3D fix";
698  } else if (last_nav_sol_.gpsFix ==
699  ublox_msgs::NavSOL::GPS_GPS_DEAD_RECKONING_COMBINED) {
700  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
701  stat.message = "GPS and dead reckoning combined";
702  } else if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_TIME_ONLY_FIX) {
703  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
704  stat.message = "Time fix only";
705  }
706  // If fix is not ok (within DOP & Accuracy Masks), raise the diagnostic level
707  if (!(last_nav_sol_.flags & ublox_msgs::NavSOL::FLAGS_GPS_FIX_OK)) {
708  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
709  stat.message += ", fix not ok";
710  }
711  // Raise diagnostic level to error if no fix
712  if (last_nav_sol_.gpsFix == ublox_msgs::NavSOL::GPS_NO_FIX) {
713  stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
714  stat.message = "No fix";
715  }
716 
717  // Add last fix position
718  stat.add("iTOW [ms]", last_nav_pos_.iTOW);
719  stat.add("Latitude [deg]", last_nav_pos_.lat * 1e-7);
720  stat.add("Longitude [deg]", last_nav_pos_.lon * 1e-7);
721  stat.add("Altitude [m]", last_nav_pos_.height * 1e-3);
722  stat.add("Height above MSL [m]", last_nav_pos_.hMSL * 1e-3);
723  stat.add("Horizontal Accuracy [m]", last_nav_pos_.hAcc * 1e-3);
724  stat.add("Vertical Accuracy [m]", last_nav_pos_.vAcc * 1e-3);
725  stat.add("# SVs used", (int)last_nav_sol_.numSV);
726 }
727 
728 void UbloxFirmware6::callbackNavPosLlh(const ublox_msgs::NavPOSLLH& m) {
729  if(enabled["nav_posllh"]) {
730  static ros::Publisher publisher =
731  nh->advertise<ublox_msgs::NavPOSLLH>("navposllh", kROSQueueSize);
732  publisher.publish(m);
733  }
734 
735  // Position message
736  static ros::Publisher fixPublisher =
737  nh->advertise<sensor_msgs::NavSatFix>("fix", kROSQueueSize);
738  if (m.iTOW == last_nav_vel_.iTOW)
739  fix_.header.stamp = velocity_.header.stamp; // use last timestamp
740  else
741  fix_.header.stamp = ros::Time::now(); // new timestamp
742 
743  fix_.header.frame_id = frame_id;
744  fix_.latitude = m.lat * 1e-7;
745  fix_.longitude = m.lon * 1e-7;
746  fix_.altitude = m.height * 1e-3;
747 
748  if (last_nav_sol_.gpsFix >= last_nav_sol_.GPS_2D_FIX)
749  fix_.status.status = fix_.status.STATUS_FIX;
750  else
751  fix_.status.status = fix_.status.STATUS_NO_FIX;
752 
753  // Convert from mm to m
754  const double varH = pow(m.hAcc / 1000.0, 2);
755  const double varV = pow(m.vAcc / 1000.0, 2);
756 
757  fix_.position_covariance[0] = varH;
758  fix_.position_covariance[4] = varH;
759  fix_.position_covariance[8] = varV;
760  fix_.position_covariance_type =
761  sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
762 
763  fix_.status.service = fix_.status.SERVICE_GPS;
764  fixPublisher.publish(fix_);
765  last_nav_pos_ = m;
766  // update diagnostics
767  freq_diag->diagnostic->tick(fix_.header.stamp);
768  updater->update();
769 }
770 
771 void UbloxFirmware6::callbackNavVelNed(const ublox_msgs::NavVELNED& m) {
772  if(enabled["nav_velned"]) {
773  static ros::Publisher publisher =
774  nh->advertise<ublox_msgs::NavVELNED>("navvelned", kROSQueueSize);
775  publisher.publish(m);
776  }
777 
778  // Example geometry message
779  static ros::Publisher velocityPublisher =
780  nh->advertise<geometry_msgs::TwistWithCovarianceStamped>("fix_velocity",
781  kROSQueueSize);
782  if (m.iTOW == last_nav_pos_.iTOW)
783  velocity_.header.stamp = fix_.header.stamp; // same time as last navposllh
784  else
785  velocity_.header.stamp = ros::Time::now(); // create a new timestamp
786  velocity_.header.frame_id = frame_id;
787 
788  // convert to XYZ linear velocity
789  velocity_.twist.twist.linear.x = m.velE / 100.0;
790  velocity_.twist.twist.linear.y = m.velN / 100.0;
791  velocity_.twist.twist.linear.z = -m.velD / 100.0;
792 
793  const double varSpeed = pow(m.sAcc / 100.0, 2);
794 
795  const int cols = 6;
796  velocity_.twist.covariance[cols * 0 + 0] = varSpeed;
797  velocity_.twist.covariance[cols * 1 + 1] = varSpeed;
798  velocity_.twist.covariance[cols * 2 + 2] = varSpeed;
799  velocity_.twist.covariance[cols * 3 + 3] = -1; // angular rate unsupported
800 
801  velocityPublisher.publish(velocity_);
802  last_nav_vel_ = m;
803 }
804 
805 void UbloxFirmware6::callbackNavSol(const ublox_msgs::NavSOL& m) {
806  if(enabled["nav_sol"]) {
807  static ros::Publisher publisher =
808  nh->advertise<ublox_msgs::NavSOL>("navsol", kROSQueueSize);
809  publisher.publish(m);
810  }
811  last_nav_sol_ = m;
812 }
813 
814 //
815 // Ublox Firmware Version 7
816 //
818 
820  //
821  // GNSS configuration
822  //
823  // GNSS enable/disable
824  nh->param("gnss/gps", enable_gps_, true);
825  nh->param("gnss/glonass", enable_glonass_, false);
826  nh->param("gnss/qzss", enable_qzss_, false);
827  getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_,
828  ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
829  nh->param("gnss/sbas", enable_sbas_, false);
830 
831  if(enable_gps_ && !supportsGnss("GPS"))
832  ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by this device");
833  if(enable_glonass_ && !supportsGnss("GLO"))
834  ROS_WARN("gnss/glonass is true, but GLONASS is not %s",
835  "supported by this device");
836  if(enable_qzss_ && !supportsGnss("QZSS"))
837  ROS_WARN("gnss/qzss is true, but QZSS is not supported by this device");
838  if(enable_sbas_ && !supportsGnss("SBAS"))
839  ROS_WARN("gnss/sbas is true, but SBAS is not supported by this device");
840 
841  if(nh->hasParam("gnss/galileo"))
842  ROS_WARN("ublox_version < 8, ignoring Galileo GNSS Settings");
843  if(nh->hasParam("gnss/beidou"))
844  ROS_WARN("ublox_version < 8, ignoring BeiDou Settings");
845  if(nh->hasParam("gnss/imes"))
846  ROS_WARN("ublox_version < 8, ignoring IMES GNSS Settings");
847 
848  // Fix Service type, used when publishing fix status messages
849  fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS
850  + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS;
851 
852  //
853  // NMEA Configuration
854  //
855  nh->param("nmea/set", set_nmea_, false);
856  if (set_nmea_) {
857  bool compat, consider;
858 
859  if (!getRosUint("nmea/version", cfg_nmea_.nmeaVersion))
860  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
861  "true, therefore nmea/version must be set");
862  if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
863  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
864  "true, therefore nmea/num_sv must be set");
865  if (!getRosUint("nmea/sv_numbering", cfg_nmea_.svNumbering))
866  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
867  "true, therefore nmea/sv_numbering must be set");
868  if (!nh->getParam("nmea/compat", compat))
869  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
870  "true, therefore nmea/compat must be set");
871  if (!nh->getParam("nmea/consider", consider))
872  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
873  "true, therefore nmea/consider must be set");
874 
875  // set flags
876  cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
877  cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
878  // set filter
879  bool temp;
880  nh->param("nmea/filter/pos", temp, false);
881  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
882  nh->param("nmea/filter/msk_pos", temp, false);
883  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
884  nh->param("nmea/filter/time", temp, false);
885  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
886  nh->param("nmea/filter/date", temp, false);
887  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
888  nh->param("nmea/filter/gps_only", temp, false);
889  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
890  nh->param("nmea/filter/track", temp, false);
891  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
892  // set gnssToFilter
893  nh->param("nmea/gnssToFilter/gps", temp, false);
894  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
895  nh->param("nmea/gnssToFilter/sbas", temp, false);
896  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
897  nh->param("nmea/gnssToFilter/qzss", temp, false);
898  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
899  nh->param("nmea/gnssToFilter/glonass", temp, false);
900  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
901 
902  getRosUint("nmea/main_talker_id", cfg_nmea_.mainTalkerId);
903  getRosUint("nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
904  }
905 }
906 
909  ublox_msgs::CfgGNSS cfgGNSSRead;
910  if (gps.poll(cfgGNSSRead)) {
911  ROS_DEBUG("Read GNSS config.");
912  ROS_DEBUG("Num. tracking channels in hardware: %i", cfgGNSSRead.numTrkChHw);
913  ROS_DEBUG("Num. tracking channels to use: %i", cfgGNSSRead.numTrkChUse);
914  } else {
915  throw std::runtime_error("Failed to read the GNSS config.");
916  }
917 
918  ublox_msgs::CfgGNSS cfgGNSSWrite;
919  cfgGNSSWrite.numConfigBlocks = 1; // do services one by one
920  cfgGNSSWrite.numTrkChHw = cfgGNSSRead.numTrkChHw;
921  cfgGNSSWrite.numTrkChUse = cfgGNSSRead.numTrkChUse;
922  cfgGNSSWrite.msgVer = 0;
923 
924  // configure GLONASS
925  if(supportsGnss("GLO")) {
926  ublox_msgs::CfgGNSS_Block block;
927  block.gnssId = block.GNSS_ID_GLONASS;
928  block.resTrkCh = block.RES_TRK_CH_GLONASS;
929  block.maxTrkCh = block.MAX_TRK_CH_GLONASS;
930  block.flags = enable_glonass_ ? block.SIG_CFG_GLONASS_L1OF : 0;
931  cfgGNSSWrite.blocks.push_back(block);
932  if (!gps.configure(cfgGNSSWrite)) {
933  throw std::runtime_error(std::string("Failed to ") +
934  ((enable_glonass_) ? "enable" : "disable") +
935  " GLONASS.");
936  }
937  }
938 
939  if(supportsGnss("QZSS")) {
940  // configure QZSS
941  ublox_msgs::CfgGNSS_Block block;
942  block.gnssId = block.GNSS_ID_QZSS;
943  block.resTrkCh = block.RES_TRK_CH_QZSS;
944  block.maxTrkCh = block.MAX_TRK_CH_QZSS;
945  block.flags = enable_qzss_ ? qzss_sig_cfg_ : 0;
946  cfgGNSSWrite.blocks[0] = block;
947  if (!gps.configure(cfgGNSSWrite)) {
948  throw std::runtime_error(std::string("Failed to ") +
949  ((enable_glonass_) ? "enable" : "disable") +
950  " QZSS.");
951  }
952  }
953 
954  if(supportsGnss("SBAS")) {
955  // configure SBAS
956  ublox_msgs::CfgGNSS_Block block;
957  block.gnssId = block.GNSS_ID_SBAS;
958  block.resTrkCh = block.RES_TRK_CH_SBAS;
959  block.maxTrkCh = block.MAX_TRK_CH_SBAS;
960  block.flags = enable_sbas_ ? block.SIG_CFG_SBAS_L1CA : 0;
961  cfgGNSSWrite.blocks[0] = block;
962  if (!gps.configure(cfgGNSSWrite)) {
963  throw std::runtime_error(std::string("Failed to ") +
964  ((enable_sbas_) ? "enable" : "disable") +
965  " SBAS.");
966  }
967  }
968 
969  if(set_nmea_ && !gps.configure(cfg_nmea_))
970  throw std::runtime_error("Failed to configure NMEA");
971 
972  return true;
973 }
974 
976  // Whether to publish Nav PVT messages to a ROS topic
977  nh->param("publish/nav/pvt", enabled["nav_pvt"], enabled["nav"]);
978  // Subscribe to Nav PVT (always does so since fix information is published
979  // from this)
980  gps.subscribe<ublox_msgs::NavPVT7>(boost::bind(
983 
984  // Subscribe to Nav SVINFO
985  nh->param("publish/nav/svinfo", enabled["nav_svinfo"], enabled["nav"]);
986  if (enabled["nav_svinfo"])
987  gps.subscribe<ublox_msgs::NavSVINFO>(boost::bind(
988  publish<ublox_msgs::NavSVINFO>, _1, "navsvinfo"),
990 
991  // Subscribe to Mon HW
992  nh->param("publish/mon_hw", enabled["mon_hw"], enabled["mon"]);
993  if (enabled["mon_hw"])
994  gps.subscribe<ublox_msgs::MonHW>(boost::bind(
995  publish<ublox_msgs::MonHW>, _1, "monhw"), kSubscribeRate);
996 }
997 
998 //
999 // Ublox Version 8
1000 //
1002 
1004  // UPD SOS configuration
1005  nh->param("clear_bbr", clear_bbr_, false);
1006  gps.setSaveOnShutdown(nh->param("save_on_shutdown", false));
1007 
1008  // GNSS enable/disable
1009  nh->param("gnss/gps", enable_gps_, true);
1010  nh->param("gnss/galileo", enable_galileo_, false);
1011  nh->param("gnss/beidou", enable_beidou_, false);
1012  nh->param("gnss/imes", enable_imes_, false);
1013  nh->param("gnss/glonass", enable_glonass_, false);
1014  nh->param("gnss/qzss", enable_qzss_, false);
1015  nh->param("gnss/sbas", enable_sbas_, false);
1016  // QZSS Signal Configuration
1017  getRosUint("gnss/qzss_sig_cfg", qzss_sig_cfg_,
1018  ublox_msgs::CfgGNSS_Block::SIG_CFG_QZSS_L1CA);
1019 
1020  if (enable_gps_ && !supportsGnss("GPS"))
1021  ROS_WARN("gnss/gps is true, but GPS GNSS is not supported by %s",
1022  "this device");
1023  if (enable_glonass_ && !supportsGnss("GLO"))
1024  ROS_WARN("gnss/glonass is true, but GLONASS is not supported by %s",
1025  "this device");
1026  if (enable_galileo_ && !supportsGnss("GAL"))
1027  ROS_WARN("gnss/galileo is true, but Galileo GNSS is not supported %s",
1028  "by this device");
1029  if (enable_beidou_ && !supportsGnss("BDS"))
1030  ROS_WARN("gnss/beidou is true, but Beidou GNSS is not supported %s",
1031  "by this device");
1032  if (enable_imes_ && !supportsGnss("IMES"))
1033  ROS_WARN("gnss/imes is true, but IMES GNSS is not supported by %s",
1034  "this device");
1035  if (enable_qzss_ && !supportsGnss("QZSS"))
1036  ROS_WARN("gnss/qzss is true, but QZSS is not supported by this device");
1037  if (enable_sbas_ && !supportsGnss("SBAS"))
1038  ROS_WARN("gnss/sbas is true, but SBAS is not supported by this device");
1039 
1040  // Fix Service type, used when publishing fix status messages
1041  fix_status_service = sensor_msgs::NavSatStatus::SERVICE_GPS
1042  + (enable_glonass_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GLONASS
1043  + (enable_beidou_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_COMPASS
1044  + (enable_galileo_ ? 1 : 0) * sensor_msgs::NavSatStatus::SERVICE_GALILEO;
1045 
1046  //
1047  // NMEA Configuration
1048  //
1049  nh->param("nmea/set", set_nmea_, false);
1050  if (set_nmea_) {
1051  bool compat, consider;
1052  cfg_nmea_.version = cfg_nmea_.VERSION; // message version
1053 
1054  // Verify that parameters are set
1055  if (!getRosUint("nmea/version", cfg_nmea_.nmeaVersion))
1056  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
1057  "true, therefore nmea/version must be set");
1058  if (!getRosUint("nmea/num_sv", cfg_nmea_.numSV))
1059  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
1060  "true, therefore nmea/num_sv must be set");
1061  if (!getRosUint("nmea/sv_numbering", cfg_nmea_.svNumbering))
1062  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
1063  "true, therefore nmea/sv_numbering must be set");
1064  if (!nh->getParam("nmea/compat", compat))
1065  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
1066  "true, therefore nmea/compat must be set");
1067  if (!nh->getParam("nmea/consider", consider))
1068  throw std::runtime_error(std::string("Invalid settings: nmea/set is ") +
1069  "true, therefore nmea/consider must be set");
1070 
1071  // set flags
1072  cfg_nmea_.flags = compat ? cfg_nmea_.FLAGS_COMPAT : 0;
1073  cfg_nmea_.flags |= consider ? cfg_nmea_.FLAGS_CONSIDER : 0;
1074  bool temp;
1075  nh->param("nmea/limit82", temp, false);
1076  cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_LIMIT82 : 0;
1077  nh->param("nmea/high_prec", temp, false);
1078  cfg_nmea_.flags |= temp ? cfg_nmea_.FLAGS_HIGH_PREC : 0;
1079  // set filter
1080  nh->param("nmea/filter/pos", temp, false);
1081  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_POS : 0;
1082  nh->param("nmea/filter/msk_pos", temp, false);
1083  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_MSK_POS : 0;
1084  nh->param("nmea/filter/time", temp, false);
1085  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TIME : 0;
1086  nh->param("nmea/filter/date", temp, false);
1087  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_DATE : 0;
1088  nh->param("nmea/filter/gps_only", temp, false);
1089  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_GPS_ONLY : 0;
1090  nh->param("nmea/filter/track", temp, false);
1091  cfg_nmea_.filter |= temp ? cfg_nmea_.FILTER_TRACK : 0;
1092  // set gnssToFilter
1093  nh->param("nmea/gnssToFilter/gps", temp, false);
1094  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GPS : 0;
1095  nh->param("nmea/gnssToFilter/sbas", temp, false);
1096  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_SBAS : 0;
1097  nh->param("nmea/gnssToFilter/qzss", temp, false);
1098  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_QZSS : 0;
1099  nh->param("nmea/gnssToFilter/glonass", temp, false);
1100  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_GLONASS : 0;
1101  nh->param("nmea/gnssToFilter/beidou", temp, false);
1102  cfg_nmea_.gnssToFilter |= temp ? cfg_nmea_.GNSS_TO_FILTER_BEIDOU : 0;
1103 
1104  getRosUint("nmea/main_talker_id", cfg_nmea_.mainTalkerId);
1105  getRosUint("nmea/gsv_talker_id", cfg_nmea_.gsvTalkerId);
1106 
1107  std::vector<uint8_t> bdsTalkerId;
1108  getRosUint("nmea/bds_talker_id", bdsTalkerId);
1109  cfg_nmea_.bdsTalkerId[0] = bdsTalkerId[0];
1110  cfg_nmea_.bdsTalkerId[1] = bdsTalkerId[1];
1111  }
1112 }
1113 
1114 
1116  if(clear_bbr_) {
1117  // clear flash memory
1118  if(!gps.clearBbr())
1119  ROS_ERROR("u-blox failed to clear flash memory");
1120  }
1121  //
1122  // Configure the GNSS, only if the configuration is different
1123  //
1124  // First, get the current GNSS configuration
1125  ublox_msgs::CfgGNSS cfg_gnss;
1126  if (gps.poll(cfg_gnss)) {
1127  ROS_DEBUG("Read GNSS config.");
1128  ROS_DEBUG("Num. tracking channels in hardware: %i", cfg_gnss.numTrkChHw);
1129  ROS_DEBUG("Num. tracking channels to use: %i", cfg_gnss.numTrkChUse);
1130  } else {
1131  throw std::runtime_error("Failed to read the GNSS config.");
1132  }
1133 
1134  // Then, check the configuration for each GNSS. If it is different, change it.
1135  bool correct = true;
1136  for (int i = 0; i < cfg_gnss.blocks.size(); i++) {
1137  ublox_msgs::CfgGNSS_Block block = cfg_gnss.blocks[i];
1138  if (block.gnssId == block.GNSS_ID_GPS
1139  && enable_gps_ != (block.flags & block.FLAGS_ENABLE)) {
1140  correct = false;
1141  cfg_gnss.blocks[i].flags =
1142  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_gps_;
1143  ROS_DEBUG("GPS Configuration is different");
1144  } else if (block.gnssId == block.GNSS_ID_SBAS
1145  && enable_sbas_ != (block.flags & block.FLAGS_ENABLE)) {
1146  correct = false;
1147  cfg_gnss.blocks[i].flags =
1148  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_sbas_;
1149  ROS_DEBUG("SBAS Configuration is different");
1150  } else if (block.gnssId == block.GNSS_ID_GALILEO
1151  && enable_galileo_ != (block.flags & block.FLAGS_ENABLE)) {
1152  correct = false;
1153  cfg_gnss.blocks[i].flags =
1154  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_galileo_;
1155  ROS_DEBUG("Galileo GNSS Configuration is different");
1156  } else if (block.gnssId == block.GNSS_ID_BEIDOU
1157  && enable_beidou_ != (block.flags & block.FLAGS_ENABLE)) {
1158  correct = false;
1159  cfg_gnss.blocks[i].flags =
1160  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_beidou_;
1161  ROS_DEBUG("BeiDou Configuration is different");
1162  } else if (block.gnssId == block.GNSS_ID_IMES
1163  && enable_imes_ != (block.flags & block.FLAGS_ENABLE)) {
1164  correct = false;
1165  cfg_gnss.blocks[i].flags =
1166  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_imes_;
1167  } else if (block.gnssId == block.GNSS_ID_QZSS
1168  && (enable_qzss_ != (block.flags & block.FLAGS_ENABLE)
1169  || (enable_qzss_
1170  && qzss_sig_cfg_ != (block.flags & block.FLAGS_SIG_CFG_MASK)))) {
1171  ROS_DEBUG("QZSS Configuration is different %u, %u",
1172  block.flags & block.FLAGS_ENABLE,
1173  enable_qzss_);
1174  correct = false;
1175  ROS_DEBUG("QZSS Configuration: %u", block.flags);
1176  cfg_gnss.blocks[i].flags =
1177  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_qzss_;
1178  ROS_DEBUG("QZSS Configuration: %u", cfg_gnss.blocks[i].flags);
1179  if (enable_qzss_)
1180  // Only change sig cfg if enabling
1181  cfg_gnss.blocks[i].flags |= qzss_sig_cfg_;
1182  } else if (block.gnssId == block.GNSS_ID_GLONASS
1183  && enable_glonass_ != (block.flags & block.FLAGS_ENABLE)) {
1184  correct = false;
1185  cfg_gnss.blocks[i].flags =
1186  (cfg_gnss.blocks[i].flags & ~block.FLAGS_ENABLE) | enable_glonass_;
1187  ROS_DEBUG("GLONASS Configuration is different");
1188  }
1189  }
1190 
1191  // If the GNSS is already configured correctly, do not re-configure GNSS
1192  // since this requires a cold reset
1193  if (correct)
1194  ROS_DEBUG("U-Blox GNSS configuration is correct. GNSS not re-configured.");
1195  else if (!gps.configGnss(cfg_gnss, boost::posix_time::seconds(15)))
1196  throw std::runtime_error(std::string("Failed to cold reset device ") +
1197  "after configuring GNSS");
1198 
1199  //
1200  // NMEA config
1201  //
1202  if (set_nmea_ && !gps.configure(cfg_nmea_))
1203  throw std::runtime_error("Failed to configure NMEA");
1204 
1205  return true;
1206 }
1207 
1209  // Whether to publish Nav PVT messages
1210  nh->param("publish/nav/pvt", enabled["nav_pvt"], enabled["nav"]);
1211  // Subscribe to Nav PVT
1212  gps.subscribe<ublox_msgs::NavPVT>(
1213  boost::bind(&UbloxFirmware7Plus::callbackNavPvt, this, _1), kSubscribeRate);
1214 
1215  // Subscribe to Nav SAT messages
1216  nh->param("publish/nav/sat", enabled["nav_sat"], enabled["nav"]);
1217  if (enabled["nav_sat"])
1218  gps.subscribe<ublox_msgs::NavSAT>(boost::bind(
1219  publish<ublox_msgs::NavSAT>, _1, "navsat"), kNavSvInfoSubscribeRate);
1220 
1221  // Subscribe to Mon HW
1222  nh->param("publish/mon/hw", enabled["mon_hw"], enabled["mon"]);
1223  if (enabled["mon_hw"])
1224  gps.subscribe<ublox_msgs::MonHW>(boost::bind(
1225  publish<ublox_msgs::MonHW>, _1, "monhw"), kSubscribeRate);
1226 
1227  // Subscribe to RTCM messages
1228  nh->param("publish/rxm/rtcm", enabled["rxm_rtcm"], enabled["rxm"]);
1229  if (enabled["rxm_rtcm"])
1230  gps.subscribe<ublox_msgs::RxmRTCM>(boost::bind(
1231  publish<ublox_msgs::RxmRTCM>, _1, "rxmrtcm"), kSubscribeRate);
1232 }
1233 
1234 //
1235 // Raw Data Products
1236 //
1238  // Defaults to true instead of to all
1239  nh->param("publish/rxm/all", enabled["rxm"], true);
1240 
1241  // Subscribe to RXM Raw
1242  nh->param("publish/rxm/raw", enabled["rxm_raw"], enabled["rxm"]);
1243  if (enabled["rxm_raw"])
1244  gps.subscribe<ublox_msgs::RxmRAW>(boost::bind(
1245  publish<ublox_msgs::RxmRAW>, _1, "rxmraw"), kSubscribeRate);
1246 
1247  // Subscribe to RXM SFRB
1248  nh->param("publish/rxm/sfrb", enabled["rxm_sfrb"], enabled["rxm"]);
1249  if (enabled["rxm_sfrb"])
1250  gps.subscribe<ublox_msgs::RxmSFRB>(boost::bind(
1251  publish<ublox_msgs::RxmSFRB>, _1, "rxmsfrb"), kSubscribeRate);
1252 
1253  // Subscribe to RXM EPH
1254  nh->param("publish/rxm/eph", enabled["rxm_eph"], enabled["rxm"]);
1255  if (enabled["rxm_eph"])
1256  gps.subscribe<ublox_msgs::RxmEPH>(boost::bind(
1257  publish<ublox_msgs::RxmEPH>, _1, "rxmeph"), kSubscribeRate);
1258 
1259  // Subscribe to RXM ALM
1260  nh->param("publish/rxm/almRaw", enabled["rxm_alm"], enabled["rxm"]);
1261  if (enabled["rxm_alm"])
1262  gps.subscribe<ublox_msgs::RxmALM>(boost::bind(
1263  publish<ublox_msgs::RxmALM>, _1, "rxmalm"), kSubscribeRate);
1264 }
1265 
1267  if (enabled["rxm_raw"])
1268  freq_diagnostics_.push_back(boost::shared_ptr<UbloxTopicDiagnostic>(
1269  new UbloxTopicDiagnostic("rxmraw", kRtcmFreqTol, kRtcmFreqWindow)));
1270  if (enabled["rxm_sfrb"])
1271  freq_diagnostics_.push_back(boost::shared_ptr<UbloxTopicDiagnostic>(
1272  new UbloxTopicDiagnostic("rxmsfrb", kRtcmFreqTol, kRtcmFreqWindow)));
1273  if (enabled["rxm_eph"])
1274  freq_diagnostics_.push_back(boost::shared_ptr<UbloxTopicDiagnostic>(
1275  new UbloxTopicDiagnostic("rxmeph", kRtcmFreqTol, kRtcmFreqWindow)));
1276  if (enabled["rxm_alm"])
1277  freq_diagnostics_.push_back(boost::shared_ptr<UbloxTopicDiagnostic>(
1278  new UbloxTopicDiagnostic("rxmalm", kRtcmFreqTol, kRtcmFreqWindow)));
1279 }
1280 
1281 AdrUdrProduct::AdrUdrProduct(float protocol_version)
1282  : protocol_version_(protocol_version)
1283 {}
1284 
1285 //
1286 // u-blox ADR devices, partially implemented
1287 //
1289  nh->param("use_adr", use_adr_, true);
1290  // Check the nav rate
1291  float nav_rate_hz = 1000 / (meas_rate * nav_rate);
1292  if(nav_rate_hz != 1)
1293  ROS_WARN("Nav Rate recommended to be 1 Hz");
1294 }
1295 
1298  throw std::runtime_error(std::string("Failed to ")
1299  + (use_adr_ ? "enable" : "disable") + "use_adr");
1300  return true;
1301 }
1302 
1304  nh->param("publish/esf/all", enabled["esf"], true);
1305 
1306  // Subscribe to NAV ATT messages
1307  nh->param("publish/nav/att", enabled["nav_att"], enabled["nav"]);
1308  if (enabled["nav_att"])
1309  gps.subscribe<ublox_msgs::NavATT>(boost::bind(
1310  publish<ublox_msgs::NavATT>, _1, "navatt"), kSubscribeRate);
1311 
1312  // Subscribe to ESF INS messages
1313  nh->param("publish/esf/ins", enabled["esf_ins"], enabled["esf"]);
1314  if (enabled["esf_ins"])
1315  gps.subscribe<ublox_msgs::EsfINS>(boost::bind(
1316  publish<ublox_msgs::EsfINS>, _1, "esfins"), kSubscribeRate);
1317 
1318  // Subscribe to ESF Meas messages
1319  nh->param("publish/esf/meas", enabled["esf_meas"], enabled["esf"]);
1320  if (enabled["esf_meas"])
1321  gps.subscribe<ublox_msgs::EsfMEAS>(boost::bind(
1322  publish<ublox_msgs::EsfMEAS>, _1, "esfmeas"), kSubscribeRate);
1323  // also publish sensor_msgs::Imu
1324  gps.subscribe<ublox_msgs::EsfMEAS>(boost::bind(
1326 
1327  // Subscribe to ESF Raw messages
1328  nh->param("publish/esf/raw", enabled["esf_raw"], enabled["esf"]);
1329  if (enabled["esf_raw"])
1330  gps.subscribe<ublox_msgs::EsfRAW>(boost::bind(
1331  publish<ublox_msgs::EsfRAW>, _1, "esfraw"), kSubscribeRate);
1332 
1333  // Subscribe to ESF Status messages
1334  nh->param("publish/esf/status", enabled["esf_status"], enabled["esf"]);
1335  if (enabled["esf_status"])
1336  gps.subscribe<ublox_msgs::EsfSTATUS>(boost::bind(
1337  publish<ublox_msgs::EsfSTATUS>, _1, "esfstatus"), kSubscribeRate);
1338 
1339  // Subscribe to HNR PVT messages
1340  nh->param("publish/hnr/pvt", enabled["hnr_pvt"], true);
1341  if (enabled["hnr_pvt"])
1342  gps.subscribe<ublox_msgs::HnrPVT>(boost::bind(
1343  publish<ublox_msgs::HnrPVT>, _1, "hnrpvt"), kSubscribeRate);
1344 }
1345 
1346 void AdrUdrProduct::callbackEsfMEAS(const ublox_msgs::EsfMEAS &m) {
1347  if (enabled["esf_meas"]) {
1348  static ros::Publisher imu_pub =
1349  nh->advertise<sensor_msgs::Imu>("imu_meas", kROSQueueSize);
1350  static ros::Publisher time_ref_pub =
1351  nh->advertise<sensor_msgs::TimeReference>("interrupt_time", kROSQueueSize);
1352 
1353  imu_.header.stamp = ros::Time::now();
1354  imu_.header.frame_id = frame_id;
1355 
1356  static const float deg_per_sec = pow(2, -12);
1357  static const float m_per_sec_sq = pow(2, -10);
1358  static const float deg_c = 1e-2;
1359 
1360  std::vector<uint32_t> imu_data = m.data;
1361  for (int i=0; i < imu_data.size(); i++){
1362  unsigned int data_type = imu_data[i] >> 24; //grab the last six bits of data
1363  int32_t data_value = static_cast<int32_t>(imu_data[i] << 8); //shift to extend sign from 24 to 32 bit integer
1364  data_value >>= 8;
1365 
1366  imu_.orientation_covariance[0] = -1;
1367  imu_.linear_acceleration_covariance[0] = -1;
1368  imu_.angular_velocity_covariance[0] = -1;
1369 
1370  if (data_type == 14) {
1371  imu_.angular_velocity.x = data_value * deg_per_sec;
1372  } else if (data_type == 16) {
1373  imu_.linear_acceleration.x = data_value * m_per_sec_sq;
1374  } else if (data_type == 13) {
1375  imu_.angular_velocity.y = data_value * deg_per_sec;
1376  } else if (data_type == 17) {
1377  imu_.linear_acceleration.y = data_value * m_per_sec_sq;
1378  } else if (data_type == 5) {
1379  imu_.angular_velocity.z = data_value * deg_per_sec;
1380  } else if (data_type == 18) {
1381  imu_.linear_acceleration.z = data_value * m_per_sec_sq;
1382  } else if (data_type == 12) {
1383  //ROS_INFO("Temperature in celsius: %f", data_value * deg_c);
1384  } else {
1385  ROS_INFO("data_type: %u", data_type);
1386  ROS_INFO("data_value: %u", data_value);
1387  }
1388 
1389  // create time ref message and put in the data
1390  //t_ref_.header.seq = m.risingEdgeCount;
1391  //t_ref_.header.stamp = ros::Time::now();
1392  //t_ref_.header.frame_id = frame_id;
1393 
1394  //t_ref_.time_ref = ros::Time((m.wnR * 604800 + m.towMsR / 1000), (m.towMsR % 1000) * 1000000 + m.towSubMsR);
1395 
1396  //std::ostringstream src;
1397  //src << "TIM" << int(m.ch);
1398  //t_ref_.source = src.str();
1399 
1400  t_ref_.header.stamp = ros::Time::now(); // create a new timestamp
1401  t_ref_.header.frame_id = frame_id;
1402 
1403  time_ref_pub.publish(t_ref_);
1404  imu_pub.publish(imu_);
1405  }
1406  }
1407 
1408  updater->force_update();
1409 }
1410 //
1411 // u-blox High Precision GNSS Reference Station
1412 //
1415  if(nav_rate * meas_rate != 1000)
1416  ROS_WARN("For HPG Ref devices, nav_rate should be exactly 1 Hz.");
1417 
1418  if(!getRosUint("tmode3", tmode3_))
1419  throw std::runtime_error("Invalid settings: TMODE3 must be set");
1420 
1421  if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1422  if(!nh->getParam("arp/position", arp_position_))
1423  throw std::runtime_error(std::string("Invalid settings: arp/position ")
1424  + "must be set if TMODE3 is fixed");
1425  if(!getRosInt("arp/position_hp", arp_position_hp_))
1426  throw std::runtime_error(std::string("Invalid settings: arp/position_hp ")
1427  + "must be set if TMODE3 is fixed");
1428  if(!nh->getParam("arp/acc", fixed_pos_acc_))
1429  throw std::runtime_error(std::string("Invalid settings: arp/acc ")
1430  + "must be set if TMODE3 is fixed");
1431  if(!nh->getParam("arp/lla_flag", lla_flag_)) {
1432  ROS_WARN("arp/lla_flag param not set, assuming ARP coordinates are %s",
1433  "in ECEF");
1434  lla_flag_ = false;
1435  }
1436  } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1437  nh->param("sv_in/reset", svin_reset_, true);
1438  if(!getRosUint("sv_in/min_dur", sv_in_min_dur_))
1439  throw std::runtime_error(std::string("Invalid settings: sv_in/min_dur ")
1440  + "must be set if TMODE3 is survey-in");
1441  if(!nh->getParam("sv_in/acc_lim", sv_in_acc_lim_))
1442  throw std::runtime_error(std::string("Invalid settings: sv_in/acc_lim ")
1443  + "must be set if TMODE3 is survey-in");
1444  } else if(tmode3_ != ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1445  throw std::runtime_error(std::string("tmode3 param invalid. See CfgTMODE3")
1446  + " flag constants for possible values.");
1447  }
1448  }
1449 }
1450 
1452  // Configure TMODE3
1453  if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_DISABLED) {
1454  if(!gps.disableTmode3())
1455  throw std::runtime_error("Failed to disable TMODE3.");
1456  mode_ = DISABLED;
1457  } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_FIXED) {
1458  if(!gps.configTmode3Fixed(lla_flag_, arp_position_, arp_position_hp_,
1459  fixed_pos_acc_))
1460  throw std::runtime_error("Failed to set TMODE3 to fixed.");
1462  throw std::runtime_error("Failed to set RTCM rates");
1463  mode_ = FIXED;
1464  } else if(tmode3_ == ublox_msgs::CfgTMODE3::FLAGS_MODE_SURVEY_IN) {
1465  if(!svin_reset_) {
1466  ublox_msgs::NavSVIN nav_svin;
1467  if(!gps.poll(nav_svin))
1468  throw std::runtime_error(std::string("Failed to poll NavSVIN while") +
1469  " configuring survey-in");
1470  // Don't reset survey-in if it's already active
1471  if(nav_svin.active) {
1472  mode_ = SURVEY_IN;
1473  return true;
1474  }
1475  // Don't reset survey-in if it already has a valid value
1476  if(nav_svin.valid) {
1477  setTimeMode();
1478  return true;
1479  }
1480  ublox_msgs::NavPVT nav_pvt;
1481  if(!gps.poll(nav_pvt))
1482  throw std::runtime_error(std::string("Failed to poll NavPVT while") +
1483  " configuring survey-in");
1484  // Don't reset survey in if in time mode with a good fix
1485  if (nav_pvt.fixType == nav_pvt.FIX_TYPE_TIME_ONLY
1486  && nav_pvt.flags & nav_pvt.FLAGS_GNSS_FIX_OK) {
1487  setTimeMode();
1488  return true;
1489  }
1490  }
1491  // Reset the Survey In
1492  // For Survey in, meas rate must be at least 1 Hz
1493  uint16_t meas_rate_temp = meas_rate < 1000 ? meas_rate : 1000; // [ms]
1494  // If measurement period isn't a factor of 1000, set to default
1495  if(1000 % meas_rate_temp != 0)
1496  meas_rate_temp = kDefaultMeasPeriod;
1497  // Set nav rate to 1 Hz during survey in
1498  if(!gps.configRate(meas_rate_temp, (int) 1000 / meas_rate_temp))
1499  throw std::runtime_error(std::string("Failed to set nav rate to 1 Hz") +
1500  "before setting TMODE3 to survey-in.");
1501  // As recommended in the documentation, first disable, then set to survey in
1502  if(!gps.disableTmode3())
1503  ROS_ERROR("Failed to disable TMODE3 before setting to survey-in.");
1504  else
1505  mode_ = DISABLED;
1506  // Set to Survey in mode
1507  if(!gps.configTmode3SurveyIn(sv_in_min_dur_, sv_in_acc_lim_))
1508  throw std::runtime_error("Failed to set TMODE3 to survey-in.");
1509  mode_ = SURVEY_IN;
1510  }
1511  return true;
1512 }
1513 
1515  // Whether to publish Nav Survey-In messages
1516  nh->param("publish/nav/svin", enabled["nav_svin"], enabled["nav"]);
1517  // Subscribe to Nav Survey-In
1518  gps.subscribe<ublox_msgs::NavSVIN>(boost::bind(
1520 }
1521 
1522 void HpgRefProduct::callbackNavSvIn(ublox_msgs::NavSVIN m) {
1523  if(enabled["nav_svin"]) {
1524  static ros::Publisher publisher =
1525  nh->advertise<ublox_msgs::NavSVIN>("navsvin", kROSQueueSize);
1526  publisher.publish(m);
1527  }
1528 
1529  last_nav_svin_ = m;
1530 
1531  if(!m.active && m.valid && mode_ == SURVEY_IN) {
1532  setTimeMode();
1533  }
1534 
1535  updater->update();
1536 }
1537 
1539  ROS_INFO("Setting mode (internal state) to Time Mode");
1540  mode_ = TIME;
1541 
1542  // Set the Measurement & nav rate to user config
1543  // (survey-in sets nav_rate to 1 Hz regardless of user setting)
1545  ROS_ERROR("Failed to set measurement rate to %d ms %s %d", meas_rate,
1546  "navigation rate to ", nav_rate);
1547  // Enable the RTCM out messages
1549  ROS_ERROR("Failed to configure RTCM IDs");
1550  return false;
1551  }
1552  return true;
1553 }
1554 
1556  updater->add("TMODE3", this, &HpgRefProduct::tmode3Diagnostics);
1557  updater->force_update();
1558 }
1559 
1562  if (mode_ == INIT) {
1563  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1564  stat.message = "Not configured";
1565  } else if (mode_ == DISABLED){
1566  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1567  stat.message = "Disabled";
1568  } else if (mode_ == SURVEY_IN) {
1569  if (!last_nav_svin_.active && !last_nav_svin_.valid) {
1570  stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1571  stat.message = "Survey-In inactive and invalid";
1572  } else if (last_nav_svin_.active && !last_nav_svin_.valid) {
1573  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1574  stat.message = "Survey-In active but invalid";
1575  } else if (!last_nav_svin_.active && last_nav_svin_.valid) {
1576  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1577  stat.message = "Survey-In complete";
1578  } else if (last_nav_svin_.active && last_nav_svin_.valid) {
1579  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1580  stat.message = "Survey-In active and valid";
1581  }
1582 
1583  stat.add("iTOW [ms]", last_nav_svin_.iTOW);
1584  stat.add("Duration [s]", last_nav_svin_.dur);
1585  stat.add("# observations", last_nav_svin_.obs);
1586  stat.add("Mean X [m]", last_nav_svin_.meanX * 1e-2);
1587  stat.add("Mean Y [m]", last_nav_svin_.meanY * 1e-2);
1588  stat.add("Mean Z [m]", last_nav_svin_.meanZ * 1e-2);
1589  stat.add("Mean X HP [m]", last_nav_svin_.meanXHP * 1e-4);
1590  stat.add("Mean Y HP [m]", last_nav_svin_.meanYHP * 1e-4);
1591  stat.add("Mean Z HP [m]", last_nav_svin_.meanZHP * 1e-4);
1592  stat.add("Mean Accuracy [m]", last_nav_svin_.meanAcc * 1e-4);
1593  } else if(mode_ == FIXED) {
1594  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1595  stat.message = "Fixed Position";
1596  } else if(mode_ == TIME) {
1597  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1598  stat.message = "Time";
1599  }
1600 }
1601 
1602 //
1603 // U-Blox High Precision GNSS Rover
1604 //
1606  // default to float, see CfgDGNSS message for details
1607  getRosUint("dgnss_mode", dgnss_mode_,
1608  ublox_msgs::CfgDGNSS::DGNSS_MODE_RTK_FIXED);
1609 }
1610 
1612  // Configure the DGNSS
1613  if(!gps.setDgnss(dgnss_mode_))
1614  throw std::runtime_error(std::string("Failed to Configure DGNSS"));
1615  return true;
1616 }
1617 
1619  // Whether to publish Nav Relative Position NED
1620  nh->param("publish/nav/relposned", enabled["nav_relposned"], enabled["nav"]);
1621  // Subscribe to Nav Relative Position NED messages (also updates diagnostics)
1622  gps.subscribe<ublox_msgs::NavRELPOSNED>(boost::bind(
1624 }
1625 
1627  freq_rtcm_ = UbloxTopicDiagnostic(std::string("rxmrtcm"),
1628  kRtcmFreqMin, kRtcmFreqMax,
1629  kRtcmFreqTol, kRtcmFreqWindow);
1630  updater->add("Carrier Phase Solution", this,
1632  updater->force_update();
1633 }
1634 
1637  uint32_t carr_soln = last_rel_pos_.flags & last_rel_pos_.FLAGS_CARR_SOLN_MASK;
1638  stat.add("iTow", last_rel_pos_.iTow);
1639  if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_NONE ||
1640  !(last_rel_pos_.flags & last_rel_pos_.FLAGS_DIFF_SOLN &&
1641  last_rel_pos_.flags & last_rel_pos_.FLAGS_REL_POS_VALID)) {
1642  stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
1643  stat.message = "None";
1644  } else {
1645  if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FLOAT) {
1646  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
1647  stat.message = "Float";
1648  } else if (carr_soln & last_rel_pos_.FLAGS_CARR_SOLN_FIXED) {
1649  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
1650  stat.message = "Fixed";
1651  }
1652  stat.add("Ref Station ID", last_rel_pos_.refStationId);
1653 
1654  double rel_pos_n = (last_rel_pos_.relPosN
1655  + (last_rel_pos_.relPosHPN * 1e-2)) * 1e-2;
1656  double rel_pos_e = (last_rel_pos_.relPosE
1657  + (last_rel_pos_.relPosHPE * 1e-2)) * 1e-2;
1658  double rel_pos_d = (last_rel_pos_.relPosD
1659  + (last_rel_pos_.relPosHPD * 1e-2)) * 1e-2;
1660  stat.add("Relative Position N [m]", rel_pos_n);
1661  stat.add("Relative Accuracy N [m]", last_rel_pos_.accN * 1e-4);
1662  stat.add("Relative Position E [m]", rel_pos_e);
1663  stat.add("Relative Accuracy E [m]", last_rel_pos_.accE * 1e-4);
1664  stat.add("Relative Position D [m]", rel_pos_d);
1665  stat.add("Relative Accuracy D [m]", last_rel_pos_.accD * 1e-4);
1666  }
1667 }
1668 
1669 void HpgRovProduct::callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m) {
1670  if (enabled["nav_relposned"]) {
1671  static ros::Publisher publisher =
1672  nh->advertise<ublox_msgs::NavRELPOSNED>("navrelposned", kROSQueueSize);
1673  publisher.publish(m);
1674  }
1675 
1676  last_rel_pos_ = m;
1677  updater->update();
1678 }
1679 
1680 //
1681 // U-Blox High Precision Positioning Receiver
1682 //
1683 
1685  // Whether to publish Nav Relative Position NED
1686  nh->param("publish/nav/relposned", enabled["nav_relposned"], enabled["nav"]);
1687  // Subscribe to Nav Relative Position NED messages (also updates diagnostics)
1688  gps.subscribe<ublox_msgs::NavRELPOSNED9>(boost::bind(
1690 
1691  // Whether to publish the Heading info from Nav Relative Position NED
1692  nh->param("publish/nav/heading", enabled["nav_heading"], enabled["nav"]);
1693 }
1694 
1695 void HpPosRecProduct::callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m) {
1696  if (enabled["nav_relposned"]) {
1697  static ros::Publisher publisher =
1698  nh->advertise<ublox_msgs::NavRELPOSNED9>("navrelposned", kROSQueueSize);
1699  publisher.publish(m);
1700  }
1701 
1702  if (enabled["nav_heading"]) {
1703  static ros::Publisher imu_pub =
1704  nh->advertise<sensor_msgs::Imu>("navheading", kROSQueueSize);
1705 
1706  imu_.header.stamp = ros::Time::now();
1707  imu_.header.frame_id = frame_id;
1708 
1709  imu_.linear_acceleration_covariance[0] = -1;
1710  imu_.angular_velocity_covariance[0] = -1;
1711 
1712  // Transform angle since ublox is representing heading as NED but ROS uses ENU as convention (REP-103).
1713  // Also convert the base-to-rover angle to a robot-to-base angle (consistent with frame_id)
1714  double heading = - (static_cast<double>(m.relPosHeading) * 1e-5 / 180.0 * M_PI) - M_PI_2;
1715  tf::Quaternion orientation;
1716  orientation.setRPY(0, 0, heading);
1717  imu_.orientation.x = orientation[0];
1718  imu_.orientation.y = orientation[1];
1719  imu_.orientation.z = orientation[2];
1720  imu_.orientation.w = orientation[3];
1721  imu_.orientation_covariance[0] = 1000.0;
1722  imu_.orientation_covariance[4] = 1000.0;
1723  imu_.orientation_covariance[8] = 1000.0;
1724  // When heading is reported to be valid, use accuracy reported in 1e-5 deg units
1725  if (m.flags & ublox_msgs::NavRELPOSNED9::FLAGS_REL_POS_HEAD_VALID)
1726  {
1727  imu_.orientation_covariance[8] = pow(m.accHeading * 1e-5 / 180.0 * M_PI, 2);
1728  }
1729 
1730  imu_pub.publish(imu_);
1731  }
1732 
1733  last_rel_pos_ = m;
1734  updater->update();
1735 }
1736 
1737 //
1738 // U-Blox Time Sync Products, partially implemented.
1739 //
1741 }
1742 
1744  uint8_t r = 1;
1745  // Configure the reciever
1746  if(!gps.setUTCtime())
1747  throw std::runtime_error(std::string("Failed to Configure TIM Product to UTC Time"));
1748 
1749  if(!gps.setTimtm2(r))
1750  throw std::runtime_error(std::string("Failed to Configure TIM Product"));
1751 
1752  return true;
1753 }
1754 
1756  ROS_INFO("TIM is Enabled: %u", enabled["tim"]);
1757  ROS_INFO("TIM-TM2 is Enabled: %u", enabled["tim_tm2"]);
1758  // Subscribe to TIM-TM2 messages (Time mark messages)
1759  nh->param("publish/tim/tm2", enabled["tim_tm2"], enabled["tim"]);
1760 
1761  gps.subscribe<ublox_msgs::TimTM2>(boost::bind(
1763 
1764  ROS_INFO("Subscribed to TIM-TM2 messages on topic tim/tm2");
1765 
1766  // Subscribe to SFRBX messages
1767  nh->param("publish/rxm/sfrb", enabled["rxm_sfrb"], enabled["rxm"]);
1768  if (enabled["rxm_sfrb"])
1769  gps.subscribe<ublox_msgs::RxmSFRBX>(boost::bind(
1770  publish<ublox_msgs::RxmSFRBX>, _1, "rxmsfrb"), kSubscribeRate);
1771 
1772  // Subscribe to RawX messages
1773  nh->param("publish/rxm/raw", enabled["rxm_raw"], enabled["rxm"]);
1774  if (enabled["rxm_raw"])
1775  gps.subscribe<ublox_msgs::RxmRAWX>(boost::bind(
1776  publish<ublox_msgs::RxmRAWX>, _1, "rxmraw"), kSubscribeRate);
1777 }
1778 
1779 void TimProduct::callbackTimTM2(const ublox_msgs::TimTM2 &m) {
1780 
1781  if (enabled["tim_tm2"]) {
1782  static ros::Publisher publisher =
1783  nh->advertise<ublox_msgs::TimTM2>("timtm2", kROSQueueSize);
1784  static ros::Publisher time_ref_pub =
1785  nh->advertise<sensor_msgs::TimeReference>("interrupt_time", kROSQueueSize);
1786 
1787  // create time ref message and put in the data
1788  t_ref_.header.seq = m.risingEdgeCount;
1789  t_ref_.header.stamp = ros::Time::now();
1790  t_ref_.header.frame_id = frame_id;
1791 
1792  t_ref_.time_ref = ros::Time((m.wnR * 604800 + m.towMsR / 1000), (m.towMsR % 1000) * 1000000 + m.towSubMsR);
1793 
1794  std::ostringstream src;
1795  src << "TIM" << int(m.ch);
1796  t_ref_.source = src.str();
1797 
1798  t_ref_.header.stamp = ros::Time::now(); // create a new timestamp
1799  t_ref_.header.frame_id = frame_id;
1800 
1801  publisher.publish(m);
1802  time_ref_pub.publish(t_ref_);
1803  }
1804 
1805  updater->force_update();
1806 }
1807 
1809  updater->force_update();
1810 }
1811 
1812 int main(int argc, char** argv) {
1813  ros::init(argc, argv, "ublox_gps");
1814  nh.reset(new ros::NodeHandle("~"));
1815  nh->param("debug", ublox_gps::debug, 1);
1816  if(ublox_gps::debug) {
1820 
1821  }
1822  UbloxNode node;
1823  return 0;
1824 }
uint32_t baudrate_
UART1 baudrate.
Definition: node.h:612
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
static constexpr uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
Definition: node.h:92
void subscribe()
Subscribe to Raw Data Product messages and set up ROS publishers.
Definition: node.cpp:1237
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
Definition: node.h:111
void close()
Closes the I/O port, and initiates save on shutdown procedure if enabled.
Definition: gps.cpp:249
msg
RawDataStreamPa rawDataStreamPa_
raw data stream logging
Definition: node.h:650
boost::shared_ptr< ComponentInterface > ComponentPtr
Definition: node.h:471
int fix_status_service
Definition: node.h:116
uint8_t fmode_
Set from fix mode string.
Definition: node.h:610
static constexpr float kDiagnosticPeriod
[s] 5Hz diagnostic period
Definition: node.h:494
bool configureUblox()
Configure rover settings.
Definition: node.cpp:1611
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
void processMonVer()
Process the MonVer message and add firmware and product components.
Definition: node.cpp:355
void subscribe()
Subscribe to all requested u-blox messages.
Definition: node.cpp:258
Implements functions for Time Sync products.
Definition: node.h:1359
Implements functions for firmware version 7.
Definition: node.h:946
static const uint8_t EPH
uint8_t sbas_usage_
SBAS Usage parameter (see CfgSBAS message)
Definition: node.h:637
sensor_msgs::TimeReference t_ref_
Definition: node.h:1117
bool getRosInt(const std::string &key, I &u)
Get a integer (size 8 or 16) value from the parameter server.
Definition: node.h:367
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
#define ROS_FATAL(...)
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
Definition: node.h:625
bool configureUblox()
Configure GNSS individually. Only configures GLONASS.
Definition: node.cpp:907
Topic diagnostics for fix / fix_velocity messages.
Definition: node.h:185
static constexpr double kPollDuration
how often (in seconds) to call poll messages
Definition: node.h:491
static constexpr double kFixFreqTol
Tolerance for Fix topic frequency as percentage of target frequency.
Definition: node.h:496
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void initializeRosDiagnostics()
Adds diagnostic updaters for Time Sync status.
Definition: node.cpp:1808
void publish(const boost::shared_ptr< M > &message) const
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
Definition: node.cpp:1684
void subscribe()
Subscribe to ADR/UDR messages.
Definition: node.cpp:1303
void ubloxCallback(const unsigned char *data, const std::size_t size)
Callback function which handles raw data.
void initializeRosDiagnostics()
Add diagnostic updaters for the TMODE3 status.
Definition: node.cpp:1555
void subscribe()
Subscribe to messages which are not generic to all firmware.
Definition: node.cpp:975
virtual void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)=0
Handle to send fix status to ROS diagnostics.
bool setTimeMode()
Set the device mode to time mode (internal state variable).
Definition: node.cpp:1538
void pollMessages(const ros::TimerEvent &event)
Poll messages from the U-Blox device.
Definition: node.cpp:232
void subscribe()
Subscribe to Time Sync messages.
Definition: node.cpp:1755
static const uint8_t ALM
bool setUseAdr(bool enable, float protocol_version)
Enable or disable ADR (automotive dead reckoning).
Definition: gps.cpp:523
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
Definition: node.h:635
bool setFixMode(uint8_t mode)
Set the device fix mode.
Definition: gps.cpp:487
void getRosParams()
Get the node parameters from the ROS Parameter Server.
Definition: node.cpp:135
static constexpr uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
Definition: node.h:90
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
Definition: node.h:643
bool configureUblox()
Configure Time Sync settings.
Definition: node.cpp:1743
static const uint8_t DEBUG
bool configureUblox()
Prints a warning, GNSS configuration not available in this version.
Definition: node.cpp:646
bool configRate(uint16_t meas_rate, uint16_t nav_rate)
Configure the device navigation and measurement rate settings.
Definition: gps.cpp:381
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m)
Set the last received message and call rover diagnostic updater.
Definition: node.cpp:1669
void start()
Implements functions for firmware version 8.
Definition: node.h:982
std::string fix_mode_
Fix mode type.
Definition: node.h:606
std::vector< boost::shared_ptr< ComponentInterface > > components_
The u-blox node components.
Definition: node.h:596
Implements functions for High Precision GNSS Rover devices.
Definition: node.h:1269
bool configureUblox()
Configure the u-blox Reference Station settings.
Definition: node.cpp:1451
bool configSbas(bool enable, uint8_t usage, uint8_t max_sbas)
Configure the SBAS settings.
Definition: gps.cpp:403
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices...
Definition: node.h:1075
void callbackNavPvt(const NavPVT &m)
Publish a NavSatFix and TwistWithCovarianceStamped messages.
Definition: node.h:766
bool setTimtm2(uint8_t rate)
Enable or disable TIM-TM2 (time mark message).
Definition: gps.cpp:582
Implements functions for High Precision GNSS Reference station devices.
Definition: node.h:1160
static const uint8_t HUI
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:120
#define ROS_WARN(...)
UbloxNode()
Initialize and run the u-blox node.
Definition: node.cpp:90
bool disableTmode3()
Set the TMODE3 settings to disabled. Should only be called for High Precision GNSS devices...
Definition: gps.cpp:460
bool set_usb_
Whether to configure the USB port.
Definition: node.h:621
static const uint8_t TEST
void addFirmwareInterface()
Add the interface for firmware specific configuration, subscribers, & diagnostics. This assumes the protocol_version_ has been set.
Definition: node.cpp:94
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
Definition: node.h:614
ublox_msgs::CfgDAT cfg_dat_
User-defined Datum.
Definition: node.h:631
uint8_t modelFromString(const std::string &model)
Determine dynamic model from human-readable string.
Definition: node.cpp:43
Implements functions for FTS products. Currently unimplemented.
Definition: node.h:1127
bool configTmode3SurveyIn(unsigned int svin_min_dur, float svin_acc_limit)
Set the TMODE3 settings to survey-in.
Definition: gps.cpp:449
bool use_adr_
Whether or not to enable dead reckoning.
Definition: node.h:1112
ROSCPP_DECL void spin(Spinner &spinner)
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
static constexpr uint32_t kROSQueueSize
Queue size for ROS publishers.
Definition: node.h:88
void initialize(void)
Initializes raw data streams If storing to file is enabled, the filename is created and the correspon...
Definition: raw_data_pa.cpp:77
static const uint8_t NOTICE
bool supportsGnss(std::string gnss)
Definition: node.h:433
bool config_on_startup_flag_
Flag for enabling configuration on startup.
Definition: node.h:126
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
Definition: node.h:618
void callbackNavSol(const ublox_msgs::NavSOL &m)
Update the number of SVs used for the fix.
Definition: node.cpp:805
void getRosParams()
Get the ROS parameters specific to the Rover configuration.
Definition: node.cpp:1605
void subscribe()
Subscribe to u-blox Reference Station messages.
Definition: node.cpp:1514
void callbackEsfMEAS(const ublox_msgs::EsfMEAS &m)
Definition: node.cpp:1346
void getRosParams()
Get the Time Sync parameters.
Definition: node.cpp:1740
std::set< std::string > supported
Which GNSS are supported by the device.
Definition: node.h:105
void subscribe()
Subscribe to Rover messages, such as NavRELPOSNED.
Definition: node.cpp:1618
sensor_msgs::Imu imu_
Definition: node.h:1116
void subscribe()
Subscribe to u-blox messages which are not generic to all firmware versions.
Definition: node.cpp:1208
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void setRawDataCallback(const Worker::Callback &callback)
Set the callback function which handles raw data.
Definition: gps.cpp:569
#define ROS_INFO(...)
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
Definition: node.h:103
bool setDgnss(uint8_t mode)
Set the DGNSS mode (see CfgDGNSS message for details).
Definition: gps.cpp:516
void setConfigOnStartup(const bool config_on_startup)
Set the internal flag for enabling or disabling the initial configurations.
Definition: gps.h:90
void initializeRosDiagnostics()
Add the fix diagnostics to the updater.
Definition: node.cpp:594
void initializeRosDiagnostics()
Initialize the diagnostic updater and add the fix diagnostic.
Definition: node.cpp:340
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
Definition: node.h:100
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
void printInf(const ublox_msgs::Inf &m, uint8_t id)
Print an INF message to the ROS console.
Definition: node.cpp:247
static const uint8_t AID
void initializeIo()
Initialize the I/O handling.
Definition: node.cpp:523
std::vector< uint8_t > rtcm_ids
IDs of RTCM out messages to configure.
Definition: node.h:122
ublox_msgs::CfgCFG save_
Parameters to save to non-volatile memory after configuration.
Definition: node.h:645
void callbackNavVelNed(const ublox_msgs::NavVELNED &m)
Update the last known velocity.
Definition: node.cpp:771
Implements functions for firmware version 9. For now it simply re-uses the firmware version 8 class b...
Definition: node.h:1032
void checkMin(V val, T min, std::string name)
Check that the parameter is above the minimum.
Definition: node.h:262
uint8_t fixModeFromString(const std::string &mode)
Determine fix mode from human-readable string.
Definition: node.cpp:72
void checkRange(V val, T min, T max, std::string name)
Check that the parameter is in the range.
Definition: node.h:279
uint8_t dmodel_
Set from dynamic model string.
Definition: node.h:608
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
Definition: node.h:118
#define ROS_WARN_STREAM(args)
void getRosParams()
Sets the fix status service type to GPS.
Definition: node.cpp:604
bool set_dat_
If true, set configure the User-Defined Datum.
Definition: node.h:629
#define ROS_DEBUG_STREAM(args)
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
Definition: node.h:124
bool setDeadReckonLimit(uint8_t limit)
Set the dead reckoning time limit.
Definition: gps.cpp:496
static constexpr double kTimeStampStatusMin
Minimum Time Stamp Status for fix frequency diagnostic.
Definition: node.h:500
float protocol_version_
Determined From Mon VER.
Definition: node.h:599
AdrUdrProduct(float protocol_version)
Definition: node.cpp:1281
void callbackTimTM2(const ublox_msgs::TimTM2 &m)
Definition: node.cpp:1779
void callbackNavPosLlh(const ublox_msgs::NavPOSLLH &m)
Publish the fix and call the fix diagnostic updater.
Definition: node.cpp:728
double rate_
The measurement rate in Hz.
Definition: node.h:627
lower
boost::shared_ptr< FixDiagnostic > freq_diag
fix frequency diagnostic updater
Definition: node.h:224
std::string dynamic_model_
dynamic model type
Definition: node.h:604
void setSaveOnShutdown(bool save_on_shutdown)
If called, when the node shuts down, it will send a command to save the flash memory.
Definition: gps.h:82
static const uint8_t WARNING
void subscribe(typename CallbackHandler_< T >::Callback callback, unsigned int rate)
Configure the U-Blox send rate of the message & subscribe to the given message.
Definition: gps.h:484
bool isInitialized() const
Definition: gps.h:354
#define ROS_INFO_STREAM(args)
void initialize()
Initialize the U-Blox node. Configure the U-Blox and subscribe to messages.
Definition: node.cpp:551
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
Definition: node.h:616
void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m)
Set the last received message and call rover diagnostic updater.
Definition: node.cpp:1695
void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the TMODE3 diagnostics.
Definition: node.cpp:1560
Topic diagnostics for u-blox messages.
Definition: node.h:130
void subscribeId(typename CallbackHandler_< T >::Callback callback, unsigned int message_id)
Subscribe to the message with the given ID. This is used for messages which have the same format but ...
Definition: gps.h:496
bool configureUblox()
Configure settings specific to firmware 8 based on ROS parameters.
Definition: node.cpp:1115
int main(int argc, char **argv)
Definition: node.cpp:1812
static Time now()
bool isEnabled(void)
Returns the if raw data streaming is enabled.
Definition: raw_data_pa.cpp:67
void shutdown()
Shutdown the node. Closes the serial port.
Definition: node.cpp:584
std::string device_
Device port.
Definition: node.h:602
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
Definition: node.h:639
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
Definition: node.h:623
void getRosParams()
Get the ADR/UDR parameters.
Definition: node.cpp:1288
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
Definition: node.h:98
void configureInf()
Configure INF messages, call after subscribe.
Definition: node.cpp:492
Implements functions for Raw Data products.
Definition: node.h:1038
bool getRosUint(const std::string &key, U &u)
Get a unsigned integer value from the parameter server.
Definition: node.h:313
void add(const std::string &key, const T &val)
This class represents u-blox ROS node for all firmware and product versions.
Definition: node.h:488
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void initializeRosDiagnostics()
Adds frequency diagnostics for RTCM topics.
Definition: node.cpp:1266
uint8_t dr_limit_
Dead reckoning limit parameter.
Definition: node.h:641
#define ROS_ERROR_STREAM(args)
void initializeRosDiagnostics()
Add diagnostic updaters for rover GNSS status, including status of RTCM messages. ...
Definition: node.cpp:1626
bool enable_sbas_
Whether or not to enable SBAS.
Definition: node.h:633
static constexpr double kFixFreqWindow
Window [num messages] for Fix Frequency Diagnostic.
Definition: node.h:498
void getRosParams(void)
Get the raw data stream parameters.
Definition: raw_data_pa.cpp:57
bool configureUblox()
Configure the device based on ROS parameters.
Definition: node.cpp:420
void carrierPhaseDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the rover diagnostics, including the carrier phase solution status (float or fixed)...
Definition: node.cpp:1635
void getRosParams()
Get the ROS parameters specific to firmware version 8.
Definition: node.cpp:1003
void getRosParams()
Get the parameters specific to firmware version 7.
Definition: node.cpp:819
static const uint8_t ERROR
void subscribe()
Subscribe to NavPVT, RxmRAW, and RxmSFRB messages.
Definition: node.cpp:655
void callbackNavSvIn(ublox_msgs::NavSVIN m)
Update the last received NavSVIN message and call diagnostic updater.
Definition: node.cpp:1522
#define ROS_ERROR(...)
static constexpr uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
Definition: node.h:94
#define ROSCONSOLE_DEFAULT_NAME
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Updates fix diagnostic from NavPOSLLH, NavVELNED, and NavSOL messages.
Definition: node.cpp:686
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 configureUblox()
Configure ADR/UDR settings.
Definition: node.cpp:1296
bool configure(const ConfigT &message, bool wait=true)
Send the given configuration message.
Definition: gps.h:516
Implements functions for firmware version 6.
Definition: node.h:676
static constexpr int kResetWait
How long to wait during I/O reset [s].
Definition: node.cpp:38
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 addProductInterface(std::string product_category, std::string ref_rov="")
Add the interface which is used for product category configuration, subscribers, & diagnostics...
Definition: node.cpp:114
void initializeTcp(std::string host, std::string port)
Initialize TCP I/O.
Definition: gps.cpp:213
void getRosParams()
Get the ROS parameters specific to the Reference Station configuration.
Definition: node.cpp:1413
std::string frame_id
The ROS frame ID of this device.
Definition: node.h:113
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