novatel_gps.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 
30 #include <sstream>
31 #include <net/ethernet.h>
32 #include <netinet/udp.h>
33 #include <netinet/tcp.h>
34 #include <netinet/ip.h>
36 
37 #include <boost/algorithm/string/join.hpp>
38 #include <boost/make_shared.hpp>
39 
40 #include <ros/ros.h>
41 #include <tf/tf.h>
42 
43 namespace novatel_gps_driver
44 {
46  gpsfix_sync_tol_(0.01),
47  wait_for_sync_(true),
48  connection_(SERIAL),
49  is_connected_(false),
50  imu_rate_forced_(false),
51  utc_offset_(0),
52  serial_baud_(115200),
53  tcp_socket_(io_service_),
54  pcap_(nullptr),
55  clocksteering_msgs_(MAX_BUFFER_SIZE),
56  corrimudata_msgs_(MAX_BUFFER_SIZE),
57  gpgga_msgs_(MAX_BUFFER_SIZE),
58  gpgsa_msgs_(MAX_BUFFER_SIZE),
59  gpgsv_msgs_(MAX_BUFFER_SIZE),
60  gphdt_msgs_(MAX_BUFFER_SIZE),
61  gprmc_msgs_(MAX_BUFFER_SIZE),
62  imu_msgs_(MAX_BUFFER_SIZE),
63  inscov_msgs_(MAX_BUFFER_SIZE),
64  inspva_msgs_(MAX_BUFFER_SIZE),
65  inspvax_msgs_(MAX_BUFFER_SIZE),
66  insstdev_msgs_(MAX_BUFFER_SIZE),
67  novatel_positions_(MAX_BUFFER_SIZE),
68  novatel_xyz_positions_(MAX_BUFFER_SIZE),
69  novatel_utm_positions_(MAX_BUFFER_SIZE),
70  novatel_velocities_(MAX_BUFFER_SIZE),
71  bestpos_sync_buffer_(SYNC_BUFFER_SIZE),
72  bestvel_sync_buffer_(SYNC_BUFFER_SIZE),
73  heading2_msgs_(MAX_BUFFER_SIZE),
74  dual_antenna_heading_msgs_(MAX_BUFFER_SIZE),
75  psrdop2_msgs_(MAX_BUFFER_SIZE),
76  range_msgs_(MAX_BUFFER_SIZE),
77  time_msgs_(MAX_BUFFER_SIZE),
78  trackstat_msgs_(MAX_BUFFER_SIZE),
79  imu_rate_(-1.0),
80  apply_vehicle_body_rotation_(false)
81  {
82  }
83 
85  {
86  Disconnect();
87  }
88 
90  const std::string& device,
91  ConnectionType connection)
92  {
93  NovatelMessageOpts opts;
94  opts["gpgga"] = 0.05;
95  opts["gprmc"] = 0.05;
96  opts["bestposa"] = 0.05;
97  opts["timea"] = 1.0;
98  opts["rangea"] = 1;
99  return Connect(device, connection, opts);
100  }
101 
103  const std::string& device,
104  ConnectionType connection,
105  NovatelMessageOpts const& opts)
106  {
107  Disconnect();
108 
109  connection_ = connection;
110 
111  if (connection_ == SERIAL)
112  {
113  return CreateSerialConnection(device, opts);
114  }
115  else if (connection_ == TCP || connection_ == UDP)
116  {
117  return CreateIpConnection(device, opts);
118  }
119  else if (connection_ == PCAP)
120  {
121  return CreatePcapConnection(device, opts);
122  }
123 
124  error_msg_ = "Invalid connection type.";
125 
126  return false;
127 
128  }
129 
131  {
132  if (connection == "serial")
133  {
134  return SERIAL;
135  }
136  else if (connection == "udp")
137  {
138  return UDP;
139  }
140  else if (connection == "tcp")
141  {
142  return TCP;
143  }
144  else if (connection == "pcap")
145  {
146  return PCAP;
147  }
148 
149  return INVALID;
150  }
151 
153  {
154  if (connection_ == SERIAL)
155  {
156  serial_.Close();
157  }
158  else if (connection_ == TCP)
159  {
160  tcp_socket_.close();
161  }
162  else if (connection_ == UDP)
163  {
164  if (udp_socket_)
165  {
166  udp_socket_->close();
167  udp_socket_.reset();
168  }
169  if (udp_endpoint_)
170  {
171  udp_endpoint_.reset();
172  }
173  }
174  else if (connection_ == PCAP)
175  {
176  if (pcap_ != nullptr)
177  {
178  pcap_close(pcap_);
179  pcap_ = nullptr;
180  }
181  }
182  is_connected_ = false;
183  }
184 
185  void NovatelGps::ApplyVehicleBodyRotation(const bool& apply_rotation)
186  {
187  apply_vehicle_body_rotation_ = apply_rotation;
188  }
189 
191  {
192  NovatelGps::ReadResult read_result = ReadData();
193 
194  if (read_result != READ_SUCCESS)
195  {
196  return read_result;
197  }
198 
199  ros::Time stamp = ros::Time::now();
200  std::vector<NmeaSentence> nmea_sentences;
201  std::vector<NovatelSentence> novatel_sentences;
202  std::vector<BinaryMessage> binary_messages;
203 
204  if (!data_buffer_.empty())
205  {
206  nmea_buffer_.insert(nmea_buffer_.end(),
207  data_buffer_.begin(),
208  data_buffer_.end());
209 
210  data_buffer_.clear();
211 
212  std::string remaining_buffer;
213 
215  nmea_buffer_,
216  nmea_sentences,
217  novatel_sentences,
218  binary_messages,
219  remaining_buffer))
220  {
221  read_result = READ_PARSE_FAILED;
222  error_msg_ = "Parse failure extracting sentences.";
223  }
224 
225  nmea_buffer_ = remaining_buffer;
226 
227  ROS_DEBUG("Parsed: %lu NMEA / %lu NovAtel / %lu Binary messages",
228  nmea_sentences.size(), novatel_sentences.size(), binary_messages.size());
229  if (!nmea_buffer_.empty())
230  {
231  ROS_DEBUG("%lu unparsed bytes left over.", nmea_buffer_.size());
232  }
233  }
234 
235  double most_recent_utc_time = extractor_.GetMostRecentUtcTime(nmea_sentences);
236 
237  for(const auto& sentence : nmea_sentences)
238  {
239  try
240  {
241  NovatelGps::ReadResult result = ParseNmeaSentence(sentence, stamp, most_recent_utc_time);
242  if (result != READ_SUCCESS)
243  {
244  read_result = result;
245  }
246  }
247  catch (const ParseException& p)
248  {
249  error_msg_ = p.what();
250  ROS_WARN("%s", p.what());
251  ROS_WARN("For sentence: [%s]", boost::algorithm::join(sentence.body, ",").c_str());
252  read_result = READ_PARSE_FAILED;
253  }
254  }
255 
256  for(const auto& sentence : novatel_sentences)
257  {
258  try
259  {
260  NovatelGps::ReadResult result = ParseNovatelSentence(sentence, stamp);
261  if (result != READ_SUCCESS)
262  {
263  read_result = result;
264  }
265  }
266  catch (const ParseException& p)
267  {
268  error_msg_ = p.what();
269  ROS_WARN("%s", p.what());
270  read_result = READ_PARSE_FAILED;
271  }
272  }
273 
274  for(const auto& msg : binary_messages)
275  {
276  try
277  {
279  if (result != READ_SUCCESS)
280  {
281  read_result = result;
282  }
283  }
284  catch (const ParseException& p)
285  {
286  error_msg_ = p.what();
287  ROS_WARN("%s", p.what());
288  read_result = READ_PARSE_FAILED;
289  }
290  }
291 
292  return read_result;
293  }
294 
295  void NovatelGps::GetNovatelPositions(std::vector<novatel_gps_msgs::NovatelPositionPtr>& positions)
296  {
297  positions.clear();
298  positions.insert(positions.end(), novatel_positions_.begin(), novatel_positions_.end());
299  novatel_positions_.clear();
300  }
301 
302  void NovatelGps::GetNovatelXYZPositions(std::vector<novatel_gps_msgs::NovatelXYZPtr>& positions)
303  {
304  positions.clear();
305  positions.insert(positions.end(), novatel_xyz_positions_.begin(), novatel_xyz_positions_.end());
306  novatel_xyz_positions_.clear();
307  }
308 
309  void NovatelGps::GetNovatelUtmPositions(std::vector<novatel_gps_msgs::NovatelUtmPositionPtr>& utm_positions)
310  {
311  utm_positions.clear();
312  utm_positions.insert(utm_positions.end(), novatel_utm_positions_.begin(), novatel_utm_positions_.end());
313  novatel_utm_positions_.clear();
314  }
315 
316  void NovatelGps::GetNovatelVelocities(std::vector<novatel_gps_msgs::NovatelVelocityPtr>& velocities)
317  {
318  velocities.resize(novatel_velocities_.size());
319  std::copy(novatel_velocities_.begin(), novatel_velocities_.end(), velocities.begin());
320  novatel_velocities_.clear();
321  }
322 
323  void NovatelGps::GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages)
324  {
325  // Clear out the fix_messages list before filling it
326  fix_messages.clear();
327 
328  while (!bestpos_sync_buffer_.empty())
329  {
330  auto& bestpos = bestpos_sync_buffer_.front();
331 
332  bool synced = false;
333 
334  auto gpsFix = boost::make_shared<gps_common::GPSFix>();
335 
336  // Speed & Track are filled in from BESTVEL logs, if available
337  while (!bestvel_sync_buffer_.empty())
338  {
339  auto& bestvel = bestvel_sync_buffer_.front();
340 
341  // TODO pjr handle wrapping around week boundary?
342  double time_diff = std::fabs(bestvel->novatel_msg_header.gps_seconds -
343  bestpos->novatel_msg_header.gps_seconds);
344  if (time_diff < gpsfix_sync_tol_)
345  {
346  // Within tolerance, messages synced
347  gpsFix->track = bestvel->track_ground;
348  gpsFix->speed = std::sqrt(std::pow(bestvel->horizontal_speed, 2) + std::pow(bestvel->vertical_speed, 2));
349  synced = true;
350  break;
351  }
352  else if (bestvel->novatel_msg_header.gps_seconds < bestpos->novatel_msg_header.gps_seconds)
353  {
354  // Bestvel timestamp is too old, throw it away and try again
355  bestvel_sync_buffer_.pop_front();
356  }
357  else
358  {
359  // Latest bestvel message is too new, do nothing for now
360  break;
361  }
362  }
363 
364  if (!synced && wait_for_sync_)
365  {
366  // TODO Handle this properly if bestvel is disabled
367  // If we have a bestpos and are configured to wait for a sync, we need
368  // to wait until a bestvel arrives.
369 
370  break;
371  }
372 
373  gpsFix->header.stamp = ros::Time::now();
374  gpsFix->altitude = bestpos->height;
375  gpsFix->latitude = bestpos->lat;
376  gpsFix->longitude = bestpos->lon;
377 
378  if (bestpos->solution_status == "SOL_COMPUTED")
379  {
380  gpsFix->status.status = gps_common::GPSStatus::STATUS_FIX;
381  }
382  else
383  {
384  gpsFix->status.status = gps_common::GPSStatus::STATUS_NO_FIX;
385  }
386 
387  gpsFix->time = bestpos->novatel_msg_header.gps_seconds;
388 
389  gpsFix->status.header.stamp = gpsFix->header.stamp;
390  gpsFix->status.satellites_visible = bestpos->num_satellites_tracked;
391  gpsFix->status.satellites_used = bestpos->num_satellites_used_in_solution;
392 
393  double sigma_x = bestpos->lon_sigma;
394  double sigma_x_squared = sigma_x * sigma_x;
395  gpsFix->position_covariance[0] = sigma_x_squared;
396 
397  double sigma_y = bestpos->lat_sigma;
398  double sigma_y_squared = sigma_y * sigma_y;
399  gpsFix->position_covariance[4] = sigma_y_squared;
400 
401  double sigma_z = bestpos->height_sigma;
402  gpsFix->position_covariance[8] = sigma_z * sigma_z;
403 
404  // See https://www.novatel.com/assets/Documents/Bulletins/apn029.pdf for info about errors
405  // 2D error is 2*DRMS, or 95% probability
406  gpsFix->err_horz = 2.0 * std::sqrt(sigma_x_squared + sigma_y_squared);
407 
408  // 3D error is 90% spherical accuracy standard
409  gpsFix->err = 0.833 * (sigma_x + sigma_y + sigma_z);
410 
411  // Vertical error is 2*sigma for 95% probability
412  gpsFix->err_vert = 2.0 * sigma_z;
413 
414  gpsFix->position_covariance_type =
415  gps_common::GPSFix::COVARIANCE_TYPE_DIAGONAL_KNOWN;
416 
417  // DOPs are filled in from the PSRDOP2 log, if available
418  if (latest_psrdop2_)
419  {
420  gpsFix->gdop = latest_psrdop2_->gdop;
421  gpsFix->pdop = latest_psrdop2_->pdop;
422  gpsFix->hdop = latest_psrdop2_->hdop;
423  gpsFix->vdop = latest_psrdop2_->vdop;
424  if (!latest_psrdop2_->systems.empty())
425  {
426  // The PSRDOP2 log can have multiple TDOPs, but the GPSFix message
427  // only has one... so just use the first one.
428  gpsFix->tdop = latest_psrdop2_->systems.front().tdop;
429  }
430  }
431 
432  // TODO Fill in orientation from INSATT on SPAN systems
433 
434  fix_messages.push_back(gpsFix);
435  bestpos_sync_buffer_.pop_front();
436  }
437  }
438 
439  void NovatelGps::GetNovatelHeading2Messages(std::vector<novatel_gps_msgs::NovatelHeading2Ptr>& headings) {
440  headings.clear();
441  headings.insert(headings.end(), heading2_msgs_.begin(), heading2_msgs_.end());
442  heading2_msgs_.clear();
443  }
444 
445  void NovatelGps::GetNovatelDualAntennaHeadingMessages(std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr>& headings) {
446  headings.clear();
447  headings.insert(headings.end(), dual_antenna_heading_msgs_.begin(), dual_antenna_heading_msgs_.end());
449  }
450 
451  void NovatelGps::GetNovatelCorrectedImuData(std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr>& imu_messages)
452  {
453  imu_messages.clear();
454  imu_messages.insert(imu_messages.end(), corrimudata_msgs_.begin(), corrimudata_msgs_.end());
455  corrimudata_msgs_.clear();
456  }
457 
458  void NovatelGps::GetNovatelPsrdop2Messages(std::vector<novatel_gps_msgs::NovatelPsrdop2Ptr>& psrdop2_messages)
459  {
460  psrdop2_messages.clear();
461  psrdop2_messages.insert(psrdop2_messages.end(), psrdop2_msgs_.begin(), psrdop2_msgs_.end());
462  psrdop2_msgs_.clear();
463  }
464 
465  void NovatelGps::GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages)
466  {
467  gpgga_messages.clear();
468  gpgga_messages.insert(gpgga_messages.end(), gpgga_msgs_.begin(), gpgga_msgs_.end());
469  gpgga_msgs_.clear();
470  }
471 
472  void NovatelGps::GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages)
473  {
474  gpgsa_messages.resize(gpgsa_msgs_.size());
475  std::copy(gpgsa_msgs_.begin(), gpgsa_msgs_.end(), gpgsa_messages.begin());
476  gpgsa_msgs_.clear();
477  }
478 
479  void NovatelGps::GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages)
480  {
481  gpgsv_messages.resize(gpgsv_msgs_.size());
482  std::copy(gpgsv_msgs_.begin(), gpgsv_msgs_.end(), gpgsv_messages.begin());
483  gpgsv_msgs_.clear();
484  }
485 
486  void NovatelGps::GetGphdtMessages(std::vector<novatel_gps_msgs::GphdtPtr>& gphdt_messages)
487  {
488  gphdt_messages.resize(gphdt_msgs_.size());
489  std::copy(gphdt_msgs_.begin(), gphdt_msgs_.end(), gphdt_messages.begin());
490  gphdt_msgs_.clear();
491  }
492 
493  void NovatelGps::GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages)
494  {
495  gprmc_messages.clear();
496  gprmc_messages.insert(gprmc_messages.end(), gprmc_msgs_.begin(), gprmc_msgs_.end());
497  gprmc_msgs_.clear();
498  }
499 
500  void NovatelGps::GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages)
501  {
502  inscov_messages.clear();
503  inscov_messages.insert(inscov_messages.end(), inscov_msgs_.begin(), inscov_msgs_.end());
504  inscov_msgs_.clear();
505  }
506 
507  void NovatelGps::GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages)
508  {
509  inspva_messages.clear();
510  inspva_messages.insert(inspva_messages.end(), inspva_msgs_.begin(), inspva_msgs_.end());
511  inspva_msgs_.clear();
512  }
513 
514  void NovatelGps::GetInspvaxMessages(std::vector<novatel_gps_msgs::InspvaxPtr>& inspvax_messages)
515  {
516  inspvax_messages.clear();
517  inspvax_messages.insert(inspvax_messages.end(), inspvax_msgs_.begin(), inspvax_msgs_.end());
518  inspvax_msgs_.clear();
519  }
520 
521  void NovatelGps::GetInsstdevMessages(std::vector<novatel_gps_msgs::InsstdevPtr>& insstdev_messages)
522  {
523  insstdev_messages.clear();
524  insstdev_messages.insert(insstdev_messages.end(), insstdev_msgs_.begin(), insstdev_msgs_.end());
525  insstdev_msgs_.clear();
526  }
527 
528  void NovatelGps::GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages)
529  {
530  range_messages.resize(range_msgs_.size());
531  std::copy(range_msgs_.begin(), range_msgs_.end(), range_messages.begin());
532  range_msgs_.clear();
533  }
534 
535  void NovatelGps::GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages)
536  {
537  time_messages.resize(time_msgs_.size());
538  std::copy(time_msgs_.begin(), time_msgs_.end(), time_messages.begin());
539  time_msgs_.clear();
540  }
541 
542  void NovatelGps::GetTrackstatMessages(std::vector<novatel_gps_msgs::TrackstatPtr>& trackstat_msgs)
543  {
544  trackstat_msgs.resize(trackstat_msgs_.size());
545  std::copy(trackstat_msgs_.begin(), trackstat_msgs_.end(), trackstat_msgs.begin());
546  trackstat_msgs_.clear();
547  }
548 
549  void NovatelGps::GetClockSteeringMessages(std::vector<novatel_gps_msgs::ClockSteeringPtr>& clocksteering_msgs)
550  {
551  clocksteering_msgs.resize(clocksteering_msgs_.size());
552  std::copy(clocksteering_msgs_.begin(), clocksteering_msgs_.end(), clocksteering_msgs.begin());
553  clocksteering_msgs_.clear();
554  }
555 
556  bool NovatelGps::CreatePcapConnection(const std::string& device, NovatelMessageOpts const& opts)
557  {
558  ROS_INFO("Opening pcap file: %s", device.c_str());
559 
560  if ((pcap_ = pcap_open_offline(device.c_str(), pcap_errbuf_)) == nullptr)
561  {
562  ROS_FATAL("Unable to open pcap file.");
563  return false;
564  }
565 
566  pcap_compile(pcap_, &pcap_packet_filter_, "tcp dst port 3001", 1, PCAP_NETMASK_UNKNOWN);
567  is_connected_ = true;
568 
569  return true;
570  }
571 
572  bool NovatelGps::CreateSerialConnection(const std::string& device, NovatelMessageOpts const& opts)
573  {
575  config.baud = serial_baud_;
577  config.flow_control = false;
578  config.data_bits = 8;
579  config.stop_bits = 1;
580  config.low_latency_mode = false;
581  config.writable = true; // Assume that we can write to this port
582 
583  bool success = serial_.Open(device, config);
584 
585  if (success)
586  {
587  is_connected_ = true;
588  if (!Configure(opts))
589  {
590  // We will not kill the connection here, because the device may already
591  // be setup to communicate correctly, but we will print a warning
592  ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
593  "device may not be functioning as expected; however, the "
594  "driver may still function correctly if the port has already "
595  "been pre-configured.");
596  }
597  }
598  else
599  {
601  }
602 
603  return success;
604  }
605 
606  bool NovatelGps::CreateIpConnection(const std::string& endpoint, NovatelMessageOpts const& opts)
607  {
608  std::string ip;
609  std::string port;
610  uint16_t num_port;
611  size_t sep_pos = endpoint.find(':');
612  if (sep_pos == std::string::npos || sep_pos == endpoint.size() - 1)
613  {
614  ROS_INFO("Using default port.");
615  std::stringstream ss;
616  if (connection_ == TCP)
617  {
618  num_port = DEFAULT_TCP_PORT;
619  }
620  else
621  {
622  num_port = DEFAULT_UDP_PORT;
623  }
624  ss << num_port;
625  port = ss.str();
626  }
627  else
628  {
629  port = endpoint.substr(sep_pos + 1);
630  }
631 
632  if (sep_pos != 0)
633  {
634  ip = endpoint.substr(0, sep_pos);
635  }
636 
637  try
638  {
639  if (!ip.empty())
640  {
641  if (connection_ == TCP)
642  {
643  boost::asio::ip::tcp::resolver resolver(io_service_);
644  boost::asio::ip::tcp::resolver::query query(ip, port);
645  boost::asio::ip::tcp::resolver::iterator iter = resolver.resolve(query);
646 
647  boost::asio::connect(tcp_socket_, iter);
648  ROS_INFO("Connecting via TCP to %s:%s", ip.c_str(), port.c_str());
649  }
650  else
651  {
652  boost::asio::ip::udp::resolver resolver(io_service_);
653  boost::asio::ip::udp::resolver::query query(ip, port);
654  udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>(*resolver.resolve(query));
655  udp_socket_.reset(new boost::asio::ip::udp::socket(io_service_));
656  udp_socket_->open(boost::asio::ip::udp::v4());
657  ROS_INFO("Connecting via UDP to %s:%s", ip.c_str(), port.c_str());
658  }
659  }
660  else
661  {
662  auto port_num = static_cast<uint16_t>(strtoll(port.c_str(), nullptr, 10));
663  if (connection_ == TCP)
664  {
665  boost::asio::ip::tcp::acceptor acceptor(io_service_,
666  boost::asio::ip::tcp::endpoint(
667  boost::asio::ip::tcp::v4(), port_num));
668  ROS_INFO("Listening on TCP port %s", port.c_str());
669  acceptor.accept(tcp_socket_);
670  ROS_INFO("Accepted TCP connection from client: %s",
671  tcp_socket_.remote_endpoint().address().to_string().c_str());
672  }
673  else
674  {
675  udp_socket_.reset(new boost::asio::ip::udp::socket(
676  io_service_,
677  boost::asio::ip::udp::endpoint(boost::asio::ip::udp::v4(),
678  port_num)));
679  boost::array<char, 1> recv_buf;
680  udp_endpoint_ = boost::make_shared<boost::asio::ip::udp::endpoint>();
681  boost::system::error_code error;
682 
683  ROS_INFO("Listening on UDP port %s", port.c_str());
684  udp_socket_->receive_from(boost::asio::buffer(recv_buf), *udp_endpoint_, 0, error);
685  if (error && error != boost::asio::error::message_size)
686  {
687  throw boost::system::system_error(error);
688  }
689 
690  ROS_INFO("Accepted UDP connection from client: %s",
691  udp_endpoint_->address().to_string().c_str());
692  }
693  }
694  }
695  catch (std::exception& e)
696  {
697  error_msg_ = e.what();
698  ROS_ERROR("Unable to connect: %s", e.what());
699  return false;
700  }
701 
702  is_connected_ = true;
703 
704  if (Configure(opts))
705  {
706  ROS_INFO("Configured GPS.");
707  }
708  else
709  {
710  // We will not kill the connection here, because the device may already
711  // be setup to communicate correctly, but we will print a warning
712  ROS_ERROR("Failed to configure GPS. This port may be read only, or the "
713  "device may not be functioning as expected; however, the "
714  "driver may still function correctly if the port has already "
715  "been pre-configured.");
716  }
717 
718  return true;
719  }
720 
722  {
723  if (connection_ == SERIAL)
724  {
726  serial_.ReadBytes(data_buffer_, 0, 1000);
727 
729  {
731  return READ_ERROR;
732  }
733  else if (result == swri_serial_util::SerialPort::TIMEOUT)
734  {
735  error_msg_ = "Timed out waiting for serial device.";
736  return READ_TIMEOUT;
737  }
739  {
740  error_msg_ = "Interrupted during read from serial device.";
741  return READ_INTERRUPTED;
742  }
743 
744  return READ_SUCCESS;
745  }
746  else if (connection_ == TCP || connection_ == UDP)
747  {
748  try
749  {
750  boost::system::error_code error;
751  size_t len;
752 
753  if (connection_ == TCP)
754  {
755  len = tcp_socket_.read_some(boost::asio::buffer(socket_buffer_), error);
756  }
757  else
758  {
759  boost::asio::ip::udp::endpoint remote_endpoint;
760  len = udp_socket_->receive_from(boost::asio::buffer(socket_buffer_), remote_endpoint);
761  }
762  data_buffer_.insert(data_buffer_.end(), socket_buffer_.begin(), socket_buffer_.begin()+len);
763  if (error)
764  {
765  error_msg_ = error.message();
766  Disconnect();
767  return READ_ERROR;
768  }
769  return READ_SUCCESS;
770  }
771  catch (std::exception& e)
772  {
773  ROS_WARN("TCP connection error: %s", e.what());
774  }
775  }
776  else if (connection_ == PCAP)
777  {
778  struct pcap_pkthdr* header;
779  const u_char *pkt_data;
780 
781  int result;
782  result = pcap_next_ex(pcap_, &header, &pkt_data);
783  if (result >= 0)
784  {
785  auto iph = reinterpret_cast<const iphdr*>(pkt_data + sizeof(struct ethhdr));
786  uint32_t iphdrlen = iph->ihl * 4u;
787 
788  switch (iph->protocol)
789  {
790  case 6: // TCP
791  {
792  if (header->len == 54)
793  {
794  // Empty packet, skip it.
795  return READ_SUCCESS;
796  }
797 
798  // It's possible to get multiple subsequent TCP packets with the same seq
799  // but latter ones have more data than previous ones. In case that happens,
800  // we need to only process the one with the most data. We do that by
801  // storing the most recently received message in a buffer, replacing it if
802  // we get a new one with the same seq but more data, and only sending it to
803  // the parser when we get a new packet with a different seq.
804  // Note that when we copy data into last_tcp_packet_, we omit the ethernet
805  // header because we don't care about it; we still need the IP and TCP
806  // headers. After we move it from last_tcp_packet_ into data_buffer, we
807  // can skip the IP header and the TCP data offset.
808  bool store_packet = true;
809  if (!last_tcp_packet_.empty())
810  {
811  auto tcph = reinterpret_cast<const tcphdr*>(pkt_data + iphdrlen + sizeof(struct ethhdr));
812  auto last_iph = reinterpret_cast<const iphdr*>(&(last_tcp_packet_[0]));
813  uint32_t last_iphdrlen = last_iph->ihl * 4u;
814  auto last_tcph = reinterpret_cast<const tcphdr*>(&(last_tcp_packet_[0]) + last_iphdrlen);
815  uint16_t last_len = ntohs(static_cast<uint16_t>(last_iph->tot_len));
816  uint16_t new_len = ntohs(static_cast<uint16_t>(iph->tot_len));
817  uint32_t last_seq = ntohl(last_tcph->seq);
818  uint32_t new_seq = ntohl(tcph->seq);
819 
820  if (new_seq != last_seq)
821  {
822  // If we got a packet that has a different seq than our previous one, send
823  // the previous one and store the new one.
824  uint32_t data_offset = last_tcph->doff * 4;
825  data_buffer_.insert(data_buffer_.end(),
826  last_tcp_packet_.begin() + last_iphdrlen + data_offset,
827  last_tcp_packet_.end());
828  }
829  else if (new_len <= last_len)
830  {
831  // If we got a packet with the same seq as the previous one but it doesn't
832  // have more data, do nothing.
833  store_packet = false;
834  }
835  }
836 
837  if (store_packet)
838  {
839  // If we get here, we either just sent the previous packet, or we got
840  // a new packet with the same seq but more data. In either case,
841  // store it.
842  last_tcp_packet_.clear();
843  last_tcp_packet_.insert(last_tcp_packet_.end(),
844  pkt_data + sizeof(struct ethhdr),
845  pkt_data + header->len);
846  }
847 
848  break;
849  }
850  case 17: // UDP
851  {
852  uint16_t frag_off = ntohs(static_cast<uint16_t>(iph->frag_off));
853  uint16_t fragment_offset = frag_off & static_cast<uint16_t>(0x1FFF);
854  size_t header_size;
855  // UDP packets may be fragmented; this isn't really "correct", but for
856  // simplicity's sake we'll assume we get fragments in the right order.
857  if (fragment_offset == 0)
858  {
859  header_size = sizeof(struct ethhdr) + iphdrlen + sizeof(struct udphdr);
860  }
861  else
862  {
863  header_size = sizeof(struct ethhdr) + iphdrlen;
864  }
865 
866  data_buffer_.insert(data_buffer_.end(), pkt_data + header_size, pkt_data + header->len);
867 
868  break;
869  }
870  default:
871  ROS_WARN("Unexpected protocol: %u", iph->protocol);
872  return READ_ERROR;
873  }
874 
875  // Add a slight delay after reading packets; if the node is being tested offline
876  // and this loop is hammering the TCP, logs won't output properly.
877  ros::Duration(0.001).sleep();
878 
879  return READ_SUCCESS;
880  }
881  else if (result == -2)
882  {
883  ROS_INFO("Done reading pcap file.");
884  if (!last_tcp_packet_.empty())
885  {
886  // Don't forget to submit the last packet if we still have one!
887  auto last_iph = reinterpret_cast<const iphdr*>(&(last_tcp_packet_[0]));
888  uint32_t iphdrlen = last_iph->ihl * 4u;
889  auto last_tcph = reinterpret_cast<const tcphdr*>(&(last_tcp_packet_[0]) + iphdrlen);
890  uint32_t data_offset = last_tcph->doff * 4u;
891  data_buffer_.insert(data_buffer_.end(),
892  last_tcp_packet_.begin() + iphdrlen + data_offset,
893  last_tcp_packet_.end());
894  last_tcp_packet_.clear();
895  }
896  Disconnect();
897  return READ_SUCCESS;
898  }
899  else
900  {
901  ROS_WARN("Error reading pcap data: %s", pcap_geterr(pcap_));
902  return READ_ERROR;
903  }
904  }
905 
906  error_msg_ = "Unsupported connection type.";
907 
908  return READ_ERROR;
909  }
910 
911  void NovatelGps::GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages)
912  {
913  imu_messages.clear();
914  imu_messages.insert(imu_messages.end(), imu_msgs_.begin(), imu_msgs_.end());
915  imu_msgs_.clear();
916  }
917 
919  {
920  if (imu_rate_ <= 0.0)
921  {
922  ROS_WARN_ONCE("IMU rate has not been configured; cannot produce sensor_msgs/Imu messages.");
923  return;
924  }
925 
927  {
928  // If we haven't received an INSSTDEV or an INSCOV message, don't do anything, just return.
929  ROS_WARN_THROTTLE(1.0, "No INSSTDEV or INSCOV data yet; orientation covariance will be unavailable.");
930  }
931 
932  size_t previous_size = imu_msgs_.size();
933  // Only do anything if we have both CORRIMUDATA and INSPVA messages.
934  while (!corrimudata_queue_.empty() && !inspva_queue_.empty())
935  {
936  novatel_gps_msgs::NovatelCorrectedImuDataPtr corrimudata = corrimudata_queue_.front();
937  novatel_gps_msgs::InspvaPtr inspva = inspva_queue_.front();
938 
939  double corrimudata_time = corrimudata->gps_week_num * SECONDS_PER_WEEK + corrimudata->gps_seconds;
940  double inspva_time = inspva->novatel_msg_header.gps_week_num *
941  SECONDS_PER_WEEK + inspva->novatel_msg_header.gps_seconds;
942 
943  if (std::fabs(corrimudata_time - inspva_time) > IMU_TOLERANCE_S)
944  {
945  // If the two messages are too far apart to sync, discard the oldest one.
946  ROS_DEBUG("INSPVA and CORRIMUDATA were unacceptably far apart.");
947  if (corrimudata_time < inspva_time)
948  {
949  ROS_DEBUG("Discarding oldest CORRIMUDATA.");
950  corrimudata_queue_.pop();
951  continue;
952  }
953  else
954  {
955  ROS_DEBUG("Discarding oldest INSPVA.");
956  inspva_queue_.pop();
957  continue;
958  }
959  }
960  // If we've successfully matched up two messages, remove them from their queues.
961  inspva_queue_.pop();
962  corrimudata_queue_.pop();
963 
964  // Now we can combine them together to make an Imu message.
965  sensor_msgs::ImuPtr imu = boost::make_shared<sensor_msgs::Imu>();
966 
967  imu->header.stamp = corrimudata->header.stamp;
968  imu->orientation = tf::createQuaternionMsgFromRollPitchYaw(inspva->roll * DEGREES_TO_RADIANS,
969  -(inspva->pitch) * DEGREES_TO_RADIANS,
970  -(inspva->azimuth) * DEGREES_TO_RADIANS);
971 
972  if (latest_inscov_)
973  {
974  imu->orientation_covariance = latest_inscov_->attitude_covariance;
975  }
976  else if (latest_insstdev_)
977  {
978  imu->orientation_covariance[0] = std::pow(2, latest_insstdev_->pitch_dev);
979  imu->orientation_covariance[4] = std::pow(2, latest_insstdev_->roll_dev);
980  imu->orientation_covariance[8] = std::pow(2, latest_insstdev_->azimuth_dev);
981  }
982  else
983  {
984  imu->orientation_covariance[0] =
985  imu->orientation_covariance[4] =
986  imu->orientation_covariance[8] = 1e-3;
987  }
988 
989  imu->angular_velocity.x = corrimudata->pitch_rate * imu_rate_;
990  imu->angular_velocity.y = corrimudata->roll_rate * imu_rate_;
991  imu->angular_velocity.z = corrimudata->yaw_rate * imu_rate_;
992  imu->angular_velocity_covariance[0] =
993  imu->angular_velocity_covariance[4] =
994  imu->angular_velocity_covariance[8] = 1e-3;
995 
996  imu->linear_acceleration.x = corrimudata->lateral_acceleration * imu_rate_;
997  imu->linear_acceleration.y = corrimudata->longitudinal_acceleration * imu_rate_;
998  imu->linear_acceleration.z = corrimudata->vertical_acceleration * imu_rate_;
999  imu->linear_acceleration_covariance[0] =
1000  imu->linear_acceleration_covariance[4] =
1001  imu->linear_acceleration_covariance[8] = 1e-3;
1002 
1003  imu_msgs_.push_back(imu);
1004  }
1005 
1006  size_t new_size = imu_msgs_.size() - previous_size;
1007  ROS_DEBUG("Created %lu new sensor_msgs/Imu messages.", new_size);
1008  }
1009 
1010  void NovatelGps::SetImuRate(double imu_rate, bool imu_rate_forced)
1011  {
1012  ROS_INFO("IMU sample rate: %f", imu_rate);
1013  imu_rate_ = imu_rate;
1014  if (imu_rate_forced)
1015  {
1016  imu_rate_forced_ = true;
1017  }
1018  }
1019 
1020  void NovatelGps::SetSerialBaud(int32_t serial_baud)
1021  {
1022  ROS_INFO("Serial baud rate : %d", serial_baud);
1023  serial_baud_ = serial_baud;
1024  }
1025 
1027  const ros::Time& stamp) noexcept(false)
1028  {
1029  switch (msg.header_.message_id_)
1030  {
1032  {
1033  novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseBinary(msg);
1034  position->header.stamp = stamp;
1035  novatel_positions_.push_back(position);
1036  bestpos_sync_buffer_.push_back(position);
1037  break;
1038  }
1040  {
1041  novatel_gps_msgs::NovatelXYZPtr xyz_position = bestxyz_parser_.ParseBinary(msg);
1042  xyz_position->header.stamp = stamp;
1043  novatel_xyz_positions_.push_back(xyz_position);
1044  break;
1045  }
1047  {
1048  novatel_gps_msgs::NovatelUtmPositionPtr utm_position = bestutm_parser_.ParseBinary(msg);
1049  utm_position->header.stamp = stamp;
1050  novatel_utm_positions_.push_back(utm_position);
1051  break;
1052  }
1054  {
1055  novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseBinary(msg);
1056  velocity->header.stamp = stamp;
1057  novatel_velocities_.push_back(velocity);
1058  bestvel_sync_buffer_.push_back(velocity);
1059  break;
1060  }
1062  {
1063  novatel_gps_msgs::NovatelHeading2Ptr heading = heading2_parser_.ParseBinary(msg);
1064  heading->header.stamp = stamp;
1065  heading2_msgs_.push_back(heading);
1066  break;
1067  }
1069  {
1070  novatel_gps_msgs::NovatelDualAntennaHeadingPtr heading = dual_antenna_heading_parser_.ParseBinary(msg);
1071  heading->header.stamp = stamp;
1072  dual_antenna_heading_msgs_.push_back(heading);
1073  break;
1074  }
1076  {
1077  novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseBinary(msg);
1078  imu->header.stamp = stamp;
1079  corrimudata_msgs_.push_back(imu);
1080  corrimudata_queue_.push(imu);
1081  if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
1082  {
1083  ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
1084  corrimudata_queue_.pop();
1085  }
1087  break;
1088  }
1090  {
1091  novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseBinary(msg);
1092  inscov->header.stamp = stamp;
1093  inscov_msgs_.push_back(inscov);
1094  latest_inscov_ = inscov;
1095  break;
1096  }
1098  {
1099  novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseBinary(msg);
1100  inspva->header.stamp = stamp;
1101  inspva_msgs_.push_back(inspva);
1102  inspva_queue_.push(inspva);
1103  if (inspva_queue_.size() > MAX_BUFFER_SIZE)
1104  {
1105  ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
1106  inspva_queue_.pop();
1107  }
1109  break;
1110  }
1112  {
1113  novatel_gps_msgs::InspvaxPtr inspvax = inspvax_parser_.ParseBinary(msg);
1114  inspvax->header.stamp = stamp;
1115  inspvax_msgs_.push_back(inspvax);
1116  break;
1117  }
1119  {
1120  novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseBinary(msg);
1121  insstdev->header.stamp = stamp;
1122  insstdev_msgs_.push_back(insstdev);
1123  latest_insstdev_ = insstdev;
1124  break;
1125  }
1127  {
1128  auto psrdop2 = psrdop2_parser_.ParseBinary(msg);
1129  psrdop2->header.stamp = stamp;
1130  psrdop2_msgs_.push_back(psrdop2);
1131  latest_psrdop2_ = psrdop2;
1132  break;
1133  }
1135  {
1136  novatel_gps_msgs::RangePtr range = range_parser_.ParseBinary(msg);
1137  range->header.stamp = stamp;
1138  range_msgs_.push_back(range);
1139  break;
1140  }
1142  {
1143  novatel_gps_msgs::TimePtr time = time_parser_.ParseBinary(msg);
1144  utc_offset_ = time->utc_offset;
1145  ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
1146  time->header.stamp = stamp;
1147  time_msgs_.push_back(time);
1148  break;
1149  }
1151  {
1152  novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseBinary(msg);
1153  trackstat->header.stamp = stamp;
1154  trackstat_msgs_.push_back(trackstat);
1155  break;
1156  }
1157  default:
1158  ROS_WARN("Unexpected binary message id: %u", msg.header_.message_id_);
1159  break;
1160  }
1161 
1162  return READ_SUCCESS;
1163  }
1164 
1166  const ros::Time& stamp,
1167  double most_recent_utc_time) noexcept(false)
1168  {
1169  if (sentence.id == GpggaParser::MESSAGE_NAME)
1170  {
1171  novatel_gps_msgs::GpggaPtr gpgga = gpgga_parser_.ParseAscii(sentence);
1172 
1173  auto gpgga_time = UtcFloatToSeconds(gpgga->utc_seconds);
1174 
1175  if (most_recent_utc_time < gpgga_time)
1176  {
1177  most_recent_utc_time = gpgga_time;
1178  }
1179 
1180  gpgga->header.stamp = stamp - ros::Duration(most_recent_utc_time - gpgga_time);
1181 
1182  gpgga_msgs_.push_back(std::move(gpgga));
1183  }
1184  else if (sentence.id == GprmcParser::MESSAGE_NAME)
1185  {
1186  novatel_gps_msgs::GprmcPtr gprmc = gprmc_parser_.ParseAscii(sentence);
1187 
1188  auto gprmc_time = UtcFloatToSeconds(gprmc->utc_seconds);
1189 
1190  if (most_recent_utc_time < gprmc_time)
1191  {
1192  most_recent_utc_time = gprmc_time;
1193  }
1194 
1195  gprmc->header.stamp = stamp - ros::Duration(most_recent_utc_time - gprmc_time);
1196 
1197  gprmc_msgs_.push_back(std::move(gprmc));
1198  }
1199  else if (sentence.id == GpgsaParser::MESSAGE_NAME)
1200  {
1201  novatel_gps_msgs::GpgsaPtr gpgsa = gpgsa_parser_.ParseAscii(sentence);
1202  gpgsa_msgs_.push_back(gpgsa);
1203  }
1204  else if (sentence.id == GpgsvParser::MESSAGE_NAME)
1205  {
1206  novatel_gps_msgs::GpgsvPtr gpgsv = gpgsv_parser_.ParseAscii(sentence);
1207  gpgsv_msgs_.push_back(gpgsv);
1208  }
1209  else if (sentence.id == GphdtParser::MESSAGE_NAME)
1210  {
1211  novatel_gps_msgs::GphdtPtr gphdt = gphdt_parser_.ParseAscii(sentence);
1212  gphdt_msgs_.push_back(gphdt);
1213  }
1214  else
1215  {
1216  ROS_DEBUG_STREAM("Unrecognized NMEA sentence " << sentence.id);
1217  }
1218 
1219  return READ_SUCCESS;
1220  }
1221 
1223  const ros::Time& stamp) noexcept(false)
1224  {
1225  if (sentence.id == "BESTPOSA")
1226  {
1227  novatel_gps_msgs::NovatelPositionPtr position = bestpos_parser_.ParseAscii(sentence);
1228  position->header.stamp = stamp;
1229  novatel_positions_.push_back(position);
1230  bestpos_sync_buffer_.push_back(position);
1231  }
1232  else if (sentence.id == "BESTXYZA")
1233  {
1234  novatel_gps_msgs::NovatelXYZPtr position = bestxyz_parser_.ParseAscii(sentence);
1235  position->header.stamp = stamp;
1236  novatel_xyz_positions_.push_back(position);
1237  }
1238  else if (sentence.id == "BESTUTMA")
1239  {
1240  novatel_gps_msgs::NovatelUtmPositionPtr utm_position = bestutm_parser_.ParseAscii(sentence);
1241  utm_position->header.stamp = stamp;
1242  novatel_utm_positions_.push_back(utm_position);
1243  }
1244  else if (sentence.id == "BESTVELA")
1245  {
1246  novatel_gps_msgs::NovatelVelocityPtr velocity = bestvel_parser_.ParseAscii(sentence);
1247  velocity->header.stamp = stamp;
1248  novatel_velocities_.push_back(velocity);
1249  bestvel_sync_buffer_.push_back(velocity);
1250  }
1251  else if (sentence.id == "HEADING2A")
1252  {
1253  novatel_gps_msgs::NovatelHeading2Ptr heading = heading2_parser_.ParseAscii(sentence);
1254  heading->header.stamp = stamp;
1255  heading2_msgs_.push_back(heading);
1256  }
1257  else if (sentence.id == "DUALANTENNAHEADINGA")
1258  {
1259  novatel_gps_msgs::NovatelDualAntennaHeadingPtr heading = dual_antenna_heading_parser_.ParseAscii(sentence);
1260  heading->header.stamp = stamp;
1261  dual_antenna_heading_msgs_.push_back(heading);
1262  }
1263  else if (sentence.id == "CORRIMUDATAA")
1264  {
1265  novatel_gps_msgs::NovatelCorrectedImuDataPtr imu = corrimudata_parser_.ParseAscii(sentence);
1266  imu->header.stamp = stamp;
1267  corrimudata_msgs_.push_back(imu);
1268  corrimudata_queue_.push(imu);
1269  if (corrimudata_queue_.size() > MAX_BUFFER_SIZE)
1270  {
1271  ROS_WARN_THROTTLE(1.0, "CORRIMUDATA queue overflow.");
1272  corrimudata_queue_.pop();
1273  }
1275  }
1276  else if (sentence.id == "INSCOVA")
1277  {
1278  novatel_gps_msgs::InscovPtr inscov = inscov_parser_.ParseAscii(sentence);
1279  inscov->header.stamp = stamp;
1280  inscov_msgs_.push_back(inscov);
1281  latest_inscov_ = inscov;
1282  }
1283  else if (sentence.id == "INSPVAA")
1284  {
1285  novatel_gps_msgs::InspvaPtr inspva = inspva_parser_.ParseAscii(sentence);
1286  inspva->header.stamp = stamp;
1287  inspva_msgs_.push_back(inspva);
1288  inspva_queue_.push(inspva);
1289  if (inspva_queue_.size() > MAX_BUFFER_SIZE)
1290  {
1291  ROS_WARN_THROTTLE(1.0, "INSPVA queue overflow.");
1292  inspva_queue_.pop();
1293  }
1295  }
1296  else if (sentence.id == "INSPVAXA")
1297  {
1298  novatel_gps_msgs::InspvaxPtr inspvax = inspvax_parser_.ParseAscii(sentence);
1299  inspvax->header.stamp = stamp;
1300  inspvax_msgs_.push_back(inspvax);
1301  }
1302  else if (sentence.id == "INSSTDEVA")
1303  {
1304  novatel_gps_msgs::InsstdevPtr insstdev = insstdev_parser_.ParseAscii(sentence);
1305  insstdev->header.stamp = stamp;
1306  insstdev_msgs_.push_back(insstdev);
1307  latest_insstdev_ = insstdev;
1308  }
1309  else if (sentence.id == "PSRDOP2A")
1310  {
1311  auto psrdop2 = psrdop2_parser_.ParseAscii(sentence);
1312  psrdop2->header.stamp = stamp;
1313  psrdop2_msgs_.push_back(psrdop2);
1314  latest_psrdop2_ = psrdop2;
1315  }
1316  else if (sentence.id == "TIMEA")
1317  {
1318  novatel_gps_msgs::TimePtr time = time_parser_.ParseAscii(sentence);
1319  utc_offset_ = time->utc_offset;
1320  ROS_DEBUG("Got a new TIME with offset %f. UTC offset is %f", time->utc_offset, utc_offset_);
1321  time->header.stamp = stamp;
1322  time_msgs_.push_back(time);
1323  }
1324  else if (sentence.id == "RANGEA")
1325  {
1326  novatel_gps_msgs::RangePtr range = range_parser_.ParseAscii(sentence);
1327  range->header.stamp = stamp;
1328  range_msgs_.push_back(range);
1329  }
1330  else if (sentence.id == "TRACKSTATA")
1331  {
1332  novatel_gps_msgs::TrackstatPtr trackstat = trackstat_parser_.ParseAscii(sentence);
1333  trackstat->header.stamp = stamp;
1334  trackstat_msgs_.push_back(trackstat);
1335  }
1336  else if (sentence.id == "RAWIMUXA")
1337  {
1338  static std::map<std::string, std::pair<double, std::string>> rates = {
1339  { "0", std::pair<double, std::string>(100, "Unknown") },
1340  { "1", std::pair<double, std::string>(100, "Honeywell HG1700 AG11") },
1341  { "4", std::pair<double, std::string>(100, "Honeywell HG1700 AG17") },
1342  { "5", std::pair<double, std::string>(100, "Honeywell HG1700 CA29") },
1343  { "8", std::pair<double, std::string>(200, "Litton LN-200 (200hz model)") },
1344  { "11", std::pair<double, std::string>(100, "Honeywell HG1700 AG58") },
1345  { "12", std::pair<double, std::string>(100, "Honeywell HG1700 AG62") },
1346  { "13", std::pair<double, std::string>(200, "iMAR ilMU-FSAS") },
1347  { "16", std::pair<double, std::string>(200, "KVH 1750 IMU") },
1348  { "19", std::pair<double, std::string>(200, "Northrop Grumman Litef LCI-1") },
1349  { "20", std::pair<double, std::string>(100, "Honeywell HG1930 AA99") },
1350  { "26", std::pair<double, std::string>(100, "Northrop Grumman Litef ISA-100C") },
1351  { "27", std::pair<double, std::string>(100, "Honeywell HG1900 CA50") },
1352  { "28", std::pair<double, std::string>(100, "Honeywell HG1930 CA50") },
1353  { "31", std::pair<double, std::string>(200, "Analog Devices ADIS16488") },
1354  { "32", std::pair<double, std::string>(125, "Sensonor STIM300") },
1355  { "33", std::pair<double, std::string>(200, "KVH1750 IMU") },
1356  { "34", std::pair<double, std::string>(200, "Northrop Grumman Litef ISA-100") },
1357  { "38", std::pair<double, std::string>(400, "Northrop Grumman Litef ISA-100 400Hz") },
1358  { "39", std::pair<double, std::string>(400, "Northrop Grumman Litef ISA-100C 400Hz") },
1359  { "41", std::pair<double, std::string>(125, "Epson G320N") },
1360  { "45", std::pair<double, std::string>(200, "KVH 1725 IMU?") }, //(This was a guess based on the 1750
1361  // as the actual rate is not documented and the specs are similar)
1362  { "52", std::pair<double, std::string>(200, "Litef microIMU") },
1363  { "56", std::pair<double, std::string>(125, "Sensonor STIM300, Direct Connection") },
1364  { "58", std::pair<double, std::string>(200, "Honeywell HG4930 AN01") },
1365  { "61", std::pair<double, std::string>(100, "Epson G370N") },
1366  };
1367 
1368  // Parse out the IMU type then save it, we don't care about the rest (3rd field)
1369  std::string id = sentence.body.size() > 1 ? sentence.body[1] : "";
1370  if (rates.find(id) != rates.end())
1371  {
1372  double rate = rates[id].first;
1373 
1374  ROS_INFO("IMU Type %s Found, Rate: %f Hz", rates[id].second.c_str(), (float)rate);
1375 
1376  // Set the rate only if it hasn't been forced already
1377  if (!imu_rate_forced_)
1378  {
1379  SetImuRate(rate, false); // Dont force set from here so it can be configured elsewhere
1380  }
1381  }
1382  else
1383  {
1384  // Error because the imu type was unknown
1385  ROS_ERROR("Unknown IMU Type Received: %s", id.c_str());
1386  }
1387  }
1388  else if (sentence.id == "CLOCKSTEERINGA")
1389  {
1390  novatel_gps_msgs::ClockSteeringPtr clocksteering = clocksteering_parser_.ParseAscii(sentence);
1391  clocksteering_msgs_.push_back(clocksteering);
1392  }
1393 
1394  return READ_SUCCESS;
1395  }
1396 
1397  bool NovatelGps::Write(const std::string& command)
1398  {
1399  std::vector<uint8_t> bytes(command.begin(), command.end());
1400 
1401  if (connection_ == SERIAL)
1402  {
1403  int32_t written = serial_.Write(bytes);
1404  if (written != (int32_t)command.length())
1405  {
1406  ROS_ERROR("Failed to send command: %s", command.c_str());
1407  }
1408  return written == (int32_t)command.length();
1409  }
1410  else if (connection_ == TCP || connection_ == UDP)
1411  {
1412  boost::system::error_code error;
1413  try
1414  {
1415  size_t written;
1416  if (connection_ == TCP)
1417  {
1418  written = boost::asio::write(tcp_socket_, boost::asio::buffer(bytes), error);
1419  }
1420  else
1421  {
1422  written = udp_socket_->send_to(boost::asio::buffer(bytes), *udp_endpoint_, 0, error);
1423  }
1424  if (error)
1425  {
1426  ROS_ERROR("Error writing TCP data: %s", error.message().c_str());
1427  Disconnect();
1428  }
1429  ROS_DEBUG("Wrote %lu bytes.", written);
1430  return written == (int32_t) command.length();
1431  }
1432  catch (std::exception& e)
1433  {
1434  Disconnect();
1435  ROS_ERROR("Exception writing TCP data: %s", e.what());
1436  }
1437  }
1438  else if (connection_ == PCAP)
1439  {
1440  ROS_WARN_ONCE("Writing data is unsupported in pcap mode.");
1441  return true;
1442  }
1443 
1444  return false;
1445  }
1446 
1448  {
1449  bool configured = true;
1450  configured = configured && Write("unlogall THISPORT_ALL\r\n");
1451 
1453  {
1454  configured = configured && Write("vehiclebodyrotation 0 0 90\r\n");
1455  configured = configured && Write("applyvehiclebodyrotation\r\n");
1456  }
1457 
1458  for(const auto& option : opts)
1459  {
1460  std::stringstream command;
1461  command << std::setprecision(3);
1462  if (option.first.find("heading2") != std::string::npos)
1463  {
1464  command << "log " << option.first << " onnew " << "\r\n";
1465  }
1466  else if (option.second < 0.0)
1467  {
1468  command << "log " << option.first << " onchanged\r\n";
1469  }
1470  else
1471  {
1472  command << "log " << option.first << " ontime " << option.second << "\r\n";
1473  }
1474  configured = configured && Write(command.str());
1475  }
1476 
1477  // Log the IMU data once to get the IMU type
1478  configured = configured && Write("log rawimuxa\r\n");
1479 
1480  return configured;
1481  }
1482 }
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...
novatel_gps_msgs::InspvaPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: inspva.cpp:47
msg
novatel_gps_msgs::InscovPtr latest_inscov_
Definition: novatel_gps.h:531
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...
novatel_gps_msgs::InspvaxPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: inspvax.cpp:110
boost::array< uint8_t, 10000 > socket_buffer_
Fixed-size buffer for reading directly from sockets.
Definition: novatel_gps.h:465
novatel_gps_msgs::InscovPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: inscov.cpp:79
DualAntennaHeadingParser dual_antenna_heading_parser_
Definition: novatel_gps.h:482
#define ROS_FATAL(...)
boost::circular_buffer< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_msgs_
Definition: novatel_gps.h:501
boost::circular_buffer< novatel_gps_msgs::GprmcPtr > gprmc_msgs_
Definition: novatel_gps.h:506
TrackstatParser trackstat_parser_
Definition: novatel_gps.h:497
novatel_gps_msgs::NovatelHeading2Ptr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: heading2.cpp:50
novatel_gps_msgs::InsstdevPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: insstdev.cpp:47
boost::shared_ptr< boost::asio::ip::udp::socket > udp_socket_
Definition: novatel_gps.h:455
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...
#define ROS_WARN_THROTTLE(rate,...)
static const std::string MESSAGE_NAME
Definition: gpgga.h:52
CorrImuDataParser corrimudata_parser_
Definition: novatel_gps.h:484
novatel_gps_msgs::NovatelPositionPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: bestpos.cpp:110
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.
novatel_gps_msgs::NovatelVelocityPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: bestvel.cpp:85
static constexpr double IMU_TOLERANCE_S
Definition: novatel_gps.h:436
novatel_gps_msgs::NovatelXYZPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: bestxyz.cpp:137
static constexpr uint16_t MESSAGE_ID
Definition: heading2.h:51
bool CreateIpConnection(const std::string &endpoint, NovatelMessageOpts const &opts)
Establishes an IP connection with a NovAtel device.
static constexpr uint32_t SECONDS_PER_WEEK
Definition: novatel_gps.h:435
static const std::string MESSAGE_NAME
Definition: gpgsv.h:47
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...
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...
swri_serial_util::SerialPort serial_
Definition: novatel_gps.h:450
std::vector< uint8_t > data_buffer_
Definition: novatel_gps.h:461
bool sleep() const
static constexpr uint16_t MESSAGE_ID
Definition: trackstat.h:49
novatel_gps_msgs::GpgsvPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: gpgsv.cpp:45
novatel_gps_msgs::TimePtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: time.cpp:111
static constexpr uint16_t MESSAGE_ID
Definition: corrimudata.h:49
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...
pcap_t * pcap_
pcap device for testing
Definition: novatel_gps.h:468
novatel_gps_msgs::NovatelPsrdop2Ptr ParseAscii(const NovatelSentence &sentence) override
Converts sentence into a ROS message pointer and returns it.
Definition: psrdop2.cpp:70
static constexpr uint32_t MESSAGE_ID
Definition: insstdev.h:49
static constexpr uint16_t DEFAULT_UDP_PORT
Definition: novatel_gps.h:432
novatel_gps_msgs::NovatelUtmPositionPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: bestutm.cpp:112
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...
novatel_gps_msgs::NovatelVelocityPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: bestvel.cpp:47
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.
boost::circular_buffer< novatel_gps_msgs::ClockSteeringPtr > clocksteering_msgs_
Definition: novatel_gps.h:500
double GetMostRecentUtcTime(const std::vector< NmeaSentence > &sentences)
Iterates through the provided messages to find the first GPGGA or GPRMC message with a valid UTC time...
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > novatel_positions_
Definition: novatel_gps.h:512
#define ROS_WARN(...)
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
Definition: novatel_gps.h:504
novatel_gps_msgs::RangePtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: range.cpp:87
NovatelMessageExtractor extractor_
Used to extract messages from the incoming data stream.
Definition: novatel_gps.h:474
static ConnectionType ParseConnection(const std::string &connection)
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
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.
boost::circular_buffer< novatel_gps_msgs::GpgsaPtr > gpgsa_msgs_
Definition: novatel_gps.h:503
boost::shared_ptr< boost::asio::ip::udp::endpoint > udp_endpoint_
Definition: novatel_gps.h:456
bool Open(const std::string &device, SerialConfig config=SerialConfig())
novatel_gps_msgs::InsstdevPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: insstdev.cpp:76
novatel_gps_msgs::GprmcPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: gprmc.cpp:46
static constexpr uint16_t MESSAGE_ID
Definition: bestxyz.h:51
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...
static const std::string MESSAGE_NAME
Definition: gphdt.h:18
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.
boost::circular_buffer< novatel_gps_msgs::InscovPtr > inscov_msgs_
Definition: novatel_gps.h:508
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > bestpos_sync_buffer_
Definition: novatel_gps.h:516
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...
bool Configure(NovatelMessageOpts const &opts)
(Re)configure the driver with a set of message options
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)
novatel_gps_msgs::NovatelPositionPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: bestpos.cpp:50
NovatelGps::ReadResult ParseBinaryMessage(const BinaryMessage &msg, const ros::Time &stamp) noexcept(false)
Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appro...
#define ROS_WARN_ONCE(...)
#define ROS_INFO(...)
static constexpr uint32_t MESSAGE_ID
Definition: inscov.h:49
novatel_gps_msgs::InsstdevPtr latest_insstdev_
Definition: novatel_gps.h:530
novatel_gps_msgs::NovatelPsrdop2Ptr latest_psrdop2_
Definition: novatel_gps.h:525
static constexpr size_t MAX_BUFFER_SIZE
Definition: novatel_gps.h:433
bool CreatePcapConnection(const std::string &device, NovatelMessageOpts const &opts)
Creates a pcap device for playing back recorded data.
boost::asio::ip::tcp::socket tcp_socket_
Definition: novatel_gps.h:454
novatel_gps_msgs::TrackstatPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: trackstat.cpp:46
void GetNovatelDualAntennaHeadingMessages(std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
Provides any DUALANTENNAHEADING messages that have been received since the last time this was called...
boost::circular_buffer< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > dual_antenna_heading_msgs_
Definition: novatel_gps.h:519
static constexpr double DEGREES_TO_RADIANS
Definition: novatel_gps.h:437
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.
boost::circular_buffer< novatel_gps_msgs::GphdtPtr > gphdt_msgs_
Definition: novatel_gps.h:505
std::queue< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_queue_
Definition: novatel_gps.h:528
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.
int32_t Write(const std::vector< uint8_t > &input)
novatel_gps_msgs::GphdtPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: gphdt.cpp:17
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
Definition: novatel_gps.h:507
NovatelGps::ReadResult ParseNovatelSentence(const NovatelSentence &sentence, const ros::Time &stamp) noexcept(false)
Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the app...
novatel_gps_msgs::TimePtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: time.cpp:45
novatel_gps_msgs::NovatelUtmPositionPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: bestutm.cpp:50
#define ROS_DEBUG_STREAM(args)
novatel_gps_msgs::NovatelPsrdop2Ptr ParseBinary(const BinaryMessage &bin_msg) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: psrdop2.cpp:30
void GetNovatelHeading2Messages(std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
Provides any HEADING2 messages that have been received since the last time this was called...
novatel_gps_msgs::ClockSteeringPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
void GenerateImuMessages()
Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them...
Result ReadBytes(std::vector< uint8_t > &output, size_t max_bytes, int32_t timeout)
novatel_gps_msgs::GpgsaPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: gpgsa.cpp:45
static const std::string MESSAGE_NAME
Definition: gprmc.h:53
boost::circular_buffer< novatel_gps_msgs::NovatelHeading2Ptr > heading2_msgs_
Definition: novatel_gps.h:518
boost::circular_buffer< novatel_gps_msgs::GpggaPtr > gpgga_msgs_
Definition: novatel_gps.h:502
void GetImuMessages(std::vector< sensor_msgs::ImuPtr > &imu_messages)
Provides any Imu messages that have been generated since the last time this was called.
static constexpr uint16_t MESSAGE_ID
Definition: range.h:50
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.
novatel_gps_msgs::TrackstatPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: trackstat.cpp:191
double UtcFloatToSeconds(double utc_float)
boost::asio::io_service io_service_
Definition: novatel_gps.h:453
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
static constexpr uint32_t MESSAGE_ID
Definition: inspvax.h:49
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...
boost::circular_buffer< novatel_gps_msgs::InsstdevPtr > insstdev_msgs_
Definition: novatel_gps.h:511
boost::circular_buffer< novatel_gps_msgs::RangePtr > range_msgs_
Definition: novatel_gps.h:521
boost::circular_buffer< novatel_gps_msgs::TimePtr > time_msgs_
Definition: novatel_gps.h:522
static constexpr uint16_t MESSAGE_ID
Definition: bestutm.h:51
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: corrimudata.cpp:73
ClockSteeringParser clocksteering_parser_
Definition: novatel_gps.h:483
bool CreateSerialConnection(const std::string &device, NovatelMessageOpts const &opts)
Establishes a serial port connection with a NovAtel device.
boost::circular_buffer< novatel_gps_msgs::NovatelUtmPositionPtr > novatel_utm_positions_
Definition: novatel_gps.h:514
static constexpr uint16_t MESSAGE_ID
Definition: time.h:49
bool ExtractCompleteMessages(const std::string &input, std::vector< NmeaSentence > &nmea_sentences, std::vector< NovatelSentence > &novatel_sentences, std::vector< BinaryMessage > &binary_messages, std::string &remaining, bool keep_nmea_container=false)
Extracts messages from a buffer of NovAtel data.
static const std::string MESSAGE_NAME
Definition: gpgsa.h:47
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll, double pitch, double yaw)
static constexpr uint16_t MESSAGE_ID
Definition: psrdop2.h:52
static Time now()
novatel_gps_msgs::NovatelCorrectedImuDataPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: corrimudata.cpp:47
std::string nmea_buffer_
Buffer containing incomplete data from message parsing.
Definition: novatel_gps.h:463
ReadResult ReadData()
Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.
novatel_gps_msgs::InscovPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: inscov.cpp:47
static constexpr uint16_t DEFAULT_TCP_PORT
Definition: novatel_gps.h:431
boost::circular_buffer< novatel_gps_msgs::TrackstatPtr > trackstat_msgs_
Definition: novatel_gps.h:523
boost::circular_buffer< novatel_gps_msgs::NovatelXYZPtr > novatel_xyz_positions_
Definition: novatel_gps.h:513
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...
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > novatel_velocities_
Definition: novatel_gps.h:515
novatel_gps_msgs::InspvaPtr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: inspva.cpp:120
std::string ErrorMsg() const
novatel_gps_msgs::NovatelXYZPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: bestxyz.cpp:50
boost::circular_buffer< novatel_gps_msgs::InspvaxPtr > inspvax_msgs_
Definition: novatel_gps.h:510
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > bestvel_sync_buffer_
Definition: novatel_gps.h:517
novatel_gps_msgs::RangePtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: range.cpp:48
bool Connect(const std::string &device, ConnectionType connection)
Definition: novatel_gps.cpp:89
boost::circular_buffer< novatel_gps_msgs::InspvaPtr > inspva_msgs_
Definition: novatel_gps.h:509
bool Write(const std::string &command)
Writes the given string of characters to a connected NovAtel device.
novatel_gps_msgs::InspvaxPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
Definition: inspvax.cpp:48
static constexpr uint32_t MESSAGE_ID
Definition: inspva.h:49
NovatelGps::ReadResult ParseNmeaSentence(const NmeaSentence &sentence, const ros::Time &stamp, double most_recent_utc_time) noexcept(false)
Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate...
#define ROS_ERROR(...)
boost::circular_buffer< novatel_gps_msgs::NovatelPsrdop2Ptr > psrdop2_msgs_
Definition: novatel_gps.h:520
std::queue< novatel_gps_msgs::InspvaPtr > inspva_queue_
Definition: novatel_gps.h:529
novatel_gps_msgs::NovatelHeading2Ptr ParseAscii(const NovatelSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: heading2.cpp:115
static constexpr uint16_t MESSAGE_ID
Definition: bestvel.h:50
static constexpr uint16_t MESSAGE_ID
Definition: bestpos.h:51
std::vector< uint8_t > last_tcp_packet_
Definition: novatel_gps.h:471
novatel_gps_msgs::NovatelDualAntennaHeadingPtr ParseBinary(const BinaryMessage &bin_msg) noexcept(false) override
Converts bin_msg into a ROS message pointer and returns it.
novatel_gps_msgs::GpggaPtr ParseAscii(const NmeaSentence &sentence) noexcept(false) override
Converts sentence into a ROS message pointer and returns it.
Definition: gpgga.cpp:47
char pcap_errbuf_[MAX_BUFFER_SIZE]
Definition: novatel_gps.h:470
#define ROS_DEBUG(...)
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