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/tail.hpp>
138 #include <boost/accumulators/statistics/variance.hpp>
139 #include <boost/circular_buffer.hpp>
140 
141 #include <diagnostic_msgs/DiagnosticStatus.h>
144 #include <gps_common/GPSFix.h>
145 #include <nodelet/nodelet.h>
146 #include <novatel_gps_msgs/NovatelCorrectedImuData.h>
147 #include <novatel_gps_msgs/NovatelFRESET.h>
148 #include <novatel_gps_msgs/NovatelMessageHeader.h>
149 #include <novatel_gps_msgs/NovatelPosition.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>
159 #include <ros/ros.h>
160 #include <sensor_msgs/Imu.h>
161 #include <sensor_msgs/NavSatFix.h>
162 #include <std_msgs/Time.h>
164 #include <swri_roscpp/parameters.h>
165 #include <swri_roscpp/publisher.h>
166 #include <swri_roscpp/subscriber.h>
167 
168 namespace stats = boost::accumulators;
169 
170 namespace novatel_gps_driver
171 {
173  {
174  public:
176  device_(""),
177  connection_type_("serial"),
178  polling_period_(0.05),
179  publish_gpgsa_(false),
180  publish_gpgsv_(false),
181  imu_rate_(100.0),
182  imu_sample_rate_(-1),
183  publish_imu_messages_(false),
190  publish_nmea_messages_(false),
192  publish_time_messages_(false),
193  publish_trackstat_(false),
194  publish_diagnostics_(true),
196  reconnect_delay_s_(0.5),
197  use_binary_messages_(false),
199  connection_(NovatelGps::SERIAL),
200  last_sync_(ros::TIME_MIN),
201  rolling_offset_(stats::tag::rolling_window::window_size = 10),
202  expected_rate_(20),
203  device_timeouts_(0),
205  device_errors_(0),
210  last_published_(ros::TIME_MIN),
211  imu_frame_id_(""),
212  frame_id_("")
213  {
214  }
215 
217  {
218  gps_.Disconnect();
219  }
220 
225  void onInit()
226  {
227  ros::NodeHandle &node = getNodeHandle();
229 
230  swri::param(priv, "device", device_, device_);
231  swri::param(priv, "imu_rate", imu_rate_, imu_rate_);
232  swri::param(priv, "imu_sample_rate", imu_sample_rate_, imu_sample_rate_);
233  swri::param(priv, "publish_clocksteering", publish_clock_steering_, false);
234  swri::param(priv, "publish_gpgsa", publish_gpgsa_, publish_gpgsa_);
235  swri::param(priv, "publish_gpgsv", publish_gpgsv_, publish_gpgsv_);
236  swri::param(priv, "publish_imu_messages", publish_imu_messages_, publish_imu_messages_);
237  swri::param(priv, "publish_novatel_positions", publish_novatel_positions_, publish_novatel_positions_);
238  swri::param(priv, "publish_novatel_xyz_positions", publish_novatel_xyz_positions_, publish_novatel_xyz_positions_);
239  swri::param(priv, "publish_novatel_utm_positions", publish_novatel_utm_positions_, publish_novatel_utm_positions_);
240  swri::param(priv, "publish_novatel_velocity", publish_novatel_velocity_, publish_novatel_velocity_);
241  swri::param(priv, "publish_novatel_heading2", publish_novatel_heading2_, publish_novatel_heading2_);
242  swri::param(priv, "publish_novatel_dual_antenna_heading", publish_novatel_dual_antenna_heading_, publish_novatel_dual_antenna_heading_);
243  swri::param(priv, "publish_nmea_messages", publish_nmea_messages_, publish_nmea_messages_);
244  swri::param(priv, "publish_range_messages", publish_range_messages_, publish_range_messages_);
245  swri::param(priv, "publish_time_messages", publish_time_messages_, publish_time_messages_);
246  swri::param(priv, "publish_trackstat", publish_trackstat_, publish_trackstat_);
247  swri::param(priv, "publish_diagnostics", publish_diagnostics_, publish_diagnostics_);
248  swri::param(priv, "publish_sync_diagnostic", publish_sync_diagnostic_, publish_sync_diagnostic_);
249  swri::param(priv, "polling_period", polling_period_, polling_period_);
250  swri::param(priv, "reconnect_delay_s", reconnect_delay_s_, reconnect_delay_s_);
251  swri::param(priv, "use_binary_messages", use_binary_messages_, use_binary_messages_);
252  swri::param(priv, "span_frame_to_ros_frame", span_frame_to_ros_frame_, span_frame_to_ros_frame_);
253 
254  swri::param(priv, "connection_type", connection_type_, connection_type_);
256  swri::param(priv, "serial_baud", serial_baud_, 115200);
257 
258  swri::param(priv, "imu_frame_id", imu_frame_id_, std::string(""));
259  swri::param(priv, "frame_id", frame_id_, std::string(""));
260 
261  //set NovatelGps parameters
262  swri::param(priv, "gpgga_gprmc_sync_tol", gps_.gpgga_gprmc_sync_tol_, 0.01);
263  swri::param(priv, "gpgga_position_sync_tol", gps_.gpgga_position_sync_tol_, 0.01);
264  swri::param(priv, "wait_for_position", gps_.wait_for_position_, false);
265 
266  // Reset Service
268 
269  sync_sub_ = swri::Subscriber(node, "gps_sync", 100, &NovatelGpsNodelet::SyncCallback, this);
270 
271  std::string gps_topic = node.resolveName("gps");
272  gps_pub_ = swri::advertise<gps_common::GPSFix>(node, gps_topic, 100);
273  fix_pub_ = swri::advertise<sensor_msgs::NavSatFix>(node, "fix", 100);
274 
276  {
277  clocksteering_pub_ = swri::advertise<novatel_gps_msgs::ClockSteering>(node, "clocksteering", 100);
278  }
279 
281  {
282  gpgga_pub_ = swri::advertise<novatel_gps_msgs::Gpgga>(node,"gpgga", 100);
283  gprmc_pub_ = swri::advertise<novatel_gps_msgs::Gprmc>(node,"gprmc", 100);
284  }
285 
286  if (publish_gpgsa_)
287  {
288  gpgsa_pub_ = swri::advertise<novatel_gps_msgs::Gpgsa>(node, "gpgsa", 100);
289  }
290 
292  {
293  imu_pub_ = swri::advertise<sensor_msgs::Imu>(node, "imu", 100);
294  novatel_imu_pub_= swri::advertise<novatel_gps_msgs::NovatelCorrectedImuData>(node, "corrimudata", 100);
295  insstdev_pub_ = swri::advertise<novatel_gps_msgs::Insstdev>(node, "insstdev", 100);
296  inspva_pub_ = swri::advertise<novatel_gps_msgs::Inspva>(node, "inspva", 100);
297  inscov_pub_ = swri::advertise<novatel_gps_msgs::Inscov>(node, "inscov", 100);
298  }
299 
300  if (publish_gpgsv_)
301  {
302  gpgsv_pub_ = swri::advertise<novatel_gps_msgs::Gpgsv>(node, "gpgsv", 100);
303  }
304 
306  {
307  novatel_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelPosition>(node, "bestpos", 100);
308  }
309 
311  {
312  novatel_xyz_position_pub_ = swri::advertise<novatel_gps_msgs::NovatelXYZ>(node, "bestxyz", 100);
313  }
314 
316  {
317  novatel_utm_pub_ = swri::advertise<novatel_gps_msgs::NovatelUtmPosition>(node, "bestutm", 100);
318  }
319 
321  {
322  novatel_velocity_pub_ = swri::advertise<novatel_gps_msgs::NovatelVelocity>(node, "bestvel", 100);
323  }
324 
326  {
327  novatel_heading2_pub_ = swri::advertise<novatel_gps_msgs::NovatelHeading2>(node, "heading2", 100);
328  }
329 
331  {
332  novatel_dual_antenna_heading_pub_ = swri::advertise<novatel_gps_msgs::NovatelDualAntennaHeading>(node, "dual_antenna_heading", 100);
333  }
334 
336  {
337  range_pub_ = swri::advertise<novatel_gps_msgs::Range>(node, "range", 100);
338  }
339 
341  {
342  time_pub_ = swri::advertise<novatel_gps_msgs::Time>(node, "time", 100);
343  }
344 
345  if (publish_trackstat_)
346  {
347  trackstat_pub_ = swri::advertise<novatel_gps_msgs::Trackstat>(node, "trackstat", 100);
348  }
349 
350  hw_id_ = "Novatel GPS (" + device_ +")";
352  {
354  diagnostic_updater_.add("Connection",
355  this,
357  diagnostic_updater_.add("Hardware",
358  this,
360  diagnostic_updater_.add("Data",
361  this,
363  diagnostic_updater_.add("Rate",
364  this,
366  diagnostic_updater_.add("GPS Fix",
367  this,
370  {
371  diagnostic_updater_.add("Sync",
372  this,
374  }
375  }
376 
378 
379  thread_ = boost::thread(&NovatelGpsNodelet::Spin, this);
380  NODELET_INFO("%s initialized", hw_id_.c_str());
381  }
382 
383  void SyncCallback(const std_msgs::TimeConstPtr& sync)
384  {
385  boost::unique_lock<boost::mutex> lock(mutex_);
386  sync_times_.push_back(sync->data);
387  }
388 
393  void Spin()
394  {
395  std::string format_suffix;
397  {
398  // NovAtel logs in binary format always end with "b", while ones in
399  // ASCII format always end in "a".
400  format_suffix = "b";
401  }
402  else
403  {
404  format_suffix = "a";
405  }
406 
407  NovatelMessageOpts opts;
408  opts["gpgga"] = polling_period_;
409  opts["gprmc"] = polling_period_;
410  opts["bestpos" + format_suffix] = polling_period_; // Best position
411  opts["time" + format_suffix] = 1.0; // Time
413  {
414  opts["bestxyz" + format_suffix] = polling_period_;
415  }
417  {
418  opts["bestutm" + format_suffix] = polling_period_;
419  }
421  {
422  opts["heading2" + format_suffix] = polling_period_;
423  }
425  {
426  opts["dual_antenna_heading" + format_suffix] = polling_period_;
427  }
428  if (publish_gpgsa_)
429  {
430  opts["gpgsa"] = polling_period_;
431  }
432  if (publish_gpgsv_)
433  {
434  opts["gpgsv"] = 1.0;
435  }
437  {
438  opts["clocksteering" + format_suffix] = 1.0;
439  }
441  {
442  double period = 1.0 / imu_rate_;
443  opts["corrimudata" + format_suffix] = period;
444  opts["inscov" + format_suffix] = 1.0;
445  opts["inspva" + format_suffix] = period;
446  opts["insstdev" + format_suffix] = 1.0;
448  {
449  NODELET_WARN("Using the ASCII message format with CORRIMUDATA logs is not recommended. "
450  "A serial link will not be able to keep up with the data rate.");
451  }
452 
453  // Only configure the imu rate if we set the param
454  if (imu_sample_rate_ > 0)
455  {
457  }
458  }
460  {
461  opts["bestvel" + format_suffix] = polling_period_; // Best velocity
462  }
464  {
465  opts["range" + format_suffix] = 1.0; // Range. 1 msg/sec is max rate
466  }
467  if (publish_trackstat_)
468  {
469  opts["trackstat" + format_suffix] = 1.0; // Trackstat
470  }
471  // Set the serial baud rate if needed
473  {
475  }
476  while (ros::ok())
477  {
478  if (gps_.Connect(device_, connection_, opts))
479  {
480  // Connected to device. Begin reading/processing data
481  NODELET_INFO("%s connected to device", hw_id_.c_str());
482  while (gps_.IsConnected() && ros::ok())
483  {
484  // Read data from the device and publish any received messages
486 
487  // Poke the diagnostic updater. It will only fire diagnostics if
488  // its internal timer (1 Hz) has elapsed. Otherwise, this is a
489  // noop
491  {
493  }
494 
495  // Spin once to let the ROS callbacks fire
496  ros::spinOnce();
497  // Sleep for a microsecond to prevent CPU hogging
498  boost::this_thread::sleep(boost::posix_time::microseconds(1));
499  } // While (gps_.IsConnected() && ros::ok()) (inner loop to process data from device)
500  }
501  else // Could not connect to the device
502  {
503  NODELET_ERROR_THROTTLE(1, "Error connecting to device <%s:%s>: %s",
504  connection_type_.c_str(),
505  device_.c_str(),
506  gps_.ErrorMsg().c_str());
507  device_errors_++;
509  }
510 
511  if (ros::ok())
512  {
513  // If ROS is still OK but we got disconnected, we're going to try
514  // to reconnect, but wait just a bit so we don't spam the device.
516  }
517 
518  // Poke the diagnostic updater. It will only fire diagnostics if
519  // its internal timer (1 Hz) has elapsed. Otherwise, this is a
520  // noop
522  {
524  }
525 
526  // Spin once to let the ROS callbacks fire
527  ros::spinOnce();
528  // Sleep for a microsecond to prevent CPU hogging
529  boost::this_thread::sleep(boost::posix_time::microseconds(1));
530 
532  {
533  // If we're playing a PCAP file, we only want to play it once.
534  ros::shutdown();
535  }
536  } // While (ros::ok) (outer loop to reconnect to device)
537 
538  gps_.Disconnect();
539  NODELET_INFO("%s disconnected and shut down", hw_id_.c_str());
540  }
541 
542  private:
543  // Parameters
545  std::string device_;
547  std::string connection_type_;
549  int32_t serial_baud_;
554  double imu_rate_;
574 
596 
598 
601 
602  boost::thread thread_;
603  boost::mutex mutex_;
604 
609  boost::circular_buffer<ros::Time> sync_times_;
611  boost::circular_buffer<ros::Time> msg_times_;
613  stats::accumulator_set<float, stats::stats<
614  stats::tag::max,
615  stats::tag::min,
616  stats::tag::mean,
617  stats::tag::variance> > offset_stats_;
619  stats::accumulator_set<float, stats::stats<stats::tag::rolling_mean> > rolling_offset_;
620 
621  // ROS diagnostics
622  std::string error_msg_;
624  std::string hw_id_;
628  int32_t device_errors_;
634  novatel_gps_msgs::NovatelPositionPtr last_novatel_position_;
635 
636  std::string imu_frame_id_;
637  std::string frame_id_;
638 
642  bool resetService(novatel_gps_msgs::NovatelFRESET::Request& req,
643  novatel_gps_msgs::NovatelFRESET::Response& res)
644  {
645  if (gps_.IsConnected() == false)
646  {
647  res.success = false;
648  }
649 
650  // Formulate the reset command and send it to the device
651  std::string command = "FRESET ";
652  command += req.target.length() ? "STANDARD" : req.target;
653  command += "\r\n";
654  gps_.Write(command);
655 
656  if (req.target.length() == 0)
657  {
658  ROS_WARN("No FRESET target specified. Doing FRESET STANDARD. This may be undesired behavior.");
659  }
660 
661  res.success = true;
662  return true;
663  }
664 
672  {
673  std::vector<novatel_gps_msgs::NovatelPositionPtr> position_msgs;
674  std::vector<novatel_gps_msgs::NovatelXYZPtr> xyz_position_msgs;
675  std::vector<novatel_gps_msgs::NovatelUtmPositionPtr> utm_msgs;
676  std::vector<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs;
677  std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs;
678  std::vector<gps_common::GPSFixPtr> fix_msgs;
679  std::vector<novatel_gps_msgs::GpggaPtr> gpgga_msgs;
680  std::vector<novatel_gps_msgs::GprmcPtr> gprmc_msgs;
681 
682  // This call appears to block if the serial device is disconnected
683  NovatelGps::ReadResult result = gps_.ProcessData();
684  if (result == NovatelGps::READ_ERROR)
685  {
686  NODELET_ERROR_THROTTLE(1, "Error reading from device <%s:%s>: %s",
687  connection_type_.c_str(),
688  device_.c_str(),
689  gps_.ErrorMsg().c_str());
690  device_errors_++;
691  }
692  else if (result == NovatelGps::READ_TIMEOUT)
693  {
694  device_timeouts_++;
695  }
696  else if (result == NovatelGps::READ_INTERRUPTED)
697  {
698  // If we are interrupted by a signal, ROS is probably
699  // quitting, but we'll wait for ROS to tell us to quit.
700  device_interrupts_++;
701  }
702  else if (result == NovatelGps::READ_PARSE_FAILED)
703  {
704  NODELET_ERROR("Error reading from device <%s:%s>: %s",
705  connection_type_.c_str(),
706  device_.c_str(),
707  gps_.ErrorMsg().c_str());
708  gps_parse_failures_++;
709  }
710  else if (result == NovatelGps::READ_INSUFFICIENT_DATA)
711  {
712  gps_insufficient_data_warnings_++;
713  }
714 
715  // Read messages from the driver into the local message lists
716  gps_.GetGpggaMessages(gpgga_msgs);
717  gps_.GetGprmcMessages(gprmc_msgs);
718  gps_.GetNovatelPositions(position_msgs);
719  gps_.GetNovatelXYZPositions(xyz_position_msgs);
720  gps_.GetNovatelUtmPositions(utm_msgs);
721  gps_.GetFixMessages(fix_msgs);
722  gps_.GetNovatelHeading2Messages(heading2_msgs);
723  gps_.GetNovatelDualAntennaHeadingMessages(dual_antenna_heading_msgs);
724 
725  // Increment the measurement count by the number of messages we just
726  // read
727  measurement_count_ += gpgga_msgs.size();
728 
729  // If there are new position messages, store the most recent
730  if (!position_msgs.empty())
731  {
732  last_novatel_position_ = position_msgs.back();
733  }
734 
735  // Find all the gppga messages that are within 20 ms of whole
736  // numbered UTC seconds and push their stamps onto the msg_times
737  // buffer
738  for (const auto& msg : gpgga_msgs)
739  {
740  if (msg->utc_seconds != 0)
741  {
742  int64_t second = static_cast<int64_t>(swri_math_util::Round(msg->utc_seconds));
743  double difference = std::fabs(msg->utc_seconds - second);
744 
745  if (difference < 0.02)
746  {
747  msg_times_.push_back(msg->header.stamp);
748  }
749  }
750  }
751 
752  // If timesync messages are available, CalculateTimeSync will
753  // update a stat accumulator of the offset of the TimeSync message
754  // stamp from the GPS message stamp
756 
757  // If TimeSync messages are available, CalculateTimeSync keeps
758  // an acculumator of their offset, which is used to
759  // calculate a rolling mean of the offset to apply to all messages
760  ros::Duration sync_offset(0); // If no TimeSyncs, assume 0 offset
761  if (last_sync_ != ros::TIME_MIN)
762  {
763  sync_offset = ros::Duration(stats::rolling_mean(rolling_offset_));
764  }
765  NODELET_DEBUG_STREAM("GPS TimeSync offset is " << sync_offset);
766 
767  if (publish_nmea_messages_)
768  {
769  for (const auto& msg : gpgga_msgs)
770  {
771  msg->header.stamp += sync_offset;
772  msg->header.frame_id = frame_id_;
773  gpgga_pub_.publish(msg);
774  }
775 
776  for (const auto& msg : gprmc_msgs)
777  {
778  msg->header.stamp += sync_offset;
779  msg->header.frame_id = frame_id_;
780  gprmc_pub_.publish(msg);
781  }
782  }
783 
784  if (publish_gpgsa_)
785  {
786  std::vector<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs;
787  gps_.GetGpgsaMessages(gpgsa_msgs);
788  for (const auto& msg : gpgsa_msgs)
789  {
790  msg->header.stamp = ros::Time::now();
791  msg->header.frame_id = frame_id_;
792  gpgsa_pub_.publish(msg);
793  }
794  }
795 
796  if (publish_gpgsv_)
797  {
798  std::vector<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs;
799  gps_.GetGpgsvMessages(gpgsv_msgs);
800  for (const auto& msg : gpgsv_msgs)
801  {
802  msg->header.stamp = ros::Time::now();
803  msg->header.frame_id = frame_id_;
804  gpgsv_pub_.publish(msg);
805  }
806  }
807 
808  if (publish_novatel_positions_)
809  {
810  for (const auto& msg : position_msgs)
811  {
812  msg->header.stamp += sync_offset;
813  msg->header.frame_id = frame_id_;
814  novatel_position_pub_.publish(msg);
815  }
816  }
817 
818  if (publish_novatel_xyz_positions_)
819  {
820  for (const auto& msg : xyz_position_msgs)
821  {
822  msg->header.stamp += sync_offset;
823  msg->header.frame_id = frame_id_;
824  novatel_xyz_position_pub_.publish(msg);
825  }
826  }
827 
828  if (publish_novatel_utm_positions_)
829  {
830  for (const auto& msg : utm_msgs)
831  {
832  msg->header.stamp += sync_offset;
833  msg->header.frame_id = frame_id_;
834  novatel_utm_pub_.publish(msg);
835  }
836  }
837 
838  if (publish_novatel_heading2_)
839  {
840  for (const auto& msg : heading2_msgs)
841  {
842  msg->header.stamp += sync_offset;
843  msg->header.frame_id = frame_id_;
844  novatel_heading2_pub_.publish(msg);
845  }
846  }
847 
848  if (publish_novatel_dual_antenna_heading_)
849  {
850  for (const auto& msg : dual_antenna_heading_msgs)
851  {
852  msg->header.stamp += sync_offset;
853  msg->header.frame_id = frame_id_;
854  novatel_dual_antenna_heading_pub_.publish(msg);
855  }
856  }
857 
858  if (publish_clock_steering_)
859  {
860  std::vector<novatel_gps_msgs::ClockSteeringPtr> msgs;
861  gps_.GetClockSteeringMessages(msgs);
862  for (const auto& msg : msgs)
863  {
864  clocksteering_pub_.publish(msg);
865  }
866  }
867 
868  if (publish_novatel_velocity_)
869  {
870  std::vector<novatel_gps_msgs::NovatelVelocityPtr> velocity_msgs;
871  gps_.GetNovatelVelocities(velocity_msgs);
872  for (const auto& msg : velocity_msgs)
873  {
874  msg->header.stamp += sync_offset;
875  msg->header.frame_id = frame_id_;
876  novatel_velocity_pub_.publish(msg);
877  }
878  }
879  if (publish_time_messages_)
880  {
881  std::vector<novatel_gps_msgs::TimePtr> time_msgs;
882  gps_.GetTimeMessages(time_msgs);
883  for (const auto& msg : time_msgs)
884  {
885  msg->header.stamp += sync_offset;
886  msg->header.frame_id = frame_id_;
887  time_pub_.publish(msg);
888  }
889  }
890  if (publish_range_messages_)
891  {
892  std::vector<novatel_gps_msgs::RangePtr> range_msgs;
893  gps_.GetRangeMessages(range_msgs);
894  for (const auto& msg : range_msgs)
895  {
896  msg->header.stamp += sync_offset;
897  msg->header.frame_id = frame_id_;
898  range_pub_.publish(msg);
899  }
900  }
901  if (publish_trackstat_)
902  {
903  std::vector<novatel_gps_msgs::TrackstatPtr> trackstat_msgs;
904  gps_.GetTrackstatMessages(trackstat_msgs);
905  for (const auto& msg : trackstat_msgs)
906  {
907  msg->header.stamp += sync_offset;
908  msg->header.frame_id = frame_id_;
909  trackstat_pub_.publish(msg);
910  }
911  }
912  if (publish_imu_messages_)
913  {
914  std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_imu_msgs;
915  gps_.GetNovatelCorrectedImuData(novatel_imu_msgs);
916  for (const auto& msg : novatel_imu_msgs)
917  {
918  msg->header.stamp += sync_offset;
919  msg->header.frame_id = imu_frame_id_;
920  novatel_imu_pub_.publish(msg);
921  }
922 
923  std::vector<sensor_msgs::ImuPtr> imu_msgs;
924  gps_.GetImuMessages(imu_msgs);
925  for (const auto& msg : imu_msgs)
926  {
927  msg->header.stamp += sync_offset;
928  msg->header.frame_id = imu_frame_id_;
929  imu_pub_.publish(msg);
930  }
931 
932  std::vector<novatel_gps_msgs::InscovPtr> inscov_msgs;
933  gps_.GetInscovMessages(inscov_msgs);
934  for (const auto& msg : inscov_msgs)
935  {
936  msg->header.stamp += sync_offset;
937  msg->header.frame_id = imu_frame_id_;
938  inscov_pub_.publish(msg);
939  }
940 
941  std::vector<novatel_gps_msgs::InspvaPtr> inspva_msgs;
942  gps_.GetInspvaMessages(inspva_msgs);
943  for (const auto& msg : inspva_msgs)
944  {
945  msg->header.stamp += sync_offset;
946  msg->header.frame_id = imu_frame_id_;
947  inspva_pub_.publish(msg);
948  }
949 
950  std::vector<novatel_gps_msgs::InsstdevPtr> insstdev_msgs;
951  gps_.GetInsstdevMessages(insstdev_msgs);
952  for (const auto& msg : insstdev_msgs)
953  {
954  msg->header.stamp += sync_offset;
955  msg->header.frame_id = imu_frame_id_;
956  insstdev_pub_.publish(msg);
957  }
958  }
959 
960  for (const auto& msg : fix_msgs)
961  {
962  msg->header.stamp += sync_offset;
963  msg->header.frame_id = frame_id_;
964  gps_pub_.publish(msg);
965 
966  if (fix_pub_.getNumSubscribers() > 0)
967  {
968  sensor_msgs::NavSatFixPtr fix_msg = ConvertGpsFixToNavSatFix(msg);
969 
970  fix_pub_.publish(fix_msg);
971  }
972 
973  // If the time between GPS message stamps is greater than 1.5
974  // times the expected publish rate, increment the
975  // publish_rate_warnings_ counter, which is used in diagnostics
976  if (last_published_ != ros::TIME_MIN &&
977  (msg->header.stamp - last_published_).toSec() > 1.5 * (1.0 / expected_rate_))
978  {
979  publish_rate_warnings_++;
980  }
981 
982  last_published_ = msg->header.stamp;
983  }
984  }
985 
986  sensor_msgs::NavSatFixPtr ConvertGpsFixToNavSatFix(const gps_common::GPSFixPtr& msg)
987  {
988  sensor_msgs::NavSatFixPtr fix_msg = boost::make_shared<sensor_msgs::NavSatFix>();
989  fix_msg->header = msg->header;
990  fix_msg->latitude = msg->latitude;
991  fix_msg->longitude = msg->longitude;
992  fix_msg->altitude = msg->altitude;
993  fix_msg->position_covariance = msg->position_covariance;
994  switch (msg->status.status)
995  {
996  case gps_common::GPSStatus::STATUS_NO_FIX:
997  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_NO_FIX;
998  break;
999  case gps_common::GPSStatus::STATUS_FIX:
1000  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1001  break;
1002  case gps_common::GPSStatus::STATUS_SBAS_FIX:
1003  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_SBAS_FIX;
1004  break;
1005  case gps_common::GPSStatus::STATUS_GBAS_FIX:
1006  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;
1007  break;
1008  case gps_common::GPSStatus::STATUS_DGPS_FIX:
1009  case gps_common::GPSStatus::STATUS_WAAS_FIX:
1010  default:
1011  ROS_WARN_ONCE("Unsupported fix status: %d", msg->status.status);
1012  fix_msg->status.status = sensor_msgs::NavSatStatus::STATUS_FIX;
1013  break;
1014  }
1015  switch (msg->position_covariance_type)
1016  {
1017  case gps_common::GPSFix::COVARIANCE_TYPE_KNOWN:
1018  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;
1019  break;
1020  case gps_common::GPSFix::COVARIANCE_TYPE_APPROXIMATED:
1021  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_APPROXIMATED;
1022  break;
1023  case gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN:
1024  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
1025  break;
1026  case gps_common::GPSFix::COVARIANCE_TYPE_UNKNOWN:
1027  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1028  break;
1029  default:
1030  ROS_WARN_ONCE("Unsupported covariance type: %d", msg->position_covariance_type);
1031  fix_msg->position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_UNKNOWN;
1032  break;
1033  }
1034  // TODO Figure out how to set this based on info in a GPSFix
1035  fix_msg->status.service = 0;
1036 
1037  return fix_msg;
1038  }
1039 
1045  {
1046  boost::unique_lock<boost::mutex> lock(mutex_);
1047  int32_t synced_i = -1;
1048  int32_t synced_j = -1;
1049  // Loop over sync times buffer
1050  for (int32_t i = 0; i < sync_times_.size(); i++)
1051  {
1052  // Loop over message times buffer
1053  for (int32_t j = synced_j + 1; j < msg_times_.size(); j++)
1054  {
1055  // Offset is the difference between the sync time and message time
1056  double offset = (sync_times_[i] - msg_times_[j]).toSec();
1057  if (std::fabs(offset) < 0.49)
1058  {
1059  // If the offset is less than 0.49 sec, the messages match
1060  synced_i = static_cast<int32_t>(i);
1061  synced_j = static_cast<int32_t>(j);
1062  // Add the offset to the stats accumulators
1063  offset_stats_(offset);
1064  rolling_offset_(offset);
1065  // Update the last sync
1066  last_sync_ = sync_times_[i];
1067  // Break out of the inner loop and continue looping through sync times
1068  break;
1069  }
1070  }
1071  }
1072 
1073  // Remove all the timesync messages that have been matched from the queue
1074  for (int i = 0; i <= synced_i && !sync_times_.empty(); i++)
1075  {
1076  sync_times_.pop_front();
1077  }
1078 
1079  // Remove all the gps messages that have been matched from the queue
1080  for (int j = 0; j <= synced_j && !msg_times_.empty(); j++)
1081  {
1082  msg_times_.pop_front();
1083  }
1084  }
1085 
1087  {
1088  status.clear();
1089  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1090 
1091  if (!last_novatel_position_)
1092  {
1093  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Status");
1094  NODELET_WARN("No GPS status data.");
1095  return;
1096  }
1097 
1098  status.add("Solution Status", last_novatel_position_->solution_status);
1099  status.add("Position Type", last_novatel_position_->position_type);
1100  status.add("Solution Age", last_novatel_position_->solution_age);
1101  status.add("Satellites Tracked", static_cast<int>(last_novatel_position_->num_satellites_tracked));
1102  status.add("Satellites Used", static_cast<int>(last_novatel_position_->num_satellites_used_in_solution));
1103  status.add("Software Version", last_novatel_position_->novatel_msg_header.receiver_software_version);
1104 
1105  const novatel_gps_msgs::NovatelReceiverStatus& rcvr_status = last_novatel_position_->novatel_msg_header.receiver_status;
1106  status.add("Status Code", rcvr_status.original_status_code);
1107 
1108  if (last_novatel_position_->novatel_msg_header.receiver_status.original_status_code != 0)
1109  {
1110  uint8_t level = diagnostic_msgs::DiagnosticStatus::WARN;
1111  std::string msg = "Status Warning";
1112  // If the antenna is disconnected/broken, this is an error
1113  if (rcvr_status.antenna_is_open ||
1114  rcvr_status.antenna_is_shorted ||
1115  !rcvr_status.antenna_powered)
1116  {
1117  msg += " Antenna Problem";
1118  level = diagnostic_msgs::DiagnosticStatus::ERROR;
1119  }
1120  status.add("Error Flag", rcvr_status.error_flag?"true":"false");
1121  status.add("Temperature Flag", rcvr_status.temperature_flag?"true":"false");
1122  status.add("Voltage Flag", rcvr_status.voltage_supply_flag?"true":"false");
1123  status.add("Antenna Not Powered", rcvr_status.antenna_powered?"false":"true");
1124  status.add("Antenna Open", rcvr_status.antenna_is_open?"true":"false");
1125  status.add("Antenna Shorted", rcvr_status.antenna_is_shorted?"true":"false");
1126  status.add("CPU Overloaded", rcvr_status.cpu_overload_flag?"true":"false");
1127  status.add("COM1 Buffer Overrun", rcvr_status.com1_buffer_overrun?"true":"false");
1128  status.add("COM2 Buffer Overrun", rcvr_status.com2_buffer_overrun?"true":"false");
1129  status.add("COM3 Buffer Overrun", rcvr_status.com3_buffer_overrun?"true":"false");
1130  status.add("USB Buffer Overrun", rcvr_status.usb_buffer_overrun?"true":"false");
1131  status.add("RF1 AGC Flag", rcvr_status.rf1_agc_flag?"true":"false");
1132  status.add("RF2 AGC Flag", rcvr_status.rf2_agc_flag?"true":"false");
1133  status.add("Almanac Flag", rcvr_status.almanac_flag?"true":"false");
1134  status.add("Position Solution Flag", rcvr_status.position_solution_flag?"true":"false");
1135  status.add("Position Fixed Flag", rcvr_status.position_fixed_flag?"true":"false");
1136  status.add("Clock Steering Status", rcvr_status.clock_steering_status_enabled?"true":"false");
1137  status.add("Clock Model Flag", rcvr_status.clock_model_flag?"true":"false");
1138  status.add("OEMV External Oscillator Flag", rcvr_status.oemv_external_oscillator_flag?"true":"false");
1139  status.add("Software Resource Flag", rcvr_status.software_resource_flag?"true":"false");
1140  status.add("Auxiliary1 Flag", rcvr_status.aux1_status_event_flag?"true":"false");
1141  status.add("Auxiliary2 Flag", rcvr_status.aux2_status_event_flag?"true":"false");
1142  status.add("Auxiliary3 Flag", rcvr_status.aux3_status_event_flag?"true":"false");
1143  NODELET_WARN("Novatel status code: %d", rcvr_status.original_status_code);
1144  status.summary(level, msg);
1145  }
1146  }
1147 
1149  {
1150  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1151 
1152  if (last_sync_ == ros::TIME_MIN)
1153  {
1154  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "No Sync");
1155  return;
1156  }
1157  else if (last_sync_ < ros::Time::now() - ros::Duration(10))
1158  {
1159  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Sync Stale");
1160  NODELET_ERROR("GPS time synchronization is stale.");
1161  }
1162 
1163  status.add("Last Sync", last_sync_);
1164  status.add("Mean Offset", stats::mean(offset_stats_));
1165  status.add("Mean Offset (rolling)", stats::rolling_mean(rolling_offset_));
1166  status.add("Offset Variance", stats::variance(offset_stats_));
1167  status.add("Min Offset", stats::min(offset_stats_));
1168  status.add("Max Offset", stats::max(offset_stats_));
1169  }
1170 
1172  {
1173  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1174 
1175  if (device_errors_ > 0)
1176  {
1177  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Device Errors");
1178  }
1179  else if (device_interrupts_ > 0)
1180  {
1181  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Interrupts");
1182  NODELET_WARN("device interrupts detected <%s:%s>: %d",
1183  connection_type_.c_str(), device_.c_str(), device_interrupts_);
1184  }
1185  else if (device_timeouts_)
1186  {
1187  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Device Timeouts");
1188  NODELET_WARN("device timeouts detected <%s:%s>: %d",
1189  connection_type_.c_str(), device_.c_str(), device_timeouts_);
1190  }
1191 
1192  status.add("Errors", device_errors_);
1193  status.add("Interrupts", device_interrupts_);
1194  status.add("Timeouts", device_timeouts_);
1195 
1196  device_timeouts_ = 0;
1197  device_interrupts_ = 0;
1198  device_errors_ = 0;
1199  }
1200 
1202  {
1203  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1204 
1205  if (gps_parse_failures_ > 0)
1206  {
1207  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Parse Failures");
1208  NODELET_WARN("gps parse failures detected <%s>: %d",
1209  hw_id_.c_str(), gps_parse_failures_);
1210  }
1211 
1212  status.add("Parse Failures", gps_parse_failures_);
1213  status.add("Insufficient Data Warnings", gps_insufficient_data_warnings_);
1214 
1215  gps_parse_failures_ = 0;
1216  gps_insufficient_data_warnings_ = 0;
1217  }
1218 
1220  {
1221  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal");
1222 
1223  double period = diagnostic_updater_.getPeriod();
1224  double measured_rate = measurement_count_ / period;
1225 
1226  if (measured_rate < 0.5 * expected_rate_)
1227  {
1228  status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Insufficient Data Rate");
1229  NODELET_ERROR("insufficient data rate <%s>: %lf < %lf",
1230  hw_id_.c_str(), measured_rate, expected_rate_);
1231  }
1232  else if (measured_rate < 0.95 * expected_rate_)
1233  {
1234  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Data Rate");
1235  NODELET_WARN("insufficient data rate <%s>: %lf < %lf",
1236  hw_id_.c_str(), measured_rate, expected_rate_);
1237  }
1238 
1239  status.add("Measurement Rate (Hz)", measured_rate);
1240 
1241  measurement_count_ = 0;
1242  }
1243 
1245  {
1246  status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Nominal Publish Rate");
1247 
1248  double elapsed = (ros::Time::now() - last_published_).toSec();
1249  bool gap_detected = false;
1250  if (elapsed > 2.0 / expected_rate_)
1251  {
1252  publish_rate_warnings_++;
1253  gap_detected = true;
1254  }
1255 
1256  if (publish_rate_warnings_ > 1 || gap_detected)
1257  {
1258  status.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Insufficient Publish Rate");
1259  NODELET_WARN("publish rate failures detected <%s>: %d",
1260  hw_id_.c_str(), publish_rate_warnings_);
1261  }
1262 
1263  status.add("Warnings", publish_rate_warnings_);
1264 
1265  publish_rate_warnings_ = 0;
1266  }
1267  };
1268 }
1269 
1270 // 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
Define NovatelMessageOpts as a map from message name to log period (seconds)
Definition: novatel_gps.h:87
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
#define NODELET_ERROR_THROTTLE(rate,...)
void setHardwareID(const std::string &hwid)
bool sleep() const
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 RateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &status)
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.
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:136
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:88
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 Wed Jul 3 2019 19:36:46