novatel_gps_nodelet.cpp
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 
128 #include <exception>
129 #include <string>
130 
131 #include <boost/accumulators/accumulators.hpp>
132 #include <boost/accumulators/statistics/max.hpp>
133 #include <boost/accumulators/statistics/mean.hpp>
134 #include <boost/accumulators/statistics/min.hpp>
135 #include <boost/accumulators/statistics/rolling_mean.hpp>
136 #include <boost/accumulators/statistics/stats.hpp>
137 #include <boost/accumulators/statistics/variance.hpp>
138 #include <boost/circular_buffer.hpp>
139 
140 #include <diagnostic_msgs/DiagnosticStatus.h>
143 #include <gps_common/GPSFix.h>
144 #include <nodelet/nodelet.h>
145 #include <novatel_gps_msgs/NovatelCorrectedImuData.h>
146 #include <novatel_gps_msgs/NovatelFRESET.h>
147 #include <novatel_gps_msgs/NovatelMessageHeader.h>
148 #include <novatel_gps_msgs/NovatelPosition.h>
149 #include <novatel_gps_msgs/NovatelPsrdop2.h>
150 #include <novatel_gps_msgs/NovatelUtmPosition.h>
151 #include <novatel_gps_msgs/NovatelVelocity.h>
152 #include <novatel_gps_msgs/NovatelHeading2.h>
153 #include <novatel_gps_msgs/NovatelDualAntennaHeading.h>
154 #include <novatel_gps_msgs/Gpgga.h>
155 #include <novatel_gps_msgs/Gprmc.h>
156 #include <novatel_gps_msgs/Range.h>
157 #include <novatel_gps_msgs/Time.h>
158 #include <novatel_gps_msgs/Inspva.h>
159 #include <novatel_gps_msgs/Inspvax.h>
161 #include <ros/ros.h>
162 #include <sensor_msgs/Imu.h>
163 #include <sensor_msgs/NavSatFix.h>
164 #include <std_msgs/Time.h>
166 #include <swri_roscpp/parameters.h>
167 #include <swri_roscpp/publisher.h>
168 #include <swri_roscpp/subscriber.h>
169 
170 namespace stats = boost::accumulators;
171 
172 namespace novatel_gps_driver
173 {
175  {
176  public:
178  device_(""),
179  connection_type_("serial"),
180  serial_baud_(115200),
181  polling_period_(0.05),
182  publish_gpgsa_(false),
183  publish_gpgsv_(false),
184  publish_gphdt_(false),
185  imu_rate_(100.0),
186  imu_sample_rate_(-1),
189  publish_imu_messages_(false),
197  publish_nmea_messages_(false),
199  publish_time_messages_(false),
200  publish_trackstat_(false),
201  publish_diagnostics_(true),
204  reconnect_delay_s_(0.5),
205  use_binary_messages_(false),
206  connection_(NovatelGps::SERIAL),
207  last_sync_(ros::TIME_MIN),
208  rolling_offset_(stats::tag::rolling_window::window_size = 10),
209  expected_rate_(20),
210  device_timeouts_(0),
212  device_errors_(0),
217  last_published_(ros::TIME_MIN),
218  imu_frame_id_(""),
219  frame_id_("")
220  {
221  }
222 
224  {
225  gps_.Disconnect();
226  }
227 
232  void onInit() override
233  {
234  ros::NodeHandle &node = getNodeHandle();
236 
237  swri::param(priv, "device", device_, device_);
238  swri::param(priv, "imu_rate", imu_rate_, imu_rate_);
239  swri::param(priv, "imu_sample_rate", imu_sample_rate_, imu_sample_rate_);
240  swri::param(priv, "publish_clocksteering", publish_clock_steering_, publish_clock_steering_);
241  swri::param(priv, "publish_gpgsa", publish_gpgsa_, publish_gpgsa_);
242  swri::param(priv, "publish_gpgsv", publish_gpgsv_, publish_gpgsv_);
243  swri::param(priv, "publish_gphdt", publish_gphdt_, publish_gphdt_);
244  swri::param(priv, "publish_imu_messages", publish_imu_messages_, publish_imu_messages_);
245  swri::param(priv, "publish_novatel_positions", publish_novatel_positions_, publish_novatel_positions_);
246  swri::param(priv, "publish_novatel_xyz_positions", publish_novatel_xyz_positions_, publish_novatel_xyz_positions_);
247  swri::param(priv, "publish_novatel_utm_positions", publish_novatel_utm_positions_, publish_novatel_utm_positions_);
248  swri::param(priv, "publish_novatel_velocity", publish_novatel_velocity_, publish_novatel_velocity_);
249  swri::param(priv, "publish_novatel_heading2", publish_novatel_heading2_, publish_novatel_heading2_);
250  swri::param(priv, "publish_novatel_dual_antenna_heading", publish_novatel_dual_antenna_heading_, publish_novatel_dual_antenna_heading_);
251  swri::param(priv, "publish_novatel_psrdop2", publish_novatel_psrdop2_, publish_novatel_psrdop2_);
252  swri::param(priv, "publish_nmea_messages", publish_nmea_messages_, publish_nmea_messages_);
253  swri::param(priv, "publish_range_messages", publish_range_messages_, publish_range_messages_);
254  swri::param(priv, "publish_time_messages", publish_time_messages_, publish_time_messages_);
255  swri::param(priv, "publish_trackstat", publish_trackstat_, publish_trackstat_);
256  swri::param(priv, "publish_diagnostics", publish_diagnostics_, publish_diagnostics_);
257  swri::param(priv, "publish_sync_diagnostic", publish_sync_diagnostic_, publish_sync_diagnostic_);
258  swri::param(priv, "polling_period", polling_period_, polling_period_);
259  swri::param(priv, "reconnect_delay_s", reconnect_delay_s_, reconnect_delay_s_);
260  swri::param(priv, "use_binary_messages", use_binary_messages_, use_binary_messages_);
261  swri::param(priv, "span_frame_to_ros_frame", span_frame_to_ros_frame_, span_frame_to_ros_frame_);
262 
263  swri::param(priv, "connection_type", connection_type_, connection_type_);
265  swri::param(priv, "serial_baud", serial_baud_, serial_baud_);
266 
267  swri::param(priv, "imu_frame_id", imu_frame_id_, std::string(""));
268  swri::param(priv, "frame_id", frame_id_, std::string(""));
269 
270  //set NovatelGps parameters
271  swri::param(priv, "gpsfix_sync_tol", gps_.gpsfix_sync_tol_, 0.01);
272  swri::param(priv, "wait_for_sync", gps_.wait_for_sync_, true);
273 
274  swri::param(priv, "publish_invalid_gpsfix", publish_invalid_gpsfix_, publish_invalid_gpsfix_);
275 
276  // Reset Service
278 
279  sync_sub_ = swri::Subscriber(node, "gps_sync", 100, &NovatelGpsNodelet::SyncCallback, this);
280 
281  std::string gps_topic = node.resolveName("gps");
282  gps_pub_ = swri::advertise<gps_common::GPSFix>(node, gps_topic, 100);
283  fix_pub_ = swri::advertise<sensor_msgs::NavSatFix>(node, "fix", 100);
284 
286  {
287  clocksteering_pub_ = swri::advertise<novatel_gps_msgs::ClockSteering>(node, "clocksteering", 100);
288  }
289 
291  {
292  gpgga_pub_ = swri::advertise<novatel_gps_msgs::Gpgga>(node, "gpgga", 100);
293  gprmc_pub_ = swri::advertise<novatel_gps_msgs::Gprmc>(node, "gprmc", 100);
294  }
295 
296  if (publish_gpgsa_)
297  {
298  gpgsa_pub_ = swri::advertise<novatel_gps_msgs::Gpgsa>(node, "gpgsa", 100);
299  }
300 
302  {
303  imu_pub_ = swri::advertise<sensor_msgs::Imu>(node, "imu", 100);
304  novatel_imu_pub_= swri::advertise<novatel_gps_msgs::NovatelCorrectedImuData>(node, "corrimudata", 100);
305  insstdev_pub_ = swri::advertise<novatel_gps_msgs::Insstdev>(node, "insstdev", 100);
306  inspva_pub_ = swri::advertise<novatel_gps_msgs::Inspva>(node, "inspva", 100);
307  inspvax_pub_ = swri::advertise<novatel_gps_msgs::Inspvax>(node, "inspvax", 100);
308  inscov_pub_ = swri::advertise<novatel_gps_msgs::Inscov>(node, "inscov", 100);
309  }
310 
311  if (publish_gpgsv_)
312  {
313  gpgsv_pub_ = swri::advertise<novatel_gps_msgs::Gpgsv>(node, "gpgsv", 100);
314  }
315 
316  if (publish_gphdt_)
317  {
318  gphdt_pub_ = swri::advertise<novatel_gps_msgs::Gphdt>(node,"gphdt", 100);
319  }
320 
322  {
323  novatel_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelPosition>(node, "bestpos", 100);
324  }
325 
327  {
328  novatel_xyz_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelXYZ>(node, "bestxyz", 100);
329  }
330 
332  {
333  novatel_utm_pub_ = swri::advertise<novatel_gps_msgs::NovatelUtmPosition>(node, "bestutm", 100);
334  }
335 
337  {
338  novatel_velocity_pub_ = swri::advertise<novatel_gps_msgs::NovatelVelocity>(node, "bestvel", 100);
339  }
340  else
341  {
342  gps_.wait_for_sync_ = false;
343  }
344 
346  {
347  novatel_heading2_pub_ = swri::advertise<novatel_gps_msgs::NovatelHeading2>(node, "heading2", 100);
348  }
349 
351  {
352  novatel_dual_antenna_heading_pub_ = swri::advertise<novatel_gps_msgs::NovatelDualAntennaHeading>(node, "dual_antenna_heading", 100);
353  }
354 
356  {
357  novatel_psrdop2_pub_ = swri::advertise<novatel_gps_msgs::NovatelPsrdop2>(node,
358  "psrdop2",
359  100,
360  true);
361  }
362 
364  {
365  range_pub_ = swri::advertise<novatel_gps_msgs::Range>(node, "range", 100);
366  }
367 
369  {
370  time_pub_ = swri::advertise<novatel_gps_msgs::Time>(node, "time", 100);
371  }
372 
373  if (publish_trackstat_)
374  {
375  trackstat_pub_ = swri::advertise<novatel_gps_msgs::Trackstat>(node, "trackstat", 100);
376  }
377 
378  hw_id_ = "Novatel GPS (" + device_ +")";
380  {
382  diagnostic_updater_.add("Connection",
383  this,
385  diagnostic_updater_.add("Hardware",
386  this,
388  diagnostic_updater_.add("Data",
389  this,
391  diagnostic_updater_.add("Rate",
392  this,
394  diagnostic_updater_.add("GPS Fix",
395  this,
398  {
399  diagnostic_updater_.add("Sync",
400  this,
402  }
403  }
404 
406 
407  thread_ = boost::thread(&NovatelGpsNodelet::Spin, this);
408  NODELET_INFO("%s initialized", hw_id_.c_str());
409  }
410 
411  void SyncCallback(const std_msgs::TimeConstPtr& sync)
412  {
413  boost::unique_lock<boost::mutex> lock(mutex_);
414  sync_times_.push_back(sync->data);
415  }
416 
421  void Spin()
422  {
423  std::string format_suffix;
425  {
426  // NovAtel logs in binary format always end with "b", while ones in
427  // ASCII format always end in "a".
428  format_suffix = "b";
429  }
430  else
431  {
432  format_suffix = "a";
433  }
434 
435  NovatelMessageOpts opts;
436  opts["gpgga"] = polling_period_;
437  opts["bestpos" + format_suffix] = polling_period_; // Best position
438  opts["bestvel" + format_suffix] = polling_period_; // Best velocity
439  opts["time" + format_suffix] = 1.0; // Time
441  {
442  opts["gprmc"] = polling_period_;
443  }
445  {
446  opts["bestxyz" + format_suffix] = polling_period_;
447  }
449  {
450  opts["bestutm" + format_suffix] = polling_period_;
451  }
453  {
454  opts["heading2" + format_suffix] = polling_period_;
455  }
457  {
458  opts["dualantennaheading" + format_suffix] = polling_period_;
459  }
461  {
462  opts["psrdop2" + format_suffix] = -1.0;
463  }
464  if (publish_gpgsa_)
465  {
466  opts["gpgsa"] = polling_period_;
467  }
468  if (publish_gpgsv_)
469  {
470  opts["gpgsv"] = 1.0;
471  }
472  if (publish_gphdt_)
473  {
474  opts["gphdt"] = polling_period_;
475  }
477  {
478  opts["clocksteering" + format_suffix] = 1.0;
479  }
481  {
482  double period = 1.0 / imu_rate_;
483  opts["corrimudata" + format_suffix] = period;
484  opts["inscov" + format_suffix] = 1.0;
485  opts["inspva" + format_suffix] = period;
486  opts["inspvax" + format_suffix] = period;
487  opts["insstdev" + format_suffix] = 1.0;
489  {
490  NODELET_WARN("Using the ASCII message format with CORRIMUDATA logs is not recommended. "
491  "A serial link will not be able to keep up with the data rate.");
492  }
493 
494  // Only configure the imu rate if we set the param
495  if (imu_sample_rate_ > 0)
496  {
498  }
499  }
501  {
502  opts["range" + format_suffix] = 1.0; // Range. 1 msg/sec is max rate
503  }
504  if (publish_trackstat_)
505  {
506  opts["trackstat" + format_suffix] = 1.0; // Trackstat
507  }
508  // Set the serial baud rate if needed
510  {
512  }
513  ros::WallRate rate(1000.0);
514  while (ros::ok())
515  {
516  if (gps_.Connect(device_, connection_, opts))
517  {
518  // Connected to device. Begin reading/processing data
519  NODELET_INFO("%s connected to device", hw_id_.c_str());
520  while (gps_.IsConnected() && ros::ok())
521  {
522  // Read data from the device and publish any received messages
524 
525  // Poke the diagnostic updater. It will only fire diagnostics if
526  // its internal timer (1 Hz) has elapsed. Otherwise, this is a
527  // noop
529  {
531  }
532 
533  // Spin once to let the ROS callbacks fire
534  ros::spinOnce();
535  // Sleep for a microsecond to prevent CPU hogging
536  rate.sleep();
537  } // While (gps_.IsConnected() && ros::ok()) (inner loop to process data from device)
538  }
539  else // Could not connect to the device
540  {
541  NODELET_ERROR_THROTTLE(1, "Error connecting to device <%s:%s>: %s",
542  connection_type_.c_str(),
543  device_.c_str(),
544  gps_.ErrorMsg().c_str());
545  device_errors_++;
547  }
548 
549  if (ros::ok())
550  {
551  // If ROS is still OK but we got disconnected, we're going to try
552  // to reconnect, but wait just a bit so we don't spam the device.
554  }
555 
556  // Poke the diagnostic updater. It will only fire diagnostics if
557  // its internal timer (1 Hz) has elapsed. Otherwise, this is a
558  // noop
560  {
562  }
563 
564  // Spin once to let the ROS callbacks fire
565  ros::spinOnce();
566  // Sleep for a microsecond to prevent CPU hogging
567  rate.sleep();
568 
570  {
571  // If we're playing a PCAP file, we only want to play it once.
572  ros::shutdown();
573  }
574  } // While (ros::ok) (outer loop to reconnect to device)
575 
576  gps_.Disconnect();
577  NODELET_INFO("%s disconnected and shut down", hw_id_.c_str());
578  }
579 
580  private:
581  // Parameters
583  std::string device_;
585  std::string connection_type_;
587  int32_t serial_baud_;
593  double imu_rate_;
615 
640 
642 
645 
646  boost::thread thread_;
647  boost::mutex mutex_;
648 
653  boost::circular_buffer<ros::Time> sync_times_;
655  boost::circular_buffer<ros::Time> msg_times_;
657  stats::accumulator_set<float, stats::stats<
658  stats::tag::max,
659  stats::tag::min,
660  stats::tag::mean,
661  stats::tag::variance> > offset_stats_;
663  stats::accumulator_set<float, stats::stats<stats::tag::rolling_mean> > rolling_offset_;
664 
665  // ROS diagnostics
666  std::string error_msg_;
668  std::string hw_id_;
672  int32_t device_errors_;
678  novatel_gps_msgs::NovatelPositionPtr last_novatel_position_;
679 
680  std::string imu_frame_id_;
681  std::string frame_id_;
682 
686  bool resetService(novatel_gps_msgs::NovatelFRESET::Request& req,
687  novatel_gps_msgs::NovatelFRESET::Response& res)
688  {
689  if (!gps_.IsConnected())
690  {
691  res.success = false;
692  }
693 
694  // Formulate the reset command and send it to the device
695  std::string command = "FRESET ";
696  command += req.target.length() ? "STANDARD" : req.target;
697  command += "\r\n";
698  gps_.Write(command);
699 
700  if (req.target.length() == 0)
701  {
702  ROS_WARN("No FRESET target specified. Doing FRESET STANDARD. This may be undesired behavior.");
703  }
704 
705  res.success = true;
706  return true;
707  }
708 
716  {
717  std::vector<gps_common::GPSFixPtr> fix_msgs;
718  std::vector<novatel_gps_msgs::NovatelPositionPtr> position_msgs;
719  std::vector<novatel_gps_msgs::GpggaPtr> gpgga_msgs;
720 
721  // This call appears to block if the serial device is disconnected
722  NovatelGps::ReadResult result = gps_.ProcessData();
723  if (result == NovatelGps::READ_ERROR)
724  {
725  NODELET_ERROR_THROTTLE(1, "Error reading from device <%s:%s>: %s",
726  connection_type_.c_str(),
727  device_.c_str(),
728  gps_.ErrorMsg().c_str());
729  device_errors_++;
730  }
731  else if (result == NovatelGps::READ_TIMEOUT)
732  {
733  device_timeouts_++;
734  }
735  else if (result == NovatelGps::READ_INTERRUPTED)
736  {
737  // If we are interrupted by a signal, ROS is probably
738  // quitting, but we'll wait for ROS to tell us to quit.
739  device_interrupts_++;
740  }
741  else if (result == NovatelGps::READ_PARSE_FAILED)
742  {
743  NODELET_ERROR("Error reading from device <%s:%s>: %s",
744  connection_type_.c_str(),
745  device_.c_str(),
746  gps_.ErrorMsg().c_str());
747  gps_parse_failures_++;
748  }
749  else if (result == NovatelGps::READ_INSUFFICIENT_DATA)
750  {
751  gps_insufficient_data_warnings_++;
752  }
753 
754  // GPSFix messages are always published, and Gpgga and Position messages
755  // are used for generating some diagnostics. Other message types will
756  // only be retrieved if we're configured to publish them.
757  gps_.GetFixMessages(fix_msgs);
758  gps_.GetGpggaMessages(gpgga_msgs);
759  gps_.GetNovatelPositions(position_msgs);
760 
761  // Increment the measurement count by the number of messages we just
762  // read
763  measurement_count_ += position_msgs.size();
764 
765  // If there are new position messages, store the most recent
766  if (!position_msgs.empty())
767  {
768  last_novatel_position_ = position_msgs.back();
769  }
770 
771  // Find all the gppga messages that are within 20 ms of whole
772  // numbered UTC seconds and push their stamps onto the msg_times
773  // buffer
774  for (const auto& msg : gpgga_msgs)
775  {
776  if (msg->utc_seconds != 0)
777  {
778  auto second = static_cast<int64_t>(swri_math_util::Round(msg->utc_seconds));
779  double difference = std::fabs(msg->utc_seconds - second);
780 
781  if (difference < 0.02)
782  {
783  msg_times_.push_back(msg->header.stamp);
784  }
785  }
786  }
787 
788  // If timesync messages are available, CalculateTimeSync will
789  // update a stat accumulator of the offset of the TimeSync message
790  // stamp from the GPS message stamp
792 
793  // If TimeSync messages are available, CalculateTimeSync keeps
794  // an acculumator of their offset, which is used to
795  // calculate a rolling mean of the offset to apply to all messages
796  ros::Duration sync_offset(0); // If no TimeSyncs, assume 0 offset
797  if (last_sync_ != ros::TIME_MIN)
798  {
799  sync_offset = ros::Duration(stats::rolling_mean(rolling_offset_));
800  }
801  NODELET_DEBUG_STREAM("GPS TimeSync offset is " << sync_offset);
802 
803  if (publish_nmea_messages_)
804  {
805  for (const auto& msg : gpgga_msgs)
806  {
807  msg->header.stamp += sync_offset;
808  msg->header.frame_id = frame_id_;
809  gpgga_pub_.publish(msg);
810  }
811 
812  std::vector<novatel_gps_msgs::GprmcPtr> gprmc_msgs;
813  gps_.GetGprmcMessages(gprmc_msgs);
814  for (const auto& msg : gprmc_msgs)
815  {
816  msg->header.stamp += sync_offset;
817  msg->header.frame_id = frame_id_;
818  gprmc_pub_.publish(msg);
819  }
820  }
821 
822  if (publish_gpgsa_)
823  {
824  std::vector<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs;
825  gps_.GetGpgsaMessages(gpgsa_msgs);
826  for (const auto& msg : gpgsa_msgs)
827  {
828  msg->header.stamp = ros::Time::now();
829  msg->header.frame_id = frame_id_;
830  gpgsa_pub_.publish(msg);
831  }
832  }
833 
834  if (publish_gpgsv_)
835  {
836  std::vector<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs;
837  gps_.GetGpgsvMessages(gpgsv_msgs);
838  for (const auto& msg : gpgsv_msgs)
839  {
840  msg->header.stamp = ros::Time::now();
841  msg->header.frame_id = frame_id_;
842  gpgsv_pub_.publish(msg);
843  }
844  }
845 
846  if (publish_gphdt_)
847  {
848  std::vector<novatel_gps_msgs::GphdtPtr> gphdt_msgs;
849  gps_.GetGphdtMessages(gphdt_msgs);
850  for (const auto& msg : gphdt_msgs)
851  {
852  msg->header.stamp = ros::Time::now();
853  msg->header.frame_id = frame_id_;
854  gphdt_pub_.publish(msg);
855  }
856  }
857 
858  if (publish_novatel_positions_)
859  {
860  for (const auto& msg : position_msgs)
861  {
862  msg->header.stamp += sync_offset;
863  msg->header.frame_id = frame_id_;
864  novatel_position_pub_.publish(msg);
865  }
866  }
867 
868  if (publish_novatel_xyz_positions_)
869  {
870  std::vector<novatel_gps_msgs::NovatelXYZPtr> xyz_position_msgs;
871  gps_.GetNovatelXYZPositions(xyz_position_msgs);
872  for (const auto& msg : xyz_position_msgs)
873  {
874  msg->header.stamp += sync_offset;
875  msg->header.frame_id = frame_id_;
876  novatel_xyz_position_pub_.publish(msg);
877  }
878  }
879 
880  if (publish_novatel_utm_positions_)
881  {
882  std::vector<novatel_gps_msgs::NovatelUtmPositionPtr> utm_msgs;
883  gps_.GetNovatelUtmPositions(utm_msgs);
884  for (const auto& msg : utm_msgs)
885  {
886  msg->header.stamp += sync_offset;
887  msg->header.frame_id = frame_id_;
888  novatel_utm_pub_.publish(msg);
889  }
890  }
891 
892  if (publish_novatel_heading2_)
893  {
894  std::vector<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs;
895  gps_.GetNovatelHeading2Messages(heading2_msgs);
896  for (const auto& msg : heading2_msgs)
897  {
898  msg->header.stamp += sync_offset;
899  msg->header.frame_id = frame_id_;
900  novatel_heading2_pub_.publish(msg);
901  }
902  }
903 
904  if (publish_novatel_dual_antenna_heading_)
905  {
906  std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs;
907  gps_.GetNovatelDualAntennaHeadingMessages(dual_antenna_heading_msgs);
908  for (const auto& msg : dual_antenna_heading_msgs)
909  {
910  msg->header.stamp += sync_offset;
911  msg->header.frame_id = frame_id_;
912  novatel_dual_antenna_heading_pub_.publish(msg);
913  }
914  }
915 
916  if (publish_novatel_psrdop2_)
917  {
918  std::vector<novatel_gps_msgs::NovatelPsrdop2Ptr> psrdop2_msgs;
919  gps_.GetNovatelPsrdop2Messages(psrdop2_msgs);
920  for (const auto& msg : psrdop2_msgs)
921  {
922  msg->header.stamp += sync_offset;
923  msg->header.frame_id = frame_id_;
924  novatel_psrdop2_pub_.publish(msg);
925  }
926  }
927 
928  if (publish_clock_steering_)
929  {
930  std::vector<novatel_gps_msgs::ClockSteeringPtr> msgs;
931  gps_.GetClockSteeringMessages(msgs);
932  for (const auto& msg : msgs)
933  {
934  clocksteering_pub_.publish(msg);
935  }
936  }
937 
938  if (publish_novatel_velocity_)
939  {
940  std::vector<novatel_gps_msgs::NovatelVelocityPtr> velocity_msgs;
941  gps_.GetNovatelVelocities(velocity_msgs);
942  for (const auto& msg : velocity_msgs)
943  {
944  msg->header.stamp += sync_offset;
945  msg->header.frame_id = frame_id_;
946  novatel_velocity_pub_.publish(msg);
947  }
948  }
949  if (publish_time_messages_)
950  {
951  std::vector<novatel_gps_msgs::TimePtr> time_msgs;
952  gps_.GetTimeMessages(time_msgs);
953  for (const auto& msg : time_msgs)
954  {
955  msg->header.stamp += sync_offset;
956  msg->header.frame_id = frame_id_;
957  time_pub_.publish(msg);
958  }
959  }
960  if (publish_range_messages_)
961  {
962  std::vector<novatel_gps_msgs::RangePtr> range_msgs;
963  gps_.GetRangeMessages(range_msgs);
964  for (const auto& msg : range_msgs)
965  {
966  msg->header.stamp += sync_offset;
967  msg->header.frame_id = frame_id_;
968  range_pub_.publish(msg);
969  }
970  }
971  if (publish_trackstat_)
972  {
973  std::vector<novatel_gps_msgs::TrackstatPtr> trackstat_msgs;
974  gps_.GetTrackstatMessages(trackstat_msgs);
975  for (const auto& msg : trackstat_msgs)
976  {
977  msg->header.stamp += sync_offset;
978  msg->header.frame_id = frame_id_;
979  trackstat_pub_.publish(msg);
980  }
981  }
982  if (publish_imu_messages_)
983  {
984  std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_imu_msgs;
985  gps_.GetNovatelCorrectedImuData(novatel_imu_msgs);
986  for (const auto& msg : novatel_imu_msgs)
987  {
988  msg->header.stamp += sync_offset;
989  msg->header.frame_id = imu_frame_id_;
990  novatel_imu_pub_.publish(msg);
991  }
992 
993  std::vector<sensor_msgs::ImuPtr> imu_msgs;
994  gps_.GetImuMessages(imu_msgs);
995  for (const auto& msg : imu_msgs)
996  {
997  msg->header.stamp += sync_offset;
998  msg->header.frame_id = imu_frame_id_;
999  imu_pub_.publish(msg);
1000  }
1001 
1002  std::vector<novatel_gps_msgs::InscovPtr> inscov_msgs;
1003  gps_.GetInscovMessages(inscov_msgs);
1004  for (const auto& msg : inscov_msgs)
1005  {
1006  msg->header.stamp += sync_offset;
1007  msg->header.frame_id = imu_frame_id_;
1008  inscov_pub_.publish(msg);
1009  }
1010 
1011  std::vector<novatel_gps_msgs::InspvaPtr> inspva_msgs;
1012  gps_.GetInspvaMessages(inspva_msgs);
1013  for (const auto& msg : inspva_msgs)
1014  {
1015  msg->header.stamp += sync_offset;
1016  msg->header.frame_id = imu_frame_id_;
1017  inspva_pub_.publish(msg);
1018  }
1019 
1020  std::vector<novatel_gps_msgs::InspvaxPtr> inspvax_msgs;
1021  gps_.GetInspvaxMessages(inspvax_msgs);
1022  for (const auto& msg : inspvax_msgs)
1023  {
1024  msg->header.stamp += sync_offset;
1025  msg->header.frame_id = imu_frame_id_;
1026  inspvax_pub_.publish(msg);
1027  }
1028 
1029  std::vector<novatel_gps_msgs::InsstdevPtr> insstdev_msgs;
1030  gps_.GetInsstdevMessages(insstdev_msgs);
1031  for (const auto& msg : insstdev_msgs)
1032  {
1033  msg->header.stamp += sync_offset;
1034  msg->header.frame_id = imu_frame_id_;
1035  insstdev_pub_.publish(msg);
1036  }
1037  }
1038 
1039  for (const auto& msg : fix_msgs)
1040  {
1041  msg->header.stamp += sync_offset;
1042  msg->header.frame_id = frame_id_;
1043  if (publish_invalid_gpsfix_ || msg->status.status != gps_common::GPSStatus::STATUS_NO_FIX)
1044  {
1045  gps_pub_.publish(msg);
1046  }
1047 
1048  if (fix_pub_.getNumSubscribers() > 0)
1049  {
1050  sensor_msgs::NavSatFixPtr fix_msg = ConvertGpsFixToNavSatFix(msg);
1051 
1052  fix_pub_.publish(fix_msg);
1053  }
1054 
1055  // If the time between GPS message stamps is greater than 1.5
1056  // times the expected publish rate, increment the
1057  // publish_rate_warnings_ counter, which is used in diagnostics
1058  if (last_published_ != ros::TIME_MIN &&
1059  (msg->header.stamp - last_published_).toSec() > 1.5 * (1.0 / expected_rate_))
1060  {
1061  publish_rate_warnings_++;
1062  }
1063 
1064  last_published_ = msg->header.stamp;
1065  }
1066  }
1067 
1068  sensor_msgs::NavSatFixPtr ConvertGpsFixToNavSatFix(const gps_common::GPSFixPtr& msg)
1069  {
1070  sensor_msgs::NavSatFixPtr fix_msg = boost::make_shared<sensor_msgs::NavSatFix>();
1071  fix_msg->header = msg->header;
1072  fix_msg->latitude = msg->latitude;
1073  fix_msg->longitude = msg->longitude;
1074  fix_msg->altitude = msg->altitude;
1075  fix_msg->position_covariance = msg->position_covariance;
1076  switch (msg->status.status)
1077  {
1078  case gps_common::GPSStatus::STATUS_NO_FIX:
1079  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
1080  break;
1081  case gps_common::GPSStatus::STATUS_FIX:
1082  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1083  break;
1084  case gps_common::GPSStatus::STATUS_SBAS_FIX:
1085  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
1086  break;
1087  case gps_common::GPSStatus::STATUS_GBAS_FIX:
1088  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
1089  break;
1090  case gps_common::GPSStatus::STATUS_DGPS_FIX:
1091  case gps_common::GPSStatus::STATUS_WAAS_FIX:
1092  default:
1093  ROS_WARN_ONCE("Unsupported fix status: %d", msg->status.status);
1094  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1095  break;
1096  }
1097  switch (msg->position_covariance_type)
1098  {
1099  case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
1100  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
1101  break;
1102  case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
1103  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
1104  break;
1105  case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
1106  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1107  break;
1108  case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
1109  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1110  break;
1111  default:
1112  ROS_WARN_ONCE("Unsupported covariance type: %d", msg->position_covariance_type);
1113  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1114  break;
1115  }
1116  // TODO Figure out how to set this based on info in a GPSFix
1117  fix_msg->status.service = 0;
1118 
1119  return fix_msg;
1120  }
1121 
1127  {
1128  boost::unique_lock<boost::mutex> lock(mutex_);
1129  int32_t synced_i = -1;
1130  int32_t synced_j = -1;
1131  // Loop over sync times buffer
1132  for (size_t i = 0; i < sync_times_.size(); i++)
1133  {
1134  // Loop over message times buffer
1135  for (size_t j = synced_j + 1; j < msg_times_.size(); j++)
1136  {
1137  // Offset is the difference between the sync time and message time
1138  double offset = (sync_times_[i] - msg_times_[j]).toSec();
1139  if (std::fabs(offset) < 0.49)
1140  {
1141  // If the offset is less than 0.49 sec, the messages match
1142  synced_i = static_cast<int32_t>(i);
1143  synced_j = static_cast<int32_t>(j);
1144  // Add the offset to the stats accumulators
1145  offset_stats_(offset);
1146  rolling_offset_(offset);
1147  // Update the last sync
1148  last_sync_ = sync_times_[i];
1149  // Break out of the inner loop and continue looping through sync times
1150  break;
1151  }
1152  }
1153  }
1154 
1155  // Remove all the timesync messages that have been matched from the queue
1156  for (int i = 0; i <= synced_i && !sync_times_.empty(); i++)
1157  {
1158  sync_times_.pop_front();
1159  }
1160 
1161  // Remove all the gps messages that have been matched from the queue
1162  for (int j = 0; j <= synced_j && !msg_times_.empty(); j++)
1163  {
1164  msg_times_.pop_front();
1165  }
1166  }
1167 
1169  {
1170  status.clear();
1171  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1172 
1173  if (!last_novatel_position_)
1174  {
1175  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Status");
1176  NODELET_WARN("No GPS status data.");
1177  return;
1178  }
1179 
1180  status.add("Solution Status", last_novatel_position_->solution_status);
1181  status.add("Position Type", last_novatel_position_->position_type);
1182  status.add("Solution Age", last_novatel_position_->solution_age);
1183  status.add("Satellites Tracked", static_cast<int>(last_novatel_position_->num_satellites_tracked));
1184  status.add("Satellites Used", static_cast<int>(last_novatel_position_->num_satellites_used_in_solution));
1185  status.add("Software Version", last_novatel_position_->novatel_msg_header.receiver_software_version);
1186 
1187  const novatel_gps_msgs::NovatelReceiverStatus& rcvr_status = last_novatel_position_->novatel_msg_header.receiver_status;
1188  status.add("Status Code", rcvr_status.original_status_code);
1189 
1190  if (last_novatel_position_->novatel_msg_header.receiver_status.original_status_code != 0)
1191  {
1192  uint8_t level = diagnostic_msgs::DiagnosticStatus::WARN;
1193  std::string msg = "Status Warning";
1194  // If the antenna is disconnected/broken, this is an error
1195  if (rcvr_status.antenna_is_open ||
1196  rcvr_status.antenna_is_shorted ||
1197  !rcvr_status.antenna_powered)
1198  {
1199  msg += " Antenna Problem";
1200  level = diagnostic_msgs::DiagnosticStatus::ERROR;
1201  }
1202  status.add("Error Flag", rcvr_status.error_flag?"true":"false");
1203  status.add("Temperature Flag", rcvr_status.temperature_flag?"true":"false");
1204  status.add("Voltage Flag", rcvr_status.voltage_supply_flag?"true":"false");
1205  status.add("Antenna Not Powered", rcvr_status.antenna_powered?"false":"true");
1206  status.add("Antenna Open", rcvr_status.antenna_is_open?"true":"false");
1207  status.add("Antenna Shorted", rcvr_status.antenna_is_shorted?"true":"false");
1208  status.add("CPU Overloaded", rcvr_status.cpu_overload_flag?"true":"false");
1209  status.add("COM1 Buffer Overrun", rcvr_status.com1_buffer_overrun?"true":"false");
1210  status.add("COM2 Buffer Overrun", rcvr_status.com2_buffer_overrun?"true":"false");
1211  status.add("COM3 Buffer Overrun", rcvr_status.com3_buffer_overrun?"true":"false");
1212  status.add("USB Buffer Overrun", rcvr_status.usb_buffer_overrun?"true":"false");
1213  status.add("RF1 AGC Flag", rcvr_status.rf1_agc_flag?"true":"false");
1214  status.add("RF2 AGC Flag", rcvr_status.rf2_agc_flag?"true":"false");
1215  status.add("Almanac Flag", rcvr_status.almanac_flag?"true":"false");
1216  status.add("Position Solution Flag", rcvr_status.position_solution_flag?"true":"false");
1217  status.add("Position Fixed Flag", rcvr_status.position_fixed_flag?"true":"false");
1218  status.add("Clock Steering Status", rcvr_status.clock_steering_status_enabled?"true":"false");
1219  status.add("Clock Model Flag", rcvr_status.clock_model_flag?"true":"false");
1220  status.add("OEMV External Oscillator Flag", rcvr_status.oemv_external_oscillator_flag?"true":"false");
1221  status.add("Software Resource Flag", rcvr_status.software_resource_flag?"true":"false");
1222  status.add("Auxiliary1 Flag", rcvr_status.aux1_status_event_flag?"true":"false");
1223  status.add("Auxiliary2 Flag", rcvr_status.aux2_status_event_flag?"true":"false");
1224  status.add("Auxiliary3 Flag", rcvr_status.aux3_status_event_flag?"true":"false");
1225  NODELET_WARN("Novatel status code: %d", rcvr_status.original_status_code);
1226  status.summary(level, msg);
1227  }
1228  }
1229 
1231  {
1232  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1233 
1234  if (last_sync_ == ros::TIME_MIN)
1235  {
1236  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Sync");
1237  return;
1238  }
1239  else if (last_sync_ < ros::Time::now() - ros::Duration(10))
1240  {
1241  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Sync Stale");
1242  NODELET_ERROR("GPS time synchronization is stale.");
1243  }
1244 
1245  status.add("Last Sync", last_sync_);
1246  status.add("Mean Offset", stats::mean(offset_stats_));
1247  status.add("Mean Offset (rolling)", stats::rolling_mean(rolling_offset_));
1248  status.add("Offset Variance", stats::variance(offset_stats_));
1249  status.add("Min Offset", stats::min(offset_stats_));
1250  status.add("Max Offset", stats::max(offset_stats_));
1251  }
1252 
1254  {
1255  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1256 
1257  if (device_errors_ > 0)
1258  {
1259  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Device Errors");
1260  }
1261  else if (device_interrupts_ > 0)
1262  {
1263  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Interrupts");
1264  NODELET_WARN("device interrupts detected <%s:%s>: %d",
1265  connection_type_.c_str(), device_.c_str(), device_interrupts_);
1266  }
1267  else if (device_timeouts_)
1268  {
1269  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Timeouts");
1270  NODELET_WARN("device timeouts detected <%s:%s>: %d",
1271  connection_type_.c_str(), device_.c_str(), device_timeouts_);
1272  }
1273 
1274  status.add("Errors", device_errors_);
1275  status.add("Interrupts", device_interrupts_);
1276  status.add("Timeouts", device_timeouts_);
1277 
1278  device_timeouts_ = 0;
1279  device_interrupts_ = 0;
1280  device_errors_ = 0;
1281  }
1282 
1284  {
1285  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1286 
1287  if (gps_parse_failures_ > 0)
1288  {
1289  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Parse Failures");
1290  NODELET_WARN("gps parse failures detected <%s>: %d",
1291  hw_id_.c_str(), gps_parse_failures_);
1292  }
1293 
1294  status.add("Parse Failures", gps_parse_failures_);
1295  status.add("Insufficient Data Warnings", gps_insufficient_data_warnings_);
1296 
1297  gps_parse_failures_ = 0;
1298  gps_insufficient_data_warnings_ = 0;
1299  }
1300 
1302  {
1303  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1304 
1305  double period = diagnostic_updater_.getPeriod();
1306  double measured_rate = measurement_count_ / period;
1307 
1308  if (measured_rate < 0.5 * expected_rate_)
1309  {
1310  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Insufficient Data Rate");
1311  NODELET_ERROR("insufficient data rate <%s>: %lf < %lf",
1312  hw_id_.c_str(), measured_rate, expected_rate_);
1313  }
1314  else if (measured_rate < 0.95 * expected_rate_)
1315  {
1316  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Data Rate");
1317  NODELET_WARN("insufficient data rate <%s>: %lf < %lf",
1318  hw_id_.c_str(), measured_rate, expected_rate_);
1319  }
1320 
1321  status.add("Measurement Rate (Hz)", measured_rate);
1322 
1323  measurement_count_ = 0;
1324  }
1325 
1327  {
1328  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal Publish Rate");
1329 
1330  double elapsed = (ros::Time::now() - last_published_).toSec();
1331  bool gap_detected = false;
1332  if (elapsed > 2.0 / expected_rate_)
1333  {
1334  publish_rate_warnings_++;
1335  gap_detected = true;
1336  }
1337 
1338  if (publish_rate_warnings_ > 1 || gap_detected)
1339  {
1340  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Publish Rate");
1341  NODELET_WARN("publish rate failures detected <%s>: %d",
1342  hw_id_.c_str(), publish_rate_warnings_);
1343  }
1344 
1345  status.add("Warnings", publish_rate_warnings_);
1346 
1347  publish_rate_warnings_ = 0;
1348  }
1349  };
1350 }
1351 
1352 // Register nodelet plugin
void GetInscovMessages(std::vector< novatel_gps_msgs::InscovPtr > &inscov_messages)
Provides any INSCOV messages that have been received since the last time this was called...
msg
stats::accumulator_set< float, stats::stats< stats::tag::rolling_mean > > rolling_offset_
Rolling mean of time offset.
void GetNovatelPositions(std::vector< novatel_gps_msgs::NovatelPositionPtr > &positions)
Provides any BESTPOS messages that have been received since the last time this was called...
void GetFixMessages(std::vector< gps_common::GPSFixPtr > &fix_messages)
Provides any GPSFix messages that have been generated since the last time this was called...
#define NODELET_ERROR(...)
void GetClockSteeringMessages(std::vector< novatel_gps_msgs::ClockSteeringPtr > &clocksteering_msgs)
Provides any CLOCKSTEERING messages that have been received since the last time this was called...
double imu_sample_rate_
How frequently the device samples the IMU, in Hz.
void GetRangeMessages(std::vector< novatel_gps_msgs::RangePtr > &range_messages)
Provides any RANGE messages that have been received since the last time this was called.
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
std::map< std::string, double > NovatelMessageOpts
Definition: novatel_gps.h:93
void GetNovatelUtmPositions(std::vector< novatel_gps_msgs::NovatelUtmPositionPtr > &utm_positions)
Provides any BESTUTM messages that have been received since the last time this was called...
boost::circular_buffer< ros::Time > msg_times_
Buffer of gps message time stamps.
std::string resolveName(const std::string &name, bool remap=true) const
void GetInspvaxMessages(std::vector< novatel_gps_msgs::InspvaxPtr > &inspvax_messages)
Provides any INSPVAX messages that have been received since the last time this was called...
#define NODELET_ERROR_THROTTLE(rate,...)
void setHardwareID(const std::string &hwid)
void add(const std::string &name, TaskFunction f)
void GetGpgsaMessages(std::vector< novatel_gps_msgs::GpgsaPtr > &gpgsa_messages)
Provides any GPGSA messages that have been received since the last time this was called.
void GetNovatelCorrectedImuData(std::vector< novatel_gps_msgs::NovatelCorrectedImuDataPtr > &imu_messages)
Provides any CORRIMUDATA messages that have been received since the last time this was called...
sensor_msgs::NavSatFixPtr ConvertGpsFixToNavSatFix(const gps_common::GPSFixPtr &msg)
void ApplyVehicleBodyRotation(const bool &apply_rotation)
Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN...
void GetNovatelVelocities(std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
Provides any BESTVEL messages that have been received since the last time this was called...
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void GetGpgsvMessages(std::vector< novatel_gps_msgs::GpgsvPtr > &gpgsv_messages)
Provides any GPGSV messages that have been received since the last time this was called.
#define ROS_WARN(...)
static ConnectionType ParseConnection(const std::string &connection)
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
ros::NodeHandle & getPrivateNodeHandle() const
void GetGphdtMessages(std::vector< novatel_gps_msgs::GphdtPtr > &gphdt_messages)
Provides any GPHDT messages that have been received since the last time this was called.
void RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
void GetNovatelPsrdop2Messages(std::vector< novatel_gps_msgs::NovatelPsrdop2Ptr > &psrdop2_messages)
Provides any PSRDOP2 messages that have been received since the last time this was called...
void GpsDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
ReadResult ProcessData()
Processes any data that has been received from the device since the last time this message was called...
void SetImuRate(double imu_rate, bool force=true)
Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.
bool sleep() const
void GetTrackstatMessages(std::vector< novatel_gps_msgs::TrackstatPtr > &trackstat_msgs)
Provides any TRACKSTAT messages that have been received since the last time this was called...
double Round(double value)
stats::accumulator_set< float, stats::stats< stats::tag::max, stats::tag::min, stats::tag::mean, stats::tag::variance > > offset_stats_
Stats on time offset.
void GetNovatelXYZPositions(std::vector< novatel_gps_msgs::NovatelXYZPtr > &positions)
Provides any BESTXYZ messages that have been received since the last time this was called...
ROSLIB_DECL std::string command(const std::string &cmd)
static void param(const ros::NodeHandle &nh, const std::string &name, int &variable, const int default_value)
int32_t serial_baud_
The baud rate used for serial connection.
#define ROS_WARN_ONCE(...)
void SyncDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
boost::circular_buffer< ros::Time > sync_times_
Buffer of sync message time stamps.
void CheckDeviceForData()
Reads data from the device and publishes any parsed messages.
std::string ErrorMsg() const
Definition: novatel_gps.h:142
void GetNovatelDualAntennaHeadingMessages(std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
Provides any DUALANTENNAHEADING messages that have been received since the last time this was called...
void GetTimeMessages(std::vector< novatel_gps_msgs::TimePtr > &time_messages)
Provides any TIME messages that have been received since the last time this was called.
ROSCPP_DECL bool ok()
void GetGpggaMessages(std::vector< novatel_gps_msgs::GpggaPtr > &gpgga_messages)
Provides any GPGGA messages that have been received since the last time this was called.
std::string device_
The device identifier e.g. /dev/ttyUSB0.
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG_STREAM(...)
void GetNovatelHeading2Messages(std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
Provides any HEADING2 messages that have been received since the last time this was called...
void GetImuMessages(std::vector< sensor_msgs::ImuPtr > &imu_messages)
Provides any Imu messages that have been generated since the last time this was called.
void SyncCallback(const std_msgs::TimeConstPtr &sync)
void GetGprmcMessages(std::vector< novatel_gps_msgs::GprmcPtr > &gprmc_messages)
Provides any GPRMC messages that have been received since the last time this was called.
void DataDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
std::string connection_type_
The connection type, ("serial", "tcp", or "udp")
ROSTIME_DECL const Time TIME_MIN
#define NODELET_INFO(...)
SWRI_NODELET_EXPORT_CLASS(swri_nodelet, TestNodelet)
void GetInspvaMessages(std::vector< novatel_gps_msgs::InspvaPtr > &inspva_messages)
Provides any INSPVA messages that have been received since the last time this was called...
uint32_t getNumSubscribers() const
bool resetService(novatel_gps_msgs::NovatelFRESET::Request &req, novatel_gps_msgs::NovatelFRESET::Response &res)
Service request to reset the gps through FRESET.
swri::Subscriber sync_sub_
Subscriber to listen for sync times from a DIO.
novatel_gps_msgs::NovatelPositionPtr last_novatel_position_
static Time now()
void FixDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
ROSCPP_DECL void shutdown()
double imu_rate_
The rate at which IMU measurements will be published, in Hz.
void GetInsstdevMessages(std::vector< novatel_gps_msgs::InsstdevPtr > &insstdev_messages)
Provides any INSSTDEV messages that have been received since the last time this was called...
void add(const std::string &key, const T &val)
bool Connect(const std::string &device, ConnectionType connection)
Definition: novatel_gps.cpp:89
bool Write(const std::string &command)
Writes the given string of characters to a connected NovAtel device.
ROSCPP_DECL void spinOnce()
diagnostic_updater::Updater diagnostic_updater_
void DeviceDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
void SetSerialBaud(int32_t serial_baud)
Sets the serial baud rate; should be called before configuring a serial connection.


novatel_gps_driver
Author(s):
autogenerated on Thu Jul 16 2020 03:17:30