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