node.h
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 #ifndef UBLOX_GPS_NODE_H
31 #define UBLOX_GPS_NODE_H
32 
33 // STL
34 #include <vector>
35 #include <set>
36 // Boost
37 #include <boost/algorithm/string.hpp>
38 #include <boost/lexical_cast.hpp>
39 #include <boost/regex.hpp>
40 // ROS includes
41 #include <ros/ros.h>
42 #include <ros/console.h>
43 #include <ros/serialization.h>
44 #include <tf/transform_datatypes.h>
47 // ROS messages
48 #include <geometry_msgs/TwistWithCovarianceStamped.h>
49 #include <geometry_msgs/Vector3Stamped.h>
50 #include <sensor_msgs/NavSatFix.h>
51 #include <sensor_msgs/TimeReference.h>
52 #include <sensor_msgs/Imu.h>
53 // Other U-Blox package includes
54 #include <ublox_msgs/ublox_msgs.h>
55 // Ublox GPS includes
56 #include <ublox_gps/gps.h>
57 #include <ublox_gps/utils.h>
58 #include <ublox_gps/raw_data_pa.h>
59 
60 // This file declares the ComponentInterface which acts as a high level
61 // interface for u-blox firmware, product categories, etc. It contains methods
62 // to configure the u-blox and subscribe to u-blox messages.
63 //
64 // This file also declares UbloxNode which implements ComponentInterface and is
65 // the main class and ros node. it implements functionality which applies to
66 // any u-blox device, regardless of the firmware version or product type.
67 // The class is designed in compositional style; it contains ComponentInterfaces
68 // which implement features specific to the device based on its firmware version
69 // and product category. UbloxNode calls the public methods of each component.
70 //
71 // This file declares UbloxFirmware is an abstract class which implements
72 // ComponentInterface and functions generic to all firmware (such as the
73 // initializing the fix diagnostics). Subclasses of UbloxFirmware for firmware
74 // versions 6-8 are also declared in this file.
75 //
76 // Lastly, this file declares classes for each product category which also
77 // implement u-blox interface, currently only the class for High Precision
78 // GNSS devices has been fully implemented and tested.
79 
85 namespace ublox_node {
86 
88 constexpr static uint32_t kROSQueueSize = 1;
90 constexpr static uint16_t kDefaultMeasPeriod = 250;
92 constexpr static uint32_t kSubscribeRate = 1;
94 constexpr static uint32_t kNavSvInfoSubscribeRate = 20;
95 
96 // ROS objects
101 
105 std::set<std::string> supported;
107 
111 std::map<std::string, bool> enabled;
113 std::string frame_id;
118 uint16_t meas_rate;
120 uint16_t nav_rate;
122 std::vector<uint8_t> rtcm_ids;
124 std::vector<uint8_t> rtcm_rates;
127 
128 
132 
133  // Must not copy this struct (would confuse FrequencyStatusParam pointers)
135 
144  UbloxTopicDiagnostic (std::string topic, double freq_tol, int freq_window) {
145  const double target_freq = 1.0 / (meas_rate * 1e-3 * nav_rate); // Hz
146  min_freq = target_freq;
147  max_freq = target_freq;
149  freq_tol, freq_window);
151  *updater,
152  freq_param);
153  }
154 
165  UbloxTopicDiagnostic (std::string topic, double freq_min, double freq_max,
166  double freq_tol, int freq_window) {
167  min_freq = freq_min;
168  max_freq = freq_max;
170  freq_tol, freq_window);
172  *updater,
173  freq_param);
174  }
175 
179  double min_freq;
181  double max_freq;
182 };
183 
187 
188  // Must not copy this struct (would confuse FrequencyStatusParam pointers)
189  FixDiagnostic(const FixDiagnostic&) = delete;
190 
200  FixDiagnostic (std::string name, double freq_tol, int freq_window,
201  double stamp_min) {
202  const double target_freq = 1.0 / (meas_rate * 1e-3 * nav_rate); // Hz
203  min_freq = target_freq;
204  max_freq = target_freq;
206  freq_tol, freq_window);
207  double stamp_max = meas_rate * 1e-3 * (1 + freq_tol);
208  diagnostic_updater::TimeStampStatusParam time_param(stamp_min, stamp_max);
210  *updater,
211  freq_param,
212  time_param);
213  }
214 
218  double min_freq;
220  double max_freq;
221 };
222 
225 
241 uint8_t modelFromString(const std::string& model);
242 
252 uint8_t fixModeFromString(const std::string& mode);
253 
261 template <typename V, typename T>
262 void checkMin(V val, T min, std::string name) {
263  if(val < min) {
264  std::stringstream oss;
265  oss << "Invalid settings: " << name << " must be > " << min;
266  throw std::runtime_error(oss.str());
267  }
268 }
269 
278 template <typename V, typename T>
279 void checkRange(V val, T min, T max, std::string name) {
280  if(val < min || val > max) {
281  std::stringstream oss;
282  oss << "Invalid settings: " << name << " must be in range [" << min <<
283  ", " << max << "].";
284  throw std::runtime_error(oss.str());
285  }
286 }
287 
296 template <typename V, typename T>
297 void checkRange(std::vector<V> val, T min, T max, std::string name) {
298  for(size_t i = 0; i < val.size(); i++) {
299  std::stringstream oss;
300  oss << name << "[" << i << "]";
301  checkRange(val[i], min, max, oss.str());
302  }
303 }
304 
312 template <typename U>
313 bool getRosUint(const std::string& key, U &u) {
314  int param;
315  if (!nh->getParam(key, param)) return false;
316  // Check the bounds
317  U min = std::numeric_limits<U>::lowest();
318  U max = std::numeric_limits<U>::max();
319  checkRange(param, min, max, key);
320  // set the output
321  u = (U) param;
322  return true;
323 }
324 
333 template <typename U, typename V>
334 void getRosUint(const std::string& key, U &u, V default_val) {
335  if(!getRosUint(key, u))
336  u = default_val;
337 }
338 
344 template <typename U>
345 bool getRosUint(const std::string& key, std::vector<U> &u) {
346  std::vector<int> param;
347  if (!nh->getParam(key, param)) return false;
348 
349  // Check the bounds
350  U min = std::numeric_limits<U>::lowest();
351  U max = std::numeric_limits<U>::max();
352  checkRange(param, min, max, key);
353 
354  // set the output
355  u.insert(u.begin(), param.begin(), param.end());
356  return true;
357 }
358 
366 template <typename I>
367 bool getRosInt(const std::string& key, I &u) {
368  int param;
369  if (!nh->getParam(key, param)) return false;
370  // Check the bounds
371  I min = std::numeric_limits<I>::lowest();
372  I max = std::numeric_limits<I>::max();
373  checkRange(param, min, max, key);
374  // set the output
375  u = (I) param;
376  return true;
377 }
378 
387 template <typename U, typename V>
388 void getRosInt(const std::string& key, U &u, V default_val) {
389  if(!getRosInt(key, u))
390  u = default_val;
391 }
392 
398 template <typename I>
399 bool getRosInt(const std::string& key, std::vector<I> &i) {
400  std::vector<int> param;
401  if (!nh->getParam(key, param)) return false;
402 
403  // Check the bounds
404  I min = std::numeric_limits<I>::lowest();
405  I max = std::numeric_limits<I>::max();
406  checkRange(param, min, max, key);
407 
408  // set the output
409  i.insert(i.begin(), param.begin(), param.end());
410  return true;
411 }
412 
421 template <typename MessageT>
422 void publish(const MessageT& m, const std::string& topic) {
423  static ros::Publisher publisher = nh->advertise<MessageT>(topic,
424  kROSQueueSize);
425  publisher.publish(m);
426 }
427 
433 bool supportsGnss(std::string gnss) {
434  return supported.count(gnss) > 0;
435 }
436 
444  public:
450  virtual void getRosParams() = 0;
451 
456  virtual bool configureUblox() = 0;
457 
463  virtual void initializeRosDiagnostics() = 0;
464 
468  virtual void subscribe() = 0;
469 };
470 
472 
488 class UbloxNode : public virtual ComponentInterface {
489  public:
491  constexpr static double kPollDuration = 1.0;
492  // Constants used for diagnostic frequency updater
494  constexpr static float kDiagnosticPeriod = 0.2;
496  constexpr static double kFixFreqTol = 0.15;
498  constexpr static double kFixFreqWindow = 10;
500  constexpr static double kTimeStampStatusMin = 0;
501 
505  UbloxNode();
506 
510  void getRosParams();
511 
516  bool configureUblox();
517 
521  void subscribe();
522 
526  void initializeRosDiagnostics();
527 
531  void printInf(const ublox_msgs::Inf &m, uint8_t id);
532 
533  private:
534 
538  void initializeIo();
539 
544  void initialize();
545 
549  void shutdown();
550 
555  bool resetDevice();
556 
562  void processMonVer();
563 
568  void addFirmwareInterface();
569 
577  void addProductInterface(std::string product_category,
578  std::string ref_rov = "");
579 
584  void pollMessages(const ros::TimerEvent& event);
585 
589  void configureInf();
590 
592 
596  std::vector<boost::shared_ptr<ComponentInterface> > components_;
597 
599  float protocol_version_ = 0;
600  // Variables set from parameter server
602  std::string device_;
604  std::string dynamic_model_;
606  std::string fix_mode_;
608  uint8_t dmodel_;
610  uint8_t fmode_;
612  uint32_t baudrate_;
614  uint16_t uart_in_;
616  uint16_t uart_out_;
618  uint16_t usb_tx_;
620 
621  bool set_usb_;
623  uint16_t usb_in_;
625  uint16_t usb_out_ ;
627  double rate_;
629  bool set_dat_;
631  ublox_msgs::CfgDAT cfg_dat_;
637  uint8_t sbas_usage_;
639  uint8_t max_sbas_;
641  uint8_t dr_limit_;
643  ublox_msgs::CfgCFG load_;
645  ublox_msgs::CfgCFG save_;
647  uint8_t tim_rate_;
648 
651 };
652 
658 class UbloxFirmware : public virtual ComponentInterface {
659  public:
663  void initializeRosDiagnostics();
664 
665  protected:
669  virtual void fixDiagnostic(
671 };
672 
677  public:
678  UbloxFirmware6();
679 
683  void getRosParams();
684 
689  bool configureUblox();
690 
694  void subscribe();
695 
696  protected:
701  void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat);
702 
703  private:
711  void callbackNavPosLlh(const ublox_msgs::NavPOSLLH& m);
712 
719  void callbackNavVelNed(const ublox_msgs::NavVELNED& m);
720 
727  void callbackNavSol(const ublox_msgs::NavSOL& m);
728 
730  ublox_msgs::NavPOSLLH last_nav_pos_;
732  ublox_msgs::NavVELNED last_nav_vel_;
734  ublox_msgs::NavSOL last_nav_sol_;
736  sensor_msgs::NavSatFix fix_;
738  geometry_msgs::TwistWithCovarianceStamped velocity_;
739 
741  ublox_msgs::CfgNMEA6 cfg_nmea_;
743  bool set_nmea_;
744 };
745 
755 template<typename NavPVT>
757  public:
766  void callbackNavPvt(const NavPVT& m) {
767  if(enabled["nav_pvt"]) {
768  // NavPVT publisher
769  static ros::Publisher publisher = nh->advertise<NavPVT>("navpvt",
770  kROSQueueSize);
771  publisher.publish(m);
772  }
773 
774  //
775  // NavSatFix message
776  //
777  static ros::Publisher fixPublisher =
778  nh->advertise<sensor_msgs::NavSatFix>("fix", kROSQueueSize);
779 
780  sensor_msgs::NavSatFix fix;
781  fix.header.frame_id = frame_id;
782  // set the timestamp
783  uint8_t valid_time = m.VALID_DATE | m.VALID_TIME | m.VALID_FULLY_RESOLVED;
784  if (((m.valid & valid_time) == valid_time) &&
785  (m.flags2 & m.FLAGS2_CONFIRMED_AVAILABLE)) {
786  // Use NavPVT timestamp since it is valid
787  // The time in nanoseconds from the NavPVT message can be between -1e9 and 1e9
788  // The ros time uses only unsigned values, so a negative nano seconds must be
789  // converted to a positive value
790  if (m.nano < 0) {
791  fix.header.stamp.sec = toUtcSeconds(m) - 1;
792  fix.header.stamp.nsec = (uint32_t)(m.nano + 1e9);
793  }
794  else {
795  fix.header.stamp.sec = toUtcSeconds(m);
796  fix.header.stamp.nsec = (uint32_t)(m.nano);
797  }
798  } else {
799  // Use ROS time since NavPVT timestamp is not valid
800  fix.header.stamp = ros::Time::now();
801  }
802  // Set the LLA
803  fix.latitude = m.lat * 1e-7; // to deg
804  fix.longitude = m.lon * 1e-7; // to deg
805  fix.altitude = m.height * 1e-3; // to [m]
806  // Set the Fix status
807  bool fixOk = m.flags & m.FLAGS_GNSS_FIX_OK;
808  if (fixOk && m.fixType >= m.FIX_TYPE_2D) {
809  fix.status.status = fix.status.STATUS_FIX;
810  if(m.flags & m.CARRIER_PHASE_FIXED)
811  fix.status.status = fix.status.STATUS_GBAS_FIX;
812  }
813  else {
814  fix.status.status = fix.status.STATUS_NO_FIX;
815  }
816  // Set the service based on GNSS configuration
817  fix.status.service = fix_status_service;
818 
819  // Set the position covariance
820  const double varH = pow(m.hAcc / 1000.0, 2); // to [m^2]
821  const double varV = pow(m.vAcc / 1000.0, 2); // to [m^2]
822  fix.position_covariance[0] = varH;
823  fix.position_covariance[4] = varH;
824  fix.position_covariance[8] = varV;
825  fix.position_covariance_type =
826  sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
827 
828  fixPublisher.publish(fix);
829 
830  //
831  // Twist message
832  //
833  static ros::Publisher velocityPublisher =
834  nh->advertise<geometry_msgs::TwistWithCovarianceStamped>("fix_velocity",
835  kROSQueueSize);
836  geometry_msgs::TwistWithCovarianceStamped velocity;
837  velocity.header.stamp = fix.header.stamp;
838  velocity.header.frame_id = frame_id;
839 
840  // convert to XYZ linear velocity [m/s] in ENU
841  velocity.twist.twist.linear.x = m.velE * 1e-3;
842  velocity.twist.twist.linear.y = m.velN * 1e-3;
843  velocity.twist.twist.linear.z = -m.velD * 1e-3;
844  // Set the covariance
845  const double covSpeed = pow(m.sAcc * 1e-3, 2);
846  const int cols = 6;
847  velocity.twist.covariance[cols * 0 + 0] = covSpeed;
848  velocity.twist.covariance[cols * 1 + 1] = covSpeed;
849  velocity.twist.covariance[cols * 2 + 2] = covSpeed;
850  velocity.twist.covariance[cols * 3 + 3] = -1; // angular rate unsupported
851 
852  velocityPublisher.publish(velocity);
853 
854  //
855  // Update diagnostics
856  //
857  last_nav_pvt_ = m;
858  freq_diag->diagnostic->tick(fix.header.stamp);
859  updater->update();
860  }
861 
862  protected:
863 
868  // check the last message, convert to diagnostic
869  if (last_nav_pvt_.fixType ==
870  ublox_msgs::NavPVT::FIX_TYPE_DEAD_RECKONING_ONLY) {
871  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
872  stat.message = "Dead reckoning only";
873  } else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_2D) {
874  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
875  stat.message = "2D fix";
876  } else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_3D) {
877  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
878  stat.message = "3D fix";
879  } else if (last_nav_pvt_.fixType ==
880  ublox_msgs::NavPVT::FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED) {
881  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
882  stat.message = "GPS and dead reckoning combined";
883  } else if (last_nav_pvt_.fixType ==
884  ublox_msgs::NavPVT::FIX_TYPE_TIME_ONLY) {
885  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
886  stat.message = "Time only fix";
887  }
888 
889  // Check whether differential GNSS available
890  if (last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_DIFF_SOLN) {
891  stat.message += ", DGNSS";
892  }
893  // If DGNSS, then update the differential solution status
894  if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FLOAT) {
895  stat.message += ", FLOAT FIX";
896  } else if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FIXED) {
897  stat.message += ", RTK FIX";
898  }
899 
900  // If fix not ok (w/in DOP & Accuracy Masks), raise the diagnostic level
901  if (!(last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_GNSS_FIX_OK)) {
902  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
903  stat.message += ", fix not ok";
904  }
905  // Raise diagnostic level to error if no fix
906  if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_NO_FIX) {
907  stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
908  stat.message = "No fix";
909  }
910 
911  // append last fix position
912  stat.add("iTOW [ms]", last_nav_pvt_.iTOW);
913  std::ostringstream gnss_coor;
914  gnss_coor << std::fixed << std::setprecision(7);
915  gnss_coor << (last_nav_pvt_.lat * 1e-7);
916  stat.add("Latitude [deg]", gnss_coor.str());
917  gnss_coor.str("");
918  gnss_coor.clear();
919  gnss_coor << (last_nav_pvt_.lon * 1e-7);
920  stat.add("Longitude [deg]", gnss_coor.str());
921  stat.add("Altitude [m]", last_nav_pvt_.height * 1e-3);
922  stat.add("Height above MSL [m]", last_nav_pvt_.hMSL * 1e-3);
923  stat.add("Horizontal Accuracy [m]", last_nav_pvt_.hAcc * 1e-3);
924  stat.add("Vertical Accuracy [m]", last_nav_pvt_.vAcc * 1e-3);
925  stat.add("# SVs used", (int)last_nav_pvt_.numSV);
926  }
927 
930  // Whether or not to enable the given GNSS
940  uint32_t qzss_sig_cfg_;
941 };
942 
946 class UbloxFirmware7 : public UbloxFirmware7Plus<ublox_msgs::NavPVT7> {
947  public:
948  UbloxFirmware7();
949 
955  void getRosParams();
956 
960  bool configureUblox();
961 
967  void subscribe();
968 
969  private:
971 
974  ublox_msgs::CfgNMEA7 cfg_nmea_;
976  bool set_nmea_;
977 };
978 
982 class UbloxFirmware8 : public UbloxFirmware7Plus<ublox_msgs::NavPVT> {
983  public:
984  UbloxFirmware8();
985 
991  void getRosParams();
992 
1000  bool configureUblox();
1001 
1009  void subscribe();
1010 
1011  private:
1012  // Set from ROS parameters
1022  ublox_msgs::CfgNMEA cfg_nmea_;
1025 };
1026 
1033 };
1034 
1038 class RawDataProduct: public virtual ComponentInterface {
1039  public:
1040  static constexpr double kRtcmFreqTol = 0.15;
1041  static constexpr int kRtcmFreqWindow = 25;
1042 
1046  void getRosParams() {}
1047 
1052  bool configureUblox() { return true; }
1053 
1059  void subscribe();
1060 
1064  void initializeRosDiagnostics();
1065 
1066  private:
1068  std::vector<boost::shared_ptr<UbloxTopicDiagnostic> > freq_diagnostics_;
1069 };
1070 
1075 class AdrUdrProduct: public virtual ComponentInterface {
1076  public:
1077  AdrUdrProduct(float protocol_version);
1078 
1084  void getRosParams();
1085 
1091  bool configureUblox();
1092 
1099  void subscribe();
1100 
1106  ROS_WARN("ROS Diagnostics specific to u-blox ADR/UDR devices is %s",
1107  "unimplemented. See AdrUdrProduct class in node.h & node.cpp.");
1108  }
1109 
1110  protected:
1112  bool use_adr_;
1114 
1115 
1116  sensor_msgs::Imu imu_;
1117  sensor_msgs::TimeReference t_ref_;
1118  ublox_msgs::TimTM2 timtm2;
1119 
1120  void callbackEsfMEAS(const ublox_msgs::EsfMEAS &m);
1121 };
1122 
1127 class FtsProduct: public virtual ComponentInterface {
1132  void getRosParams() {
1133  ROS_WARN("Functionality specific to u-blox FTS devices is %s",
1134  "unimplemented. See FtsProduct class in node.h & node.cpp.");
1135  }
1136 
1141  bool configureUblox() { return false; }
1142 
1147  void subscribe() {}
1148 
1154 };
1155 
1160 class HpgRefProduct: public virtual ComponentInterface {
1161  public:
1171  void getRosParams();
1172 
1181  bool configureUblox();
1182 
1188  void subscribe();
1189 
1193  void initializeRosDiagnostics();
1194 
1203  void callbackNavSvIn(ublox_msgs::NavSVIN m);
1204 
1205  protected:
1212  void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
1213 
1219  bool setTimeMode();
1220 
1222  ublox_msgs::NavSVIN last_nav_svin_;
1223 
1225  uint8_t tmode3_;
1226 
1227  // TMODE3 = Fixed mode settings
1229 
1232 
1233  std::vector<float> arp_position_;
1235 
1236  std::vector<int8_t> arp_position_hp_;
1238 
1240 
1241  // Settings for TMODE3 = Survey-in
1243 
1250 
1251  uint32_t sv_in_min_dur_;
1253 
1255 
1257  enum {
1262  TIME
1263  } mode_;
1264 };
1265 
1269 class HpgRovProduct: public virtual ComponentInterface {
1270  public:
1271  // Constants for diagnostic updater
1273  constexpr static double kRtcmFreqMin = 1;
1275  constexpr static double kRtcmFreqMax = 10;
1277  constexpr static double kRtcmFreqTol = 0.1;
1279  constexpr static int kRtcmFreqWindow = 25;
1285  void getRosParams();
1286 
1293  bool configureUblox();
1294 
1298  void subscribe();
1299 
1304  void initializeRosDiagnostics();
1305 
1306  protected:
1311  void carrierPhaseDiagnostics(
1313 
1319  void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m);
1320 
1321 
1323  ublox_msgs::NavRELPOSNED last_rel_pos_;
1324 
1326 
1327  uint8_t dgnss_mode_;
1328 
1331 };
1332 
1333 class HpPosRecProduct: public virtual HpgRefProduct {
1334  public:
1338  void subscribe();
1339 
1340  protected:
1341 
1347  void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m);
1348 
1349  sensor_msgs::Imu imu_;
1350 
1352  ublox_msgs::NavRELPOSNED9 last_rel_pos_;
1353 };
1354 
1359 class TimProduct: public virtual ComponentInterface {
1364  void getRosParams();
1365 
1370  bool configureUblox();
1371 
1377  void subscribe();
1378 
1383  void initializeRosDiagnostics();
1384 
1385  protected:
1390  void callbackTimTM2(const ublox_msgs::TimTM2 &m);
1391 
1392  sensor_msgs::TimeReference t_ref_;
1393 };
1394 
1395 }
1396 
1397 #endif
uint32_t baudrate_
UART1 baudrate.
Definition: node.h:612
static constexpr uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
Definition: node.h:92
float fixed_pos_acc_
Fixed Position Accuracy [m].
Definition: node.h:1239
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
Definition: node.h:111
float sv_in_acc_lim_
Survey in accuracy limit [m].
Definition: node.h:1254
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
Implements functions for Time Sync products.
Definition: node.h:1359
Implements functions for firmware version 7.
Definition: node.h:946
uint8_t sbas_usage_
SBAS Usage parameter (see CfgSBAS message)
Definition: node.h:637
sensor_msgs::TimeReference t_ref_
Definition: node.h:1117
bool param(const std::string &param_name, T &param_val, const T &default_val)
bool getRosInt(const std::string &key, I &u)
Get a integer (size 8 or 16) value from the parameter server.
Definition: node.h:367
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
Definition: node.h:625
This abstract class represents a firmware component.
Definition: node.h:658
Topic diagnostics for fix / fix_velocity messages.
Definition: node.h:185
bool clear_bbr_
Whether to clear the flash memory during configuration.
Definition: node.h:1024
Implements functions for raw data stream.
Definition: raw_data_pa.h:60
ublox_msgs::CfgNMEA6 cfg_nmea_
Used to configure NMEA (if set_nmea_) filled with ROS parameters.
Definition: node.h:741
double max_freq
Maximum allow frequency of topic.
Definition: node.h:181
std::vector< float > arp_position_
Antenna Reference Point Position [m] or [deg].
Definition: node.h:1233
void publish(const boost::shared_ptr< M > &message) const
void initializeRosDiagnostics()
Adds diagnostic updaters for FTS status.
Definition: node.h:1153
UbloxTopicDiagnostic freq_rtcm_
The RTCM topic frequency diagnostic updater.
Definition: node.h:1330
ublox_msgs::TimTM2 timtm2
Definition: node.h:1118
NavPVT last_nav_pvt_
The last received NavPVT message.
Definition: node.h:929
ROSCONSOLE_DECL void initialize()
ublox_msgs::CfgNMEA7 cfg_nmea_
Used to configure NMEA (if set_nmea_)
Definition: node.h:974
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the fix diagnostics from Nav PVT message.
Definition: node.h:867
FixDiagnostic(std::string name, double freq_tol, int freq_window, double stamp_min)
Add a topic diagnostic to the diagnostic updater for fix topics.
Definition: node.h:200
bool enable_gps_
Whether or not to enable GPS.
Definition: node.h:932
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
Definition: node.h:635
uint32_t sv_in_min_dur_
Measurement period used during Survey-In [s].
Definition: node.h:1251
static constexpr uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
Definition: node.h:90
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
Definition: node.h:643
bool enable_beidou_
Whether or not to enable the BeiDuo GNSS.
Definition: node.h:1016
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
void getRosParams()
Get the FTS parameters.
Definition: node.h:1132
double max_freq
Maximum allow frequency of topic.
Definition: node.h:220
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
Implements functions for High Precision GNSS Reference station devices.
Definition: node.h:1160
bool set_nmea_
Whether or not to configure the NMEA settings.
Definition: node.h:1020
void publish(const MessageT &m, const std::string &topic)
Publish a ROS message of type MessageT.
Definition: node.h:422
geometry_msgs::TwistWithCovarianceStamped velocity_
The last Twist based on last_nav_vel_.
Definition: node.h:738
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:120
sensor_msgs::NavSatFix fix_
The last NavSatFix based on last_nav_pos_.
Definition: node.h:736
bool enable_sbas_
Whether or not to enable SBAS.
Definition: node.h:938
#define ROS_WARN(...)
bool set_nmea_
Whether or not to configure the NMEA settings.
Definition: node.h:743
diagnostic_updater::HeaderlessTopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
Definition: node.h:177
ublox_msgs::NavSVIN last_nav_svin_
The last received Nav SVIN message.
Definition: node.h:1222
bool set_usb_
Whether to configure the USB port.
Definition: node.h:621
ublox_msgs::NavRELPOSNED last_rel_pos_
Last relative position (used for diagnostic updater)
Definition: node.h:1323
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
Definition: node.h:614
bool configureUblox()
Configure FTS settings.
Definition: node.h:1141
bool svin_reset_
Whether to always reset the survey-in during configuration.
Definition: node.h:1248
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 lla_flag_
True if coordinates are in LLA, false if ECEF.
Definition: node.h:1230
bool use_adr_
Whether or not to enable dead reckoning.
Definition: node.h:1112
ublox_msgs::NavVELNED last_nav_vel_
The last received navigation velocity.
Definition: node.h:732
static constexpr uint32_t kROSQueueSize
Queue size for ROS publishers.
Definition: node.h:88
bool enable_galileo_
Whether or not to enable the Galileo GNSS.
Definition: node.h:1014
void subscribe()
bool supportsGnss(std::string gnss)
Definition: node.h:433
bool config_on_startup_flag_
Flag for enabling configuration on startup.
Definition: node.h:126
bool enable_imes_
Whether or not to enable the IMES GNSS.
Definition: node.h:1018
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
Definition: node.h:618
ublox_msgs::NavRELPOSNED9 last_rel_pos_
Last relative position (used for diagnostic updater)
Definition: node.h:1352
bool enable_qzss_
Whether or not to enable QZSS.
Definition: node.h:936
std::set< std::string > supported
Which GNSS are supported by the device.
Definition: node.h:105
sensor_msgs::Imu imu_
Definition: node.h:1116
Initialization mode (before configuration)
Definition: node.h:1258
ublox_msgs::NavPOSLLH last_nav_pos_
The last received navigation position.
Definition: node.h:730
void subscribe()
Subscribe to FTS messages.
Definition: node.h:1147
uint8_t dgnss_mode_
The DGNSS mode.
Definition: node.h:1327
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
Definition: node.h:103
UbloxTopicDiagnostic(std::string topic, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
Definition: node.h:144
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
Definition: node.h:100
void initializeRosDiagnostics()
Initialize the ROS diagnostics for the ADR/UDR device.
Definition: node.h:1105
Time mode disabled.
Definition: node.h:1260
ublox_msgs::NavSOL last_nav_sol_
The last received num SVs used.
Definition: node.h:734
long toUtcSeconds(const NavPVT &msg)
Convert date/time to UTC time in seconds.
Definition: utils.h:16
void getRosParams()
Does nothing since there are no Raw Data product specific settings.
Definition: node.h:1046
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
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
sensor_msgs::Imu imu_
Definition: node.h:1349
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
bool set_nmea_
Whether or not to Configure the NMEA settings.
Definition: node.h:976
diagnostic_updater::TopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
Definition: node.h:216
bool set_dat_
If true, set configure the User-Defined Datum.
Definition: node.h:629
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
Definition: node.h:124
UbloxTopicDiagnostic(std::string topic, double freq_min, double freq_max, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
Definition: node.h:165
std::vector< int8_t > arp_position_hp_
Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9].
Definition: node.h:1236
uint8_t tmode3_
TMODE3 to set, such as disabled, survey-in, fixed.
Definition: node.h:1225
sensor_msgs::TimeReference t_ref_
Definition: node.h:1392
double rate_
The measurement rate in Hz.
Definition: node.h:627
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
ublox_msgs::CfgNMEA cfg_nmea_
Desired NMEA configuration.
Definition: node.h:1022
This interface is used to add functionality to the main node.
Definition: node.h:443
std::vector< boost::shared_ptr< UbloxTopicDiagnostic > > freq_diagnostics_
Topic diagnostic updaters.
Definition: node.h:1068
uint8_t tim_rate_
rate for TIM-TM2
Definition: node.h:647
Handles communication with and configuration of the u-blox device.
Definition: gps.h:68
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
Definition: node.h:616
int min(int a, int b)
Topic diagnostics for u-blox messages.
Definition: node.h:130
uint32_t qzss_sig_cfg_
The QZSS Signal configuration, see CfgGNSS message.
Definition: node.h:940
bool enable_glonass_
Whether or not to enable GLONASS.
Definition: node.h:934
static Time now()
std::string device_
Device port.
Definition: node.h:602
bool configureUblox()
Does nothing since there are no Raw Data product specific settings.
Definition: node.h:1052
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
Definition: node.h:639
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
Definition: node.h:623
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
Definition: node.h:98
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
uint8_t dr_limit_
Dead reckoning limit parameter.
Definition: node.h:641
bool enable_sbas_
Whether or not to enable SBAS.
Definition: node.h:633
double min_freq
Minimum allow frequency of topic.
Definition: node.h:218
double min_freq
Minimum allow frequency of topic.
Definition: node.h:179
static constexpr uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
Definition: node.h:94
Implements functions for firmware version 6.
Definition: node.h:676
std::string frame_id
The ROS frame ID of this device.
Definition: node.h:113
Fixed mode (should switch to time mode almost immediately)
Definition: node.h:1259


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