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 #include <nmea_msgs/Sentence.h>
54 // Other U-Blox package includes
55 #include <ublox_msgs/ublox_msgs.h>
56 // Ublox GPS includes
57 #include <ublox_gps/gps.h>
58 #include <ublox_gps/utils.h>
59 #include <ublox_gps/raw_data_pa.h>
60 
61 #include <rtcm_msgs/Message.h>
62 
63 // This file declares the ComponentInterface which acts as a high level
64 // interface for u-blox firmware, product categories, etc. It contains methods
65 // to configure the u-blox and subscribe to u-blox messages.
66 //
67 // This file also declares UbloxNode which implements ComponentInterface and is
68 // the main class and ros node. it implements functionality which applies to
69 // any u-blox device, regardless of the firmware version or product type.
70 // The class is designed in compositional style; it contains ComponentInterfaces
71 // which implement features specific to the device based on its firmware version
72 // and product category. UbloxNode calls the public methods of each component.
73 //
74 // This file declares UbloxFirmware is an abstract class which implements
75 // ComponentInterface and functions generic to all firmware (such as the
76 // initializing the fix diagnostics). Subclasses of UbloxFirmware for firmware
77 // versions 6-8 are also declared in this file.
78 //
79 // Lastly, this file declares classes for each product category which also
80 // implement u-blox interface, currently only the class for High Precision
81 // GNSS devices has been fully implemented and tested.
82 
88 namespace ublox_node {
89 
91 constexpr static uint32_t kROSQueueSize = 1;
93 constexpr static uint16_t kDefaultMeasPeriod = 250;
95 constexpr static uint32_t kSubscribeRate = 1;
97 constexpr static uint32_t kNavSvInfoSubscribeRate = 20;
98 
99 // ROS objects
104 
108 std::set<std::string> supported;
110 
114 std::map<std::string, bool> enabled;
116 std::string frame_id;
121 uint16_t meas_rate;
123 uint16_t nav_rate;
125 std::vector<uint8_t> rtcm_ids;
127 std::vector<uint8_t> rtcm_rates;
130 
131 
135 
136  // Must not copy this struct (would confuse FrequencyStatusParam pointers)
138 
147  UbloxTopicDiagnostic (std::string topic, double freq_tol, int freq_window) {
148  const double target_freq = 1.0 / (meas_rate * 1e-3 * nav_rate); // Hz
149  min_freq = target_freq;
150  max_freq = target_freq;
152  freq_tol, freq_window);
154  *updater,
155  freq_param);
156  }
157 
168  UbloxTopicDiagnostic (std::string topic, double freq_min, double freq_max,
169  double freq_tol, int freq_window) {
170  min_freq = freq_min;
171  max_freq = freq_max;
173  freq_tol, freq_window);
175  *updater,
176  freq_param);
177  }
178 
182  double min_freq;
184  double max_freq;
185 };
186 
190 
191  // Must not copy this struct (would confuse FrequencyStatusParam pointers)
192  FixDiagnostic(const FixDiagnostic&) = delete;
193 
203  FixDiagnostic (std::string name, double freq_tol, int freq_window,
204  double stamp_min) {
205  const double target_freq = 1.0 / (meas_rate * 1e-3 * nav_rate); // Hz
206  min_freq = target_freq;
207  max_freq = target_freq;
209  freq_tol, freq_window);
210  double stamp_max = meas_rate * 1e-3 * (1 + freq_tol);
211  diagnostic_updater::TimeStampStatusParam time_param(stamp_min, stamp_max);
213  *updater,
214  freq_param,
215  time_param);
216  }
217 
221  double min_freq;
223  double max_freq;
224 };
225 
228 
244 uint8_t modelFromString(const std::string& model);
245 
255 uint8_t fixModeFromString(const std::string& mode);
256 
264 template <typename V, typename T>
265 void checkMin(V val, T min, std::string name) {
266  if(val < min) {
267  std::stringstream oss;
268  oss << "Invalid settings: " << name << " must be > " << min;
269  throw std::runtime_error(oss.str());
270  }
271 }
272 
281 template <typename V, typename T>
282 void checkRange(V val, T min, T max, std::string name) {
283  if(val < min || val > max) {
284  std::stringstream oss;
285  oss << "Invalid settings: " << name << " must be in range [" << min <<
286  ", " << max << "].";
287  throw std::runtime_error(oss.str());
288  }
289 }
290 
299 template <typename V, typename T>
300 void checkRange(std::vector<V> val, T min, T max, std::string name) {
301  for(size_t i = 0; i < val.size(); i++) {
302  std::stringstream oss;
303  oss << name << "[" << i << "]";
304  checkRange(val[i], min, max, oss.str());
305  }
306 }
307 
315 template <typename U>
316 bool getRosUint(const std::string& key, U &u) {
317  int param;
318  if (!nh->getParam(key, param)) return false;
319  // Check the bounds
320  U min = std::numeric_limits<U>::lowest();
321  U max = std::numeric_limits<U>::max();
322  checkRange(param, min, max, key);
323  // set the output
324  u = (U) param;
325  return true;
326 }
327 
336 template <typename U, typename V>
337 void getRosUint(const std::string& key, U &u, V default_val) {
338  if(!getRosUint(key, u))
339  u = default_val;
340 }
341 
347 template <typename U>
348 bool getRosUint(const std::string& key, std::vector<U> &u) {
349  std::vector<int> param;
350  if (!nh->getParam(key, param)) return false;
351 
352  // Check the bounds
353  U min = std::numeric_limits<U>::lowest();
354  U max = std::numeric_limits<U>::max();
355  checkRange(param, min, max, key);
356 
357  // set the output
358  u.insert(u.begin(), param.begin(), param.end());
359  return true;
360 }
361 
369 template <typename I>
370 bool getRosInt(const std::string& key, I &u) {
371  int param;
372  if (!nh->getParam(key, param)) return false;
373  // Check the bounds
374  I min = std::numeric_limits<I>::lowest();
375  I max = std::numeric_limits<I>::max();
376  checkRange(param, min, max, key);
377  // set the output
378  u = (I) param;
379  return true;
380 }
381 
390 template <typename U, typename V>
391 void getRosInt(const std::string& key, U &u, V default_val) {
392  if(!getRosInt(key, u))
393  u = default_val;
394 }
395 
401 template <typename I>
402 bool getRosInt(const std::string& key, std::vector<I> &i) {
403  std::vector<int> param;
404  if (!nh->getParam(key, param)) return false;
405 
406  // Check the bounds
407  I min = std::numeric_limits<I>::lowest();
408  I max = std::numeric_limits<I>::max();
409  checkRange(param, min, max, key);
410 
411  // set the output
412  i.insert(i.begin(), param.begin(), param.end());
413  return true;
414 }
415 
424 template <typename MessageT>
425 void publish(const MessageT& m, const std::string& topic) {
426  static ros::Publisher publisher = nh->advertise<MessageT>(topic,
427  kROSQueueSize);
428  publisher.publish(m);
429 }
430 
431 void publish_nmea(const std::string& sentence, const std::string& topic) {
432  static ros::Publisher publisher = nh->advertise<nmea_msgs::Sentence>(topic,
433  kROSQueueSize);
434  nmea_msgs::Sentence m;
435  m.header.stamp = ros::Time::now();
436  m.header.frame_id = frame_id;
437  m.sentence = sentence;
438  publisher.publish(m);
439 }
440 
446 bool supportsGnss(std::string gnss) {
447  return supported.count(gnss) > 0;
448 }
449 
457  public:
463  virtual void getRosParams() = 0;
464 
469  virtual bool configureUblox() = 0;
470 
476  virtual void initializeRosDiagnostics() = 0;
477 
481  virtual void subscribe() = 0;
482 };
483 
485 
501 class UbloxNode : public virtual ComponentInterface {
502  public:
504  constexpr static double kKeepAlivePeriod = 10.0;
506  constexpr static double kPollDuration = 1.0;
507  // Constants used for diagnostic frequency updater
509  constexpr static float kDiagnosticPeriod = 0.2;
511  constexpr static double kFixFreqTol = 0.15;
513  constexpr static double kFixFreqWindow = 10;
515  constexpr static double kTimeStampStatusMin = 0;
516 
520  UbloxNode();
521 
525  void getRosParams();
526 
531  bool configureUblox();
532 
536  void subscribe();
537 
541  void initializeRosDiagnostics();
542 
546  void printInf(const ublox_msgs::Inf &m, uint8_t id);
547 
548  private:
549 
553  void initializeIo();
554 
559  void initialize();
560 
564  void shutdown();
565 
570  bool resetDevice();
571 
577  void processMonVer();
578 
583  void addFirmwareInterface();
584 
592  void addProductInterface(std::string product_category,
593  std::string ref_rov = "");
594 
599  void keepAlive(const ros::TimerEvent& event);
600 
605  void pollMessages(const ros::TimerEvent& event);
606 
610  void configureInf();
611 
613 
617  std::vector<boost::shared_ptr<ComponentInterface> > components_;
618 
620  float protocol_version_ = 0;
621  // Variables set from parameter server
623  std::string device_;
625  std::string dynamic_model_;
627  std::string fix_mode_;
629  uint8_t dmodel_;
631  uint8_t fmode_;
633  uint32_t baudrate_;
635  uint16_t uart_in_;
637  uint16_t uart_out_;
639  uint16_t usb_tx_;
641 
642  bool set_usb_;
644  uint16_t usb_in_;
646  uint16_t usb_out_ ;
648  double rate_;
650  bool set_dat_;
652  ublox_msgs::CfgDAT cfg_dat_;
658  uint8_t sbas_usage_;
660  uint8_t max_sbas_;
662  uint8_t dr_limit_;
664  ublox_msgs::CfgCFG load_;
666  ublox_msgs::CfgCFG save_;
668  uint8_t tim_rate_;
669 
672 };
673 
679 class UbloxFirmware : public virtual ComponentInterface {
680  public:
684  void initializeRosDiagnostics();
685 
686  protected:
690  virtual void fixDiagnostic(
692 };
693 
698  public:
699  UbloxFirmware6();
700 
704  void getRosParams();
705 
710  bool configureUblox();
711 
715  void subscribe();
716 
717  protected:
722  void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper& stat);
723 
724  private:
732  void callbackNavPosLlh(const ublox_msgs::NavPOSLLH& m);
733 
740  void callbackNavVelNed(const ublox_msgs::NavVELNED& m);
741 
748  void callbackNavSol(const ublox_msgs::NavSOL& m);
749 
751  ublox_msgs::NavPOSLLH last_nav_pos_;
753  ublox_msgs::NavVELNED last_nav_vel_;
755  ublox_msgs::NavSOL last_nav_sol_;
757  sensor_msgs::NavSatFix fix_;
759  geometry_msgs::TwistWithCovarianceStamped velocity_;
760 
762  ublox_msgs::CfgNMEA6 cfg_nmea_;
764  bool set_nmea_;
765 };
766 
776 template<typename NavPVT>
778  public:
787  void callbackNavPvt(const NavPVT& m) {
788  if(enabled["nav_pvt"]) {
789  // NavPVT publisher
790  static ros::Publisher publisher = nh->advertise<NavPVT>("navpvt",
791  kROSQueueSize);
792  publisher.publish(m);
793  }
794 
795  //
796  // NavSatFix message
797  //
798  static ros::Publisher fixPublisher =
799  nh->advertise<sensor_msgs::NavSatFix>("fix", kROSQueueSize);
800 
801  sensor_msgs::NavSatFix fix;
802  fix.header.frame_id = frame_id;
803  // set the timestamp
804  uint8_t valid_time = m.VALID_DATE | m.VALID_TIME | m.VALID_FULLY_RESOLVED;
805  if (((m.valid & valid_time) == valid_time) &&
806  (m.flags2 & m.FLAGS2_CONFIRMED_AVAILABLE)) {
807  // Use NavPVT timestamp since it is valid
808  // The time in nanoseconds from the NavPVT message can be between -1e9 and 1e9
809  // The ros time uses only unsigned values, so a negative nano seconds must be
810  // converted to a positive value
811  if (m.nano < 0) {
812  fix.header.stamp.sec = toUtcSeconds(m) - 1;
813  fix.header.stamp.nsec = (uint32_t)(m.nano + 1e9);
814  }
815  else {
816  fix.header.stamp.sec = toUtcSeconds(m);
817  fix.header.stamp.nsec = (uint32_t)(m.nano);
818  }
819  } else {
820  // Use ROS time since NavPVT timestamp is not valid
821  fix.header.stamp = ros::Time::now();
822  }
823  // Set the LLA
824  fix.latitude = m.lat * 1e-7; // to deg
825  fix.longitude = m.lon * 1e-7; // to deg
826  fix.altitude = m.height * 1e-3; // to [m]
827  // Set the Fix status
828  bool fixOk = m.flags & m.FLAGS_GNSS_FIX_OK;
829  if (fixOk && m.fixType >= m.FIX_TYPE_2D) {
830  fix.status.status = fix.status.STATUS_FIX;
831  if(m.flags & m.CARRIER_PHASE_FIXED)
832  fix.status.status = fix.status.STATUS_GBAS_FIX;
833  }
834  else {
835  fix.status.status = fix.status.STATUS_NO_FIX;
836  }
837  // Set the service based on GNSS configuration
838  fix.status.service = fix_status_service;
839 
840  // Set the position covariance
841  const double varH = pow(m.hAcc / 1000.0, 2); // to [m^2]
842  const double varV = pow(m.vAcc / 1000.0, 2); // to [m^2]
843  fix.position_covariance[0] = varH;
844  fix.position_covariance[4] = varH;
845  fix.position_covariance[8] = varV;
846  fix.position_covariance_type =
847  sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
848 
849  fixPublisher.publish(fix);
850 
851  //
852  // Twist message
853  //
854  static ros::Publisher velocityPublisher =
855  nh->advertise<geometry_msgs::TwistWithCovarianceStamped>("fix_velocity",
856  kROSQueueSize);
857  geometry_msgs::TwistWithCovarianceStamped velocity;
858  velocity.header.stamp = fix.header.stamp;
859  velocity.header.frame_id = frame_id;
860 
861  // convert to XYZ linear velocity [m/s] in ENU
862  velocity.twist.twist.linear.x = m.velE * 1e-3;
863  velocity.twist.twist.linear.y = m.velN * 1e-3;
864  velocity.twist.twist.linear.z = -m.velD * 1e-3;
865  // Set the covariance
866  const double covSpeed = pow(m.sAcc * 1e-3, 2);
867  const int cols = 6;
868  velocity.twist.covariance[cols * 0 + 0] = covSpeed;
869  velocity.twist.covariance[cols * 1 + 1] = covSpeed;
870  velocity.twist.covariance[cols * 2 + 2] = covSpeed;
871  velocity.twist.covariance[cols * 3 + 3] = -1; // angular rate unsupported
872 
873  velocityPublisher.publish(velocity);
874 
875  //
876  // Update diagnostics
877  //
878  last_nav_pvt_ = m;
879  freq_diag->diagnostic->tick(fix.header.stamp);
880  updater->update();
881  }
882 
883  protected:
884 
889  // check the last message, convert to diagnostic
890  if (last_nav_pvt_.fixType ==
891  ublox_msgs::NavPVT::FIX_TYPE_DEAD_RECKONING_ONLY) {
892  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
893  stat.message = "Dead reckoning only";
894  } else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_2D) {
895  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
896  stat.message = "2D fix";
897  } else if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_3D) {
898  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
899  stat.message = "3D fix";
900  } else if (last_nav_pvt_.fixType ==
901  ublox_msgs::NavPVT::FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED) {
902  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
903  stat.message = "GPS and dead reckoning combined";
904  } else if (last_nav_pvt_.fixType ==
905  ublox_msgs::NavPVT::FIX_TYPE_TIME_ONLY) {
906  stat.level = diagnostic_msgs::DiagnosticStatus::OK;
907  stat.message = "Time only fix";
908  }
909 
910  // Check whether differential GNSS available
911  if (last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_DIFF_SOLN) {
912  stat.message += ", DGNSS";
913  }
914  // If DGNSS, then update the differential solution status
915  if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FLOAT) {
916  stat.message += ", FLOAT FIX";
917  } else if (last_nav_pvt_.flags & ublox_msgs::NavPVT::CARRIER_PHASE_FIXED) {
918  stat.message += ", RTK FIX";
919  }
920 
921  // If fix not ok (w/in DOP & Accuracy Masks), raise the diagnostic level
922  if (!(last_nav_pvt_.flags & ublox_msgs::NavPVT::FLAGS_GNSS_FIX_OK)) {
923  stat.level = diagnostic_msgs::DiagnosticStatus::WARN;
924  stat.message += ", fix not ok";
925  }
926  // Raise diagnostic level to error if no fix
927  if (last_nav_pvt_.fixType == ublox_msgs::NavPVT::FIX_TYPE_NO_FIX) {
928  stat.level = diagnostic_msgs::DiagnosticStatus::ERROR;
929  stat.message = "No fix";
930  }
931 
932  // append last fix position
933  stat.add("iTOW [ms]", last_nav_pvt_.iTOW);
934  std::ostringstream gnss_coor;
935  gnss_coor << std::fixed << std::setprecision(7);
936  gnss_coor << (last_nav_pvt_.lat * 1e-7);
937  stat.add("Latitude [deg]", gnss_coor.str());
938  gnss_coor.str("");
939  gnss_coor.clear();
940  gnss_coor << (last_nav_pvt_.lon * 1e-7);
941  stat.add("Longitude [deg]", gnss_coor.str());
942  stat.add("Altitude [m]", last_nav_pvt_.height * 1e-3);
943  stat.add("Height above MSL [m]", last_nav_pvt_.hMSL * 1e-3);
944  stat.add("Horizontal Accuracy [m]", last_nav_pvt_.hAcc * 1e-3);
945  stat.add("Vertical Accuracy [m]", last_nav_pvt_.vAcc * 1e-3);
946  stat.add("# SVs used", (int)last_nav_pvt_.numSV);
947  }
948 
951  // Whether or not to enable the given GNSS
961  uint32_t qzss_sig_cfg_;
962 };
963 
967 class UbloxFirmware7 : public UbloxFirmware7Plus<ublox_msgs::NavPVT7> {
968  public:
969  UbloxFirmware7();
970 
976  void getRosParams();
977 
981  bool configureUblox();
982 
988  void subscribe();
989 
990  private:
992 
995  ublox_msgs::CfgNMEA7 cfg_nmea_;
997  bool set_nmea_;
998 };
999 
1003 class UbloxFirmware8 : public UbloxFirmware7Plus<ublox_msgs::NavPVT> {
1004  public:
1005  UbloxFirmware8();
1006 
1012  void getRosParams();
1013 
1021  bool configureUblox();
1022 
1030  void subscribe();
1031 
1032  private:
1033  // Set from ROS parameters
1043  ublox_msgs::CfgNMEA cfg_nmea_;
1046 };
1047 
1054 };
1055 
1059 class RawDataProduct: public virtual ComponentInterface {
1060  public:
1061  static constexpr double kRtcmFreqTol = 0.15;
1062  static constexpr int kRtcmFreqWindow = 25;
1063 
1067  void getRosParams() {}
1068 
1073  bool configureUblox() { return true; }
1074 
1080  void subscribe();
1081 
1085  void initializeRosDiagnostics();
1086 
1087  private:
1089  std::vector<boost::shared_ptr<UbloxTopicDiagnostic> > freq_diagnostics_;
1090 };
1091 
1096 class AdrUdrProduct: public virtual ComponentInterface {
1097  public:
1098  AdrUdrProduct(float protocol_version);
1099 
1105  void getRosParams();
1106 
1112  bool configureUblox();
1113 
1120  void subscribe();
1121 
1127  ROS_WARN("ROS Diagnostics specific to u-blox ADR/UDR devices is %s",
1128  "unimplemented. See AdrUdrProduct class in node.h & node.cpp.");
1129  }
1130 
1131  protected:
1133  bool use_adr_;
1135 
1136 
1137  sensor_msgs::Imu imu_;
1138  sensor_msgs::TimeReference t_ref_;
1139  ublox_msgs::TimTM2 timtm2;
1140 
1141  void callbackEsfMEAS(const ublox_msgs::EsfMEAS &m);
1142 };
1143 
1148 class FtsProduct: public virtual ComponentInterface {
1153  void getRosParams() {
1154  ROS_WARN("Functionality specific to u-blox FTS devices is %s",
1155  "unimplemented. See FtsProduct class in node.h & node.cpp.");
1156  }
1157 
1162  bool configureUblox() { return false; }
1163 
1168  void subscribe() {}
1169 
1175 };
1176 
1181 class HpgRefProduct: public virtual ComponentInterface {
1182  public:
1192  void getRosParams();
1193 
1202  bool configureUblox();
1203 
1209  void subscribe();
1210 
1214  void initializeRosDiagnostics();
1215 
1224  void callbackNavSvIn(ublox_msgs::NavSVIN m);
1225 
1226  protected:
1233  void tmode3Diagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
1234 
1240  bool setTimeMode();
1241 
1243  ublox_msgs::NavSVIN last_nav_svin_;
1244 
1246  uint8_t tmode3_;
1247 
1248  // TMODE3 = Fixed mode settings
1250 
1253 
1254  std::vector<float> arp_position_;
1256 
1257  std::vector<int8_t> arp_position_hp_;
1259 
1261 
1262  // Settings for TMODE3 = Survey-in
1264 
1271 
1272  uint32_t sv_in_min_dur_;
1274 
1276 
1278  enum {
1283  TIME
1284  } mode_;
1285 };
1286 
1290 class HpgRovProduct: public virtual ComponentInterface {
1291  public:
1292  // Constants for diagnostic updater
1294  constexpr static double kRtcmFreqMin = 1;
1296  constexpr static double kRtcmFreqMax = 10;
1298  constexpr static double kRtcmFreqTol = 0.1;
1300  constexpr static int kRtcmFreqWindow = 25;
1306  void getRosParams();
1307 
1314  bool configureUblox();
1315 
1319  void subscribe();
1320 
1325  void initializeRosDiagnostics();
1326 
1327  protected:
1332  void carrierPhaseDiagnostics(
1334 
1340  void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED &m);
1341 
1342 
1344  ublox_msgs::NavRELPOSNED last_rel_pos_;
1345 
1347 
1348  uint8_t dgnss_mode_;
1349 
1352 };
1353 
1354 class HpPosRecProduct: public virtual HpgRefProduct {
1355  public:
1359  void subscribe();
1360 
1361  protected:
1362 
1366  void callbackNavHpPosLlh(const ublox_msgs::NavHPPOSLLH& m);
1367 
1373  void callbackNavRelPosNed(const ublox_msgs::NavRELPOSNED9 &m);
1374 
1375  sensor_msgs::Imu imu_;
1376 
1378  ublox_msgs::NavRELPOSNED9 last_rel_pos_;
1379 };
1380 
1385 class TimProduct: public virtual ComponentInterface {
1390  void getRosParams();
1391 
1396  bool configureUblox();
1397 
1403  void subscribe();
1404 
1409  void initializeRosDiagnostics();
1410 
1411  protected:
1416  void callbackTimTM2(const ublox_msgs::TimTM2 &m);
1417 
1418  sensor_msgs::TimeReference t_ref_;
1419 };
1420 
1421 }
1422 
1423 #endif
uint32_t baudrate_
UART1 baudrate.
Definition: node.h:633
static constexpr uint32_t kSubscribeRate
Default subscribe Rate to u-blox messages [Hz].
Definition: node.h:95
float fixed_pos_acc_
Fixed Position Accuracy [m].
Definition: node.h:1260
std::map< std::string, bool > enabled
Whether or not to publish the given ublox message.
Definition: node.h:114
float sv_in_acc_lim_
Survey in accuracy limit [m].
Definition: node.h:1275
RawDataStreamPa rawDataStreamPa_
raw data stream logging
Definition: node.h:671
boost::shared_ptr< ComponentInterface > ComponentPtr
Definition: node.h:484
int fix_status_service
Definition: node.h:119
uint8_t fmode_
Set from fix mode string.
Definition: node.h:631
Implements functions for Time Sync products.
Definition: node.h:1385
Implements functions for firmware version 7.
Definition: node.h:967
uint8_t sbas_usage_
SBAS Usage parameter (see CfgSBAS message)
Definition: node.h:658
sensor_msgs::TimeReference t_ref_
Definition: node.h:1138
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:370
uint16_t usb_out_
USB out protocol (see CfgPRT message for constants)
Definition: node.h:646
This abstract class represents a firmware component.
Definition: node.h:679
Topic diagnostics for fix / fix_velocity messages.
Definition: node.h:188
bool clear_bbr_
Whether to clear the flash memory during configuration.
Definition: node.h:1045
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:762
double max_freq
Maximum allow frequency of topic.
Definition: node.h:184
std::vector< float > arp_position_
Antenna Reference Point Position [m] or [deg].
Definition: node.h:1254
void initializeRosDiagnostics()
Adds diagnostic updaters for FTS status.
Definition: node.h:1174
UbloxTopicDiagnostic freq_rtcm_
The RTCM topic frequency diagnostic updater.
Definition: node.h:1351
ublox_msgs::TimTM2 timtm2
Definition: node.h:1139
NavPVT last_nav_pvt_
The last received NavPVT message.
Definition: node.h:950
ROSCONSOLE_DECL void initialize()
ublox_msgs::CfgNMEA7 cfg_nmea_
Used to configure NMEA (if set_nmea_)
Definition: node.h:995
void fixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Update the fix diagnostics from Nav PVT message.
Definition: node.h:888
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:203
bool enable_gps_
Whether or not to enable GPS.
Definition: node.h:953
bool enable_ppp_
Whether or not to enable PPP (advanced setting)
Definition: node.h:656
uint32_t sv_in_min_dur_
Measurement period used during Survey-In [s].
Definition: node.h:1272
static constexpr uint16_t kDefaultMeasPeriod
Default measurement period for HPG devices.
Definition: node.h:93
ublox_msgs::CfgCFG load_
Parameters to load from non-volatile memory during configuration.
Definition: node.h:664
bool enable_beidou_
Whether or not to enable the BeiDuo GNSS.
Definition: node.h:1037
Implements functions for firmware version 8.
Definition: node.h:1003
std::string fix_mode_
Fix mode type.
Definition: node.h:627
std::vector< boost::shared_ptr< ComponentInterface > > components_
The u-blox node components.
Definition: node.h:617
Implements functions for High Precision GNSS Rover devices.
Definition: node.h:1290
void getRosParams()
Get the FTS parameters.
Definition: node.h:1153
double max_freq
Maximum allow frequency of topic.
Definition: node.h:223
Implements functions for Automotive Dead Reckoning (ADR) and Untethered Dead Reckoning (UDR) Devices...
Definition: node.h:1096
void callbackNavPvt(const NavPVT &m)
Publish a NavSatFix and TwistWithCovarianceStamped messages.
Definition: node.h:787
Implements functions for High Precision GNSS Reference station devices.
Definition: node.h:1181
bool set_nmea_
Whether or not to configure the NMEA settings.
Definition: node.h:1041
void publish(const MessageT &m, const std::string &topic)
Publish a ROS message of type MessageT.
Definition: node.h:425
geometry_msgs::TwistWithCovarianceStamped velocity_
The last Twist based on last_nav_vel_.
Definition: node.h:759
uint16_t nav_rate
Navigation rate in measurement cycles, see CfgRate.msg.
Definition: node.h:123
sensor_msgs::NavSatFix fix_
The last NavSatFix based on last_nav_pos_.
Definition: node.h:757
bool enable_sbas_
Whether or not to enable SBAS.
Definition: node.h:959
#define ROS_WARN(...)
bool set_nmea_
Whether or not to configure the NMEA settings.
Definition: node.h:764
diagnostic_updater::HeaderlessTopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
Definition: node.h:180
ublox_msgs::NavSVIN last_nav_svin_
The last received Nav SVIN message.
Definition: node.h:1243
bool set_usb_
Whether to configure the USB port.
Definition: node.h:642
ublox_msgs::NavRELPOSNED last_rel_pos_
Last relative position (used for diagnostic updater)
Definition: node.h:1344
uint16_t uart_in_
UART in protocol (see CfgPRT message for constants)
Definition: node.h:635
bool configureUblox()
Configure FTS settings.
Definition: node.h:1162
bool svin_reset_
Whether to always reset the survey-in during configuration.
Definition: node.h:1269
ublox_msgs::CfgDAT cfg_dat_
User-defined Datum.
Definition: node.h:652
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:1148
bool lla_flag_
True if coordinates are in LLA, false if ECEF.
Definition: node.h:1251
bool use_adr_
Whether or not to enable dead reckoning.
Definition: node.h:1133
ublox_msgs::NavVELNED last_nav_vel_
The last received navigation velocity.
Definition: node.h:753
static constexpr uint32_t kROSQueueSize
Queue size for ROS publishers.
Definition: node.h:91
bool enable_galileo_
Whether or not to enable the Galileo GNSS.
Definition: node.h:1035
void subscribe()
bool supportsGnss(std::string gnss)
Definition: node.h:446
bool config_on_startup_flag_
Flag for enabling configuration on startup.
Definition: node.h:129
bool enable_imes_
Whether or not to enable the IMES GNSS.
Definition: node.h:1039
uint16_t usb_tx_
USB TX Ready Pin configuration (see CfgPRT message for constants)
Definition: node.h:639
ublox_msgs::NavRELPOSNED9 last_rel_pos_
Last relative position (used for diagnostic updater)
Definition: node.h:1378
bool enable_qzss_
Whether or not to enable QZSS.
Definition: node.h:957
void publish(const boost::shared_ptr< M > &message) const
std::set< std::string > supported
Which GNSS are supported by the device.
Definition: node.h:108
sensor_msgs::Imu imu_
Definition: node.h:1137
Initialization mode (before configuration)
Definition: node.h:1279
ublox_msgs::NavPOSLLH last_nav_pos_
The last received navigation position.
Definition: node.h:751
void subscribe()
Subscribe to FTS messages.
Definition: node.h:1168
uint8_t dgnss_mode_
The DGNSS mode.
Definition: node.h:1348
ublox_gps::Gps gps
Handles communication with the U-Blox Device.
Definition: node.h:106
UbloxTopicDiagnostic(std::string topic, double freq_tol, int freq_window)
Add a topic diagnostic to the diagnostic updater for.
Definition: node.h:147
boost::shared_ptr< ros::NodeHandle > nh
Node Handle for GPS node.
Definition: node.h:103
void initializeRosDiagnostics()
Initialize the ROS diagnostics for the ADR/UDR device.
Definition: node.h:1126
Time mode disabled.
Definition: node.h:1281
ublox_msgs::NavSOL last_nav_sol_
The last received num SVs used.
Definition: node.h:755
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:1067
std::vector< uint8_t > rtcm_ids
IDs of RTCM out messages to configure.
Definition: node.h:125
ublox_msgs::CfgCFG save_
Parameters to save to non-volatile memory after configuration.
Definition: node.h:666
Implements functions for firmware version 9. For now it simply re-uses the firmware version 8 class b...
Definition: node.h:1053
void checkMin(V val, T min, std::string name)
Check that the parameter is above the minimum.
Definition: node.h:265
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:1375
void checkRange(V val, T min, T max, std::string name)
Check that the parameter is in the range.
Definition: node.h:282
uint8_t dmodel_
Set from dynamic model string.
Definition: node.h:629
uint16_t meas_rate
The measurement [ms], see CfgRate.msg.
Definition: node.h:121
bool set_nmea_
Whether or not to Configure the NMEA settings.
Definition: node.h:997
diagnostic_updater::TopicDiagnostic * diagnostic
Topic frequency diagnostic updater.
Definition: node.h:219
bool set_dat_
If true, set configure the User-Defined Datum.
Definition: node.h:650
std::vector< uint8_t > rtcm_rates
Rates of RTCM out messages. Size must be the same as rtcm_ids.
Definition: node.h:127
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:168
std::vector< int8_t > arp_position_hp_
Antenna Reference Point Position High Precision [0.1 mm] or [deg * 1e-9].
Definition: node.h:1257
uint8_t tmode3_
TMODE3 to set, such as disabled, survey-in, fixed.
Definition: node.h:1246
sensor_msgs::TimeReference t_ref_
Definition: node.h:1418
double rate_
The measurement rate in Hz.
Definition: node.h:648
boost::shared_ptr< FixDiagnostic > freq_diag
fix frequency diagnostic updater
Definition: node.h:227
std::string dynamic_model_
dynamic model type
Definition: node.h:625
ublox_msgs::CfgNMEA cfg_nmea_
Desired NMEA configuration.
Definition: node.h:1043
This interface is used to add functionality to the main node.
Definition: node.h:456
std::vector< boost::shared_ptr< UbloxTopicDiagnostic > > freq_diagnostics_
Topic diagnostic updaters.
Definition: node.h:1089
uint8_t tim_rate_
rate for TIM-TM2
Definition: node.h:668
Handles communication with and configuration of the u-blox device.
Definition: gps.h:69
uint16_t uart_out_
UART out protocol (see CfgPRT message for constants)
Definition: node.h:637
int min(int a, int b)
ROSCONSOLE_DECL void shutdown()
Topic diagnostics for u-blox messages.
Definition: node.h:133
uint32_t qzss_sig_cfg_
The QZSS Signal configuration, see CfgGNSS message.
Definition: node.h:961
bool enable_glonass_
Whether or not to enable GLONASS.
Definition: node.h:955
static Time now()
std::string device_
Device port.
Definition: node.h:623
bool configureUblox()
Does nothing since there are no Raw Data product specific settings.
Definition: node.h:1073
uint8_t max_sbas_
Max SBAS parameter (see CfgSBAS message)
Definition: node.h:660
uint16_t usb_in_
USB in protocol (see CfgPRT message for constants)
Definition: node.h:644
boost::shared_ptr< diagnostic_updater::Updater > updater
ROS diagnostic updater.
Definition: node.h:101
Implements functions for Raw Data products.
Definition: node.h:1059
bool getRosUint(const std::string &key, U &u)
Get a unsigned integer value from the parameter server.
Definition: node.h:316
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:501
uint8_t dr_limit_
Dead reckoning limit parameter.
Definition: node.h:662
bool enable_sbas_
Whether or not to enable SBAS.
Definition: node.h:654
double min_freq
Minimum allow frequency of topic.
Definition: node.h:221
double min_freq
Minimum allow frequency of topic.
Definition: node.h:182
static constexpr uint32_t kNavSvInfoSubscribeRate
Subscribe Rate for u-blox SV Info messages.
Definition: node.h:97
Implements functions for firmware version 6.
Definition: node.h:697
void publish_nmea(const std::string &sentence, const std::string &topic)
Definition: node.h:431
std::string frame_id
The ROS frame ID of this device.
Definition: node.h:116
Fixed mode (should switch to time mode almost immediately)
Definition: node.h:1280


ublox_gps
Author(s): Johannes Meyer
autogenerated on Thu Dec 8 2022 03:41:52