novatel_gps.h
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 #ifndef NOVATEL_OEM628_NOVATEL_GPS_H_
31 #define NOVATEL_OEM628_NOVATEL_GPS_H_
32 
33 #include <map>
34 #include <queue>
35 #include <string>
36 #include <vector>
37 
38 #include <boost/asio.hpp>
39 #include <boost/circular_buffer.hpp>
40 
41 #include <pcap.h>
42 
44 
45 #include <gps_common/GPSFix.h>
46 
47 #include <novatel_gps_msgs/Gpgga.h>
48 #include <novatel_gps_msgs/Gpgsa.h>
49 #include <novatel_gps_msgs/Gprmc.h>
50 #include <novatel_gps_msgs/Inspva.h>
51 #include <novatel_gps_msgs/Insstdev.h>
52 #include <novatel_gps_msgs/NovatelCorrectedImuData.h>
53 #include <novatel_gps_msgs/NovatelPosition.h>
54 #include <novatel_gps_msgs/NovatelXYZ.h>
55 #include <novatel_gps_msgs/NovatelUtmPosition.h>
56 #include <novatel_gps_msgs/NovatelVelocity.h>
57 #include <novatel_gps_msgs/Range.h>
58 #include <novatel_gps_msgs/Time.h>
59 #include <novatel_gps_msgs/Trackstat.h>
60 
62 
80 
81 #include <sensor_msgs/Imu.h>
83 
84 namespace novatel_gps_driver
85 {
87  typedef std::map<std::string, double> NovatelMessageOpts;
88 
89  class NovatelGps
90  {
91  public:
93 
95  {
102  };
103 
104  NovatelGps();
105  ~NovatelGps();
106 
115  bool Connect(const std::string& device, ConnectionType connection);
116 
126  bool Connect(const std::string& device, ConnectionType connection, NovatelMessageOpts const& opts);
127 
131  void Disconnect();
132 
136  std::string ErrorMsg() const { return error_msg_; }
137 
143  void GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages);
149  void GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages);
155  void GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages);
161  void GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages);
167  void GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages);
173  void GetNovatelHeading2Messages(std::vector<novatel_gps_msgs::NovatelHeading2Ptr>& headings);
179  void GetNovatelDualAntennaHeadingMessages(std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr>& headings);
185  void GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages);
191  void GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages);
197  void GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages);
203  void GetInsstdevMessages(std::vector<novatel_gps_msgs::InsstdevPtr>& insstdev_messages);
209  void GetNovatelCorrectedImuData(std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr>& imu_messages);
215  void GetNovatelPositions(std::vector<novatel_gps_msgs::NovatelPositionPtr>& positions);
221  void GetNovatelXYZPositions(std::vector<novatel_gps_msgs::NovatelXYZPtr>& positions);
227  void GetNovatelUtmPositions(std::vector<novatel_gps_msgs::NovatelUtmPositionPtr>& utm_positions);
233  void GetNovatelVelocities(std::vector<novatel_gps_msgs::NovatelVelocityPtr>& velocities);
239  void GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages);
245  void GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages);
251  void GetTrackstatMessages(std::vector<novatel_gps_msgs::TrackstatPtr>& trackstat_msgs);
257  void GetClockSteeringMessages(std::vector<novatel_gps_msgs::ClockSteeringPtr>& clocksteering_msgs);
258 
262  bool IsConnected() { return is_connected_; }
263 
269  static ConnectionType ParseConnection(const std::string& connection);
270 
276  void ApplyVehicleBodyRotation(const bool& apply_rotation);
277 
285 
291  void SetImuRate(double imu_rate, bool force = true);
292 
297  void SetSerialBaud(int32_t serial_baud);
298 
304  bool Write(const std::string& command);
305 
306  //parameters
307  double gpgga_gprmc_sync_tol_; //seconds
308  double gpgga_position_sync_tol_; //seconds
309  bool wait_for_position_; //if false, do not require position message to make gps fix message
310  //added this because position message is sometimes > 1 s late.
311 
312  private:
320  bool Configure(NovatelMessageOpts const& opts);
321 
341  bool CreateIpConnection(const std::string& endpoint, NovatelMessageOpts const& opts);
342 
355  bool CreateSerialConnection(const std::string& device, NovatelMessageOpts const& opts);
356 
364  bool CreatePcapConnection(const std::string& device, NovatelMessageOpts const& opts);
365 
370  void GenerateImuMessages();
371 
380  const ros::Time& stamp) throw(ParseException);
391  const ros::Time& stamp,
392  double most_recent_utc_time) throw(ParseException);
401  const ros::Time& stamp) throw(ParseException);
402 
409 
410  static constexpr uint16_t DEFAULT_TCP_PORT = 3001;
411  static constexpr uint16_t DEFAULT_UDP_PORT = 3002;
412  static constexpr size_t MAX_BUFFER_SIZE = 100;
413  static constexpr size_t SYNC_BUFFER_SIZE = 10;
414  static constexpr uint32_t SECONDS_PER_WEEK = 604800;
415  static constexpr double IMU_TOLERANCE_S = 0.0002;
416  static constexpr double DEGREES_TO_RADIANS = M_PI / 180.0;
417 
419 
420  std::string error_msg_;
421 
424 
425  double utc_offset_;
426 
427  // Serial connection
428  int32_t serial_baud_;
430 
431  // TCP / UDP connections
432  boost::asio::io_service io_service_;
433  boost::asio::ip::tcp::socket tcp_socket_;
436 
437  // Data buffers
440  std::vector<uint8_t> data_buffer_;
442  std::string nmea_buffer_;
444  boost::array<uint8_t, 10000> socket_buffer_;
445 
447  pcap_t* pcap_;
448  bpf_program pcap_packet_filter_;
450  std::vector<uint8_t> last_tcp_packet_;
451 
454 
455  // Message parsers
474 
475  // Message buffers
476  boost::circular_buffer<novatel_gps_msgs::ClockSteeringPtr> clocksteering_msgs_;
477  boost::circular_buffer<novatel_gps_msgs::NovatelCorrectedImuDataPtr> corrimudata_msgs_;
478  boost::circular_buffer<novatel_gps_msgs::GpggaPtr> gpgga_msgs_;
479  boost::circular_buffer<novatel_gps_msgs::Gpgga> gpgga_sync_buffer_;
480  boost::circular_buffer<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs_;
481  boost::circular_buffer<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs_;
482  boost::circular_buffer<novatel_gps_msgs::GprmcPtr> gprmc_msgs_;
483  boost::circular_buffer<novatel_gps_msgs::Gprmc> gprmc_sync_buffer_;
484  boost::circular_buffer<sensor_msgs::ImuPtr> imu_msgs_;
485  boost::circular_buffer<novatel_gps_msgs::InscovPtr> inscov_msgs_;
486  boost::circular_buffer<novatel_gps_msgs::InspvaPtr> inspva_msgs_;
487  boost::circular_buffer<novatel_gps_msgs::InsstdevPtr> insstdev_msgs_;
488  boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> novatel_positions_;
489  boost::circular_buffer<novatel_gps_msgs::NovatelXYZPtr> novatel_xyz_positions_;
490  boost::circular_buffer<novatel_gps_msgs::NovatelUtmPositionPtr> novatel_utm_positions_;
491  boost::circular_buffer<novatel_gps_msgs::NovatelVelocityPtr> novatel_velocities_;
492  boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> position_sync_buffer_;
493  boost::circular_buffer<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs_;
494  boost::circular_buffer<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs_;
495  boost::circular_buffer<novatel_gps_msgs::RangePtr> range_msgs_;
496  boost::circular_buffer<novatel_gps_msgs::TimePtr> time_msgs_;
497  boost::circular_buffer<novatel_gps_msgs::TrackstatPtr> trackstat_msgs_;
498 
499  // IMU data synchronization queues
500  std::queue<novatel_gps_msgs::NovatelCorrectedImuDataPtr> corrimudata_queue_;
501  std::queue<novatel_gps_msgs::InspvaPtr> inspva_queue_;
502  novatel_gps_msgs::InsstdevPtr latest_insstdev_;
503  novatel_gps_msgs::InscovPtr latest_inscov_;
504  double imu_rate_;
505 
506  // Additional Options
508  };
509 }
510 
511 #endif // NOVATEL_OEM628_NOVATEL_GPS_H_
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::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
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...
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.
static constexpr double IMU_TOLERANCE_S
Definition: novatel_gps.h:415
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
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...
swri_serial_util::SerialPort serial_
Definition: novatel_gps.h:429
std::vector< uint8_t > data_buffer_
Definition: novatel_gps.h:440
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 uint16_t DEFAULT_UDP_PORT
Definition: novatel_gps.h:411
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
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > novatel_positions_
Definition: novatel_gps.h:488
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
Definition: novatel_gps.h:481
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.
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
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
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::InsstdevPtr latest_insstdev_
Definition: novatel_gps.h:502
static constexpr size_t MAX_BUFFER_SIZE
Definition: novatel_gps.h:412
std::string ErrorMsg() const
Definition: novatel_gps.h:136
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.
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
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...
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.
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...
boost::circular_buffer< novatel_gps_msgs::InsstdevPtr > insstdev_msgs_
Definition: novatel_gps.h:487
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
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
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_.
static constexpr size_t SYNC_BUFFER_SIZE
Definition: novatel_gps.h:413
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
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
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.
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
std::vector< uint8_t > last_tcp_packet_
Definition: novatel_gps.h:450
char pcap_errbuf_[MAX_BUFFER_SIZE]
Definition: novatel_gps.h:449
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