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/Gphdt.h>
50 #include <novatel_gps_msgs/Gprmc.h>
51 #include <novatel_gps_msgs/Inspva.h>
52 #include <novatel_gps_msgs/Inspvax.h>
53 #include <novatel_gps_msgs/Insstdev.h>
54 #include <novatel_gps_msgs/NovatelCorrectedImuData.h>
55 #include <novatel_gps_msgs/NovatelPosition.h>
56 #include <novatel_gps_msgs/NovatelXYZ.h>
57 #include <novatel_gps_msgs/NovatelUtmPosition.h>
58 #include <novatel_gps_msgs/NovatelVelocity.h>
59 #include <novatel_gps_msgs/Range.h>
60 #include <novatel_gps_msgs/Time.h>
61 #include <novatel_gps_msgs/Trackstat.h>
62 
64 
85 
86 #include <sensor_msgs/Imu.h>
88 
89 namespace novatel_gps_driver
90 {
93  typedef std::map<std::string, double> NovatelMessageOpts;
94 
95  class NovatelGps
96  {
97  public:
99 
101  {
108  };
109 
110  NovatelGps();
111  ~NovatelGps();
112 
121  bool Connect(const std::string& device, ConnectionType connection);
122 
132  bool Connect(const std::string& device, ConnectionType connection, NovatelMessageOpts const& opts);
133 
137  void Disconnect();
138 
142  std::string ErrorMsg() const { return error_msg_; }
143 
149  void GetFixMessages(std::vector<gps_common::GPSFixPtr>& fix_messages);
155  void GetGpggaMessages(std::vector<novatel_gps_msgs::GpggaPtr>& gpgga_messages);
161  void GetGpgsaMessages(std::vector<novatel_gps_msgs::GpgsaPtr>& gpgsa_messages);
167  void GetGpgsvMessages(std::vector<novatel_gps_msgs::GpgsvPtr>& gpgsv_messages);
173  void GetGphdtMessages(std::vector<novatel_gps_msgs::GphdtPtr>& gphdt_messages);
179  void GetGprmcMessages(std::vector<novatel_gps_msgs::GprmcPtr>& gprmc_messages);
185  void GetNovatelHeading2Messages(std::vector<novatel_gps_msgs::NovatelHeading2Ptr>& headings);
191  void GetNovatelDualAntennaHeadingMessages(std::vector<novatel_gps_msgs::NovatelDualAntennaHeadingPtr>& headings);
197  void GetNovatelPsrdop2Messages(std::vector<novatel_gps_msgs::NovatelPsrdop2Ptr>& psrdop2_messages);
203  void GetImuMessages(std::vector<sensor_msgs::ImuPtr>& imu_messages);
209  void GetInscovMessages(std::vector<novatel_gps_msgs::InscovPtr>& inscov_messages);
215  void GetInspvaMessages(std::vector<novatel_gps_msgs::InspvaPtr>& inspva_messages);
221  void GetInspvaxMessages(std::vector<novatel_gps_msgs::InspvaxPtr>& inspvax_messages);
227  void GetInsstdevMessages(std::vector<novatel_gps_msgs::InsstdevPtr>& insstdev_messages);
233  void GetNovatelCorrectedImuData(std::vector<novatel_gps_msgs::NovatelCorrectedImuDataPtr>& imu_messages);
239  void GetNovatelPositions(std::vector<novatel_gps_msgs::NovatelPositionPtr>& positions);
245  void GetNovatelXYZPositions(std::vector<novatel_gps_msgs::NovatelXYZPtr>& positions);
251  void GetNovatelUtmPositions(std::vector<novatel_gps_msgs::NovatelUtmPositionPtr>& utm_positions);
257  void GetNovatelVelocities(std::vector<novatel_gps_msgs::NovatelVelocityPtr>& velocities);
263  void GetRangeMessages(std::vector<novatel_gps_msgs::RangePtr>& range_messages);
269  void GetTimeMessages(std::vector<novatel_gps_msgs::TimePtr>& time_messages);
275  void GetTrackstatMessages(std::vector<novatel_gps_msgs::TrackstatPtr>& trackstat_msgs);
281  void GetClockSteeringMessages(std::vector<novatel_gps_msgs::ClockSteeringPtr>& clocksteering_msgs);
282 
286  bool IsConnected() { return is_connected_; }
287 
293  static ConnectionType ParseConnection(const std::string& connection);
294 
300  void ApplyVehicleBodyRotation(const bool& apply_rotation);
301 
309 
315  void SetImuRate(double imu_rate, bool force = true);
316 
321  void SetSerialBaud(int32_t serial_baud);
322 
328  bool Write(const std::string& command);
329 
330  double gpsfix_sync_tol_; //seconds
331  bool wait_for_sync_; // wait until a bestvel has arrived before publishing bestpos
332 
333  private:
341  bool Configure(NovatelMessageOpts const& opts);
342 
362  bool CreateIpConnection(const std::string& endpoint, NovatelMessageOpts const& opts);
363 
376  bool CreateSerialConnection(const std::string& device, NovatelMessageOpts const& opts);
377 
385  bool CreatePcapConnection(const std::string& device, NovatelMessageOpts const& opts);
386 
391  void GenerateImuMessages();
392 
401  const ros::Time& stamp) noexcept(false);
412  const ros::Time& stamp,
413  double most_recent_utc_time) noexcept(false);
422  const ros::Time& stamp) noexcept(false);
423 
430 
431  static constexpr uint16_t DEFAULT_TCP_PORT = 3001;
432  static constexpr uint16_t DEFAULT_UDP_PORT = 3002;
433  static constexpr size_t MAX_BUFFER_SIZE = 100;
434  static constexpr size_t SYNC_BUFFER_SIZE = 10;
435  static constexpr uint32_t SECONDS_PER_WEEK = 604800;
436  static constexpr double IMU_TOLERANCE_S = 0.0002;
437  static constexpr double DEGREES_TO_RADIANS = M_PI / 180.0;
438 
440 
441  std::string error_msg_;
442 
445 
446  double utc_offset_;
447 
448  // Serial connection
449  int32_t serial_baud_;
451 
452  // TCP / UDP connections
453  boost::asio::io_service io_service_;
454  boost::asio::ip::tcp::socket tcp_socket_;
457 
458  // Data buffers
461  std::vector<uint8_t> data_buffer_;
463  std::string nmea_buffer_;
465  boost::array<uint8_t, 10000> socket_buffer_;
466 
468  pcap_t* pcap_;
469  bpf_program pcap_packet_filter_;
471  std::vector<uint8_t> last_tcp_packet_;
472 
475 
476  // Message parsers
498 
499  // Message buffers
500  boost::circular_buffer<novatel_gps_msgs::ClockSteeringPtr> clocksteering_msgs_;
501  boost::circular_buffer<novatel_gps_msgs::NovatelCorrectedImuDataPtr> corrimudata_msgs_;
502  boost::circular_buffer<novatel_gps_msgs::GpggaPtr> gpgga_msgs_;
503  boost::circular_buffer<novatel_gps_msgs::GpgsaPtr> gpgsa_msgs_;
504  boost::circular_buffer<novatel_gps_msgs::GpgsvPtr> gpgsv_msgs_;
505  boost::circular_buffer<novatel_gps_msgs::GphdtPtr> gphdt_msgs_;
506  boost::circular_buffer<novatel_gps_msgs::GprmcPtr> gprmc_msgs_;
507  boost::circular_buffer<sensor_msgs::ImuPtr> imu_msgs_;
508  boost::circular_buffer<novatel_gps_msgs::InscovPtr> inscov_msgs_;
509  boost::circular_buffer<novatel_gps_msgs::InspvaPtr> inspva_msgs_;
510  boost::circular_buffer<novatel_gps_msgs::InspvaxPtr> inspvax_msgs_;
511  boost::circular_buffer<novatel_gps_msgs::InsstdevPtr> insstdev_msgs_;
512  boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> novatel_positions_;
513  boost::circular_buffer<novatel_gps_msgs::NovatelXYZPtr> novatel_xyz_positions_;
514  boost::circular_buffer<novatel_gps_msgs::NovatelUtmPositionPtr> novatel_utm_positions_;
515  boost::circular_buffer<novatel_gps_msgs::NovatelVelocityPtr> novatel_velocities_;
516  boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> bestpos_sync_buffer_;
517  boost::circular_buffer<novatel_gps_msgs::NovatelVelocityPtr> bestvel_sync_buffer_;
518  boost::circular_buffer<novatel_gps_msgs::NovatelHeading2Ptr> heading2_msgs_;
519  boost::circular_buffer<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> dual_antenna_heading_msgs_;
520  boost::circular_buffer<novatel_gps_msgs::NovatelPsrdop2Ptr> psrdop2_msgs_;
521  boost::circular_buffer<novatel_gps_msgs::RangePtr> range_msgs_;
522  boost::circular_buffer<novatel_gps_msgs::TimePtr> time_msgs_;
523  boost::circular_buffer<novatel_gps_msgs::TrackstatPtr> trackstat_msgs_;
524 
525  novatel_gps_msgs::NovatelPsrdop2Ptr latest_psrdop2_;
526 
527  // IMU data synchronization queues
528  std::queue<novatel_gps_msgs::NovatelCorrectedImuDataPtr> corrimudata_queue_;
529  std::queue<novatel_gps_msgs::InspvaPtr> inspva_queue_;
530  novatel_gps_msgs::InsstdevPtr latest_insstdev_;
531  novatel_gps_msgs::InscovPtr latest_inscov_;
532  double imu_rate_;
533 
534  // Additional Options
536  };
537 }
538 
539 #endif // NOVATEL_OEM628_NOVATEL_GPS_H_
clocksteering.h
insstdev.h
novatel_gps_driver::NovatelGps::GetInspvaxMessages
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.
Definition: novatel_gps.cpp:514
novatel_gps_driver::NovatelGps::PCAP
@ PCAP
Definition: novatel_gps.h:98
novatel_gps_driver::NovatelGps::time_parser_
TimeParser time_parser_
Definition: novatel_gps.h:496
novatel_gps_driver::NovatelGps::GetClockSteeringMessages
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.
Definition: novatel_gps.cpp:549
novatel_gps_driver::DualAntennaHeadingParser
Definition: dual_antenna_heading.h:40
novatel_gps_driver::NovatelGps::novatel_velocities_
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > novatel_velocities_
Definition: novatel_gps.h:515
novatel_gps_driver::NovatelGps::READ_TIMEOUT
@ READ_TIMEOUT
Definition: novatel_gps.h:104
novatel_gps_driver::NovatelGps::nmea_buffer_
std::string nmea_buffer_
Buffer containing incomplete data from message parsing.
Definition: novatel_gps.h:463
novatel_gps_driver::NovatelGps::socket_buffer_
boost::array< uint8_t, 10000 > socket_buffer_
Fixed-size buffer for reading directly from sockets.
Definition: novatel_gps.h:465
novatel_gps_driver::NovatelGps::GetInscovMessages
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.
Definition: novatel_gps.cpp:500
novatel_gps_driver::NovatelGps::apply_vehicle_body_rotation_
bool apply_vehicle_body_rotation_
Definition: novatel_gps.h:535
novatel_gps_driver::NovatelGps::gpsfix_sync_tol_
double gpsfix_sync_tol_
Definition: novatel_gps.h:330
novatel_gps_driver::NovatelGps::Connect
bool Connect(const std::string &device, ConnectionType connection)
Definition: novatel_gps.cpp:89
boost::shared_ptr< boost::asio::ip::udp::socket >
novatel_gps_driver::NovatelGps::TCP
@ TCP
Definition: novatel_gps.h:98
novatel_gps_driver::NovatelGps::gpgsv_msgs_
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
Definition: novatel_gps.h:504
novatel_gps_driver::NovatelGps::trackstat_parser_
TrackstatParser trackstat_parser_
Definition: novatel_gps.h:497
novatel_gps_driver::NovatelGps::utc_offset_
double utc_offset_
Definition: novatel_gps.h:446
novatel_gps_driver::NovatelGps::GetNovatelPositions
void GetNovatelPositions(std::vector< novatel_gps_msgs::NovatelPositionPtr > &positions)
Provides any BESTPOS messages that have been received since the last time this was called.
Definition: novatel_gps.cpp:295
novatel_gps_driver::ClockSteeringParser
Definition: clocksteering.h:38
novatel_gps_driver::NovatelGps::corrimudata_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_msgs_
Definition: novatel_gps.h:501
novatel_gps_driver::NovatelGps::ParseConnection
static ConnectionType ParseConnection(const std::string &connection)
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
Definition: novatel_gps.cpp:130
novatel_gps_driver::NovatelGps::wait_for_sync_
bool wait_for_sync_
Definition: novatel_gps.h:331
novatel_gps_driver::NovatelGps::SetSerialBaud
void SetSerialBaud(int32_t serial_baud)
Sets the serial baud rate; should be called before configuring a serial connection.
Definition: novatel_gps.cpp:1020
novatel_gps_driver::NovatelGps::gprmc_parser_
GprmcParser gprmc_parser_
Definition: novatel_gps.h:489
novatel_gps_driver::NovatelGps::inscov_msgs_
boost::circular_buffer< novatel_gps_msgs::InscovPtr > inscov_msgs_
Definition: novatel_gps.h:508
novatel_gps_driver::NovatelSentence
Definition: novatel_sentence.h:42
novatel_gps_driver::NovatelGps::clocksteering_msgs_
boost::circular_buffer< novatel_gps_msgs::ClockSteeringPtr > clocksteering_msgs_
Definition: novatel_gps.h:500
novatel_gps_driver::NovatelGps::inspva_queue_
std::queue< novatel_gps_msgs::InspvaPtr > inspva_queue_
Definition: novatel_gps.h:529
novatel_gps_driver::NovatelGps::serial_
swri_serial_util::SerialPort serial_
Definition: novatel_gps.h:450
novatel_gps_driver::NovatelGps::inspva_parser_
InspvaParser inspva_parser_
Definition: novatel_gps.h:491
novatel_gps_driver::NovatelGps::GetRangeMessages
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.
Definition: novatel_gps.cpp:528
novatel_gps_driver::NovatelGps::latest_inscov_
novatel_gps_msgs::InscovPtr latest_inscov_
Definition: novatel_gps.h:531
novatel_gps_driver::NovatelGps::GetNovatelXYZPositions
void GetNovatelXYZPositions(std::vector< novatel_gps_msgs::NovatelXYZPtr > &positions)
Provides any BESTXYZ messages that have been received since the last time this was called.
Definition: novatel_gps.cpp:302
novatel_gps_driver::GpgsvParser
Definition: gpgsv.h:38
novatel_gps_driver::NovatelGps::GetNovatelUtmPositions
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.
Definition: novatel_gps.cpp:309
novatel_gps_driver::NovatelGps::Configure
bool Configure(NovatelMessageOpts const &opts)
(Re)configure the driver with a set of message options
Definition: novatel_gps.cpp:1447
gpgsa.h
novatel_gps_driver::NovatelGps::udp_endpoint_
boost::shared_ptr< boost::asio::ip::udp::endpoint > udp_endpoint_
Definition: novatel_gps.h:456
novatel_gps_driver::NovatelGps::GetNovatelVelocities
void GetNovatelVelocities(std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
Provides any BESTVEL messages that have been received since the last time this was called.
Definition: novatel_gps.cpp:316
novatel_gps_driver::TrackstatParser
Definition: trackstat.h:38
novatel_gps_driver::NovatelGps::GetGpgsvMessages
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.
Definition: novatel_gps.cpp:479
novatel_gps_driver::NovatelGps::ErrorMsg
std::string ErrorMsg() const
Definition: novatel_gps.h:142
bestxyz.h
gprmc.h
novatel_gps_driver::NovatelGps::pcap_packet_filter_
bpf_program pcap_packet_filter_
Definition: novatel_gps.h:469
novatel_gps_driver::NovatelGps::READ_INSUFFICIENT_DATA
@ READ_INSUFFICIENT_DATA
Definition: novatel_gps.h:103
novatel_gps_driver::GpggaParser
Definition: gpgga.h:38
novatel_gps_driver::BinaryMessage
Definition: binary_message.h:42
novatel_gps_driver::NovatelGps::data_buffer_
std::vector< uint8_t > data_buffer_
Definition: novatel_gps.h:461
novatel_gps_driver::NovatelGps::extractor_
NovatelMessageExtractor extractor_
Used to extract messages from the incoming data stream.
Definition: novatel_gps.h:474
novatel_gps_driver::GphdtParser
Definition: gphdt.h:9
inspvax.h
novatel_gps_driver::NovatelGps::ConnectionType
ConnectionType
Definition: novatel_gps.h:98
novatel_gps_driver::InspvaParser
Definition: inspva.h:38
novatel_gps_driver::NovatelGps::GetNovatelPsrdop2Messages
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.
Definition: novatel_gps.cpp:458
novatel_gps_driver::NovatelGps::GetTrackstatMessages
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.
Definition: novatel_gps.cpp:542
novatel_gps_driver::NovatelGps::READ_ERROR
@ READ_ERROR
Definition: novatel_gps.h:106
novatel_gps_driver::NovatelGps::~NovatelGps
~NovatelGps()
Definition: novatel_gps.cpp:84
novatel_gps_driver::NovatelGps::gpgsa_msgs_
boost::circular_buffer< novatel_gps_msgs::GpgsaPtr > gpgsa_msgs_
Definition: novatel_gps.h:503
novatel_gps_driver::NovatelGps::READ_PARSE_FAILED
@ READ_PARSE_FAILED
Definition: novatel_gps.h:107
novatel_gps_driver::NovatelGps::insstdev_parser_
InsstdevParser insstdev_parser_
Definition: novatel_gps.h:493
bestutm.h
novatel_gps_driver::NovatelGps::GetImuMessages
void GetImuMessages(std::vector< sensor_msgs::ImuPtr > &imu_messages)
Provides any Imu messages that have been generated since the last time this was called.
Definition: novatel_gps.cpp:911
novatel_gps_driver::Psrdop2Parser
Definition: psrdop2.h:39
novatel_gps_driver::NovatelGps::imu_msgs_
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
Definition: novatel_gps.h:507
novatel_gps_driver::NovatelGps::ProcessData
ReadResult ProcessData()
Processes any data that has been received from the device since the last time this message was called...
Definition: novatel_gps.cpp:190
novatel_gps_driver::BestposParser
Definition: bestpos.h:40
novatel_gps_driver::NovatelGps::imu_rate_forced_
bool imu_rate_forced_
Definition: novatel_gps.h:444
novatel_gps_driver::NovatelGps::dual_antenna_heading_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > dual_antenna_heading_msgs_
Definition: novatel_gps.h:519
novatel_gps_driver::NovatelGps::range_parser_
RangeParser range_parser_
Definition: novatel_gps.h:495
novatel_gps_driver::NovatelGps::time_msgs_
boost::circular_buffer< novatel_gps_msgs::TimePtr > time_msgs_
Definition: novatel_gps.h:522
novatel_gps_driver::NovatelGps::bestpos_sync_buffer_
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > bestpos_sync_buffer_
Definition: novatel_gps.h:516
novatel_gps_driver::BestutmParser
Definition: bestutm.h:40
novatel_gps_driver::GprmcParser
Definition: gprmc.h:38
novatel_gps_driver::NovatelGps::gphdt_msgs_
boost::circular_buffer< novatel_gps_msgs::GphdtPtr > gphdt_msgs_
Definition: novatel_gps.h:505
novatel_message_extractor.h
heading2.h
novatel_gps_driver::NovatelGps::bestutm_parser_
BestutmParser bestutm_parser_
Definition: novatel_gps.h:479
psrdop2.h
novatel_gps_driver::NovatelGps::bestxyz_parser_
BestxyzParser bestxyz_parser_
Definition: novatel_gps.h:478
time.h
novatel_gps_driver::GpgsaParser
Definition: gpgsa.h:38
novatel_gps_driver::NovatelGps::heading2_parser_
Heading2Parser heading2_parser_
Definition: novatel_gps.h:481
novatel_gps_driver::NovatelGps::corrimudata_queue_
std::queue< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_queue_
Definition: novatel_gps.h:528
novatel_gps_driver::RangeParser
Definition: range.h:38
novatel_gps_driver::NovatelGps::tcp_socket_
boost::asio::ip::tcp::socket tcp_socket_
Definition: novatel_gps.h:454
novatel_gps_driver::NovatelGps::UDP
@ UDP
Definition: novatel_gps.h:98
novatel_gps_driver::NovatelGps::ParseBinaryMessage
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...
Definition: novatel_gps.cpp:1026
novatel_gps_driver::NovatelGps::ApplyVehicleBodyRotation
void ApplyVehicleBodyRotation(const bool &apply_rotation)
Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN...
Definition: novatel_gps.cpp:185
corrimudata.h
novatel_gps_driver::NovatelGps::bestpos_parser_
BestposParser bestpos_parser_
Definition: novatel_gps.h:477
novatel_gps_driver::NovatelGps::CreatePcapConnection
bool CreatePcapConnection(const std::string &device, NovatelMessageOpts const &opts)
Creates a pcap device for playing back recorded data.
Definition: novatel_gps.cpp:556
novatel_gps_driver::InscovParser
Definition: inscov.h:38
novatel_gps_driver::NovatelGps::range_msgs_
boost::circular_buffer< novatel_gps_msgs::RangePtr > range_msgs_
Definition: novatel_gps.h:521
novatel_gps_driver::NovatelGps::inscov_parser_
InscovParser inscov_parser_
Definition: novatel_gps.h:490
novatel_gps_driver::NovatelGps::novatel_positions_
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > novatel_positions_
Definition: novatel_gps.h:512
trackstat.h
novatel_gps_driver::NovatelGps::INVALID
@ INVALID
Definition: novatel_gps.h:98
novatel_gps_driver::NovatelGps::bestvel_parser_
BestvelParser bestvel_parser_
Definition: novatel_gps.h:480
novatel_gps_driver::NovatelGps::GetNovatelCorrectedImuData
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.
Definition: novatel_gps.cpp:451
novatel_gps_driver::NovatelGps::GetGphdtMessages
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.
Definition: novatel_gps.cpp:486
novatel_gps_driver::NovatelGps::GetTimeMessages
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.
Definition: novatel_gps.cpp:535
range.h
novatel_gps_driver::NovatelMessageOpts
std::map< std::string, double > NovatelMessageOpts
Definition: novatel_gps.h:93
serial_port.h
inspva.h
novatel_gps_driver::NovatelGps::ParseNovatelSentence
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...
Definition: novatel_gps.cpp:1222
novatel_gps_driver::InspvaxParser
Definition: inspvax.h:38
novatel_gps_driver
Definition: binary_header.h:37
novatel_gps_driver::NovatelGps::latest_psrdop2_
novatel_gps_msgs::NovatelPsrdop2Ptr latest_psrdop2_
Definition: novatel_gps.h:525
novatel_gps_driver::BestxyzParser
Definition: bestxyz.h:40
novatel_gps_driver::NovatelGps::READ_INTERRUPTED
@ READ_INTERRUPTED
Definition: novatel_gps.h:105
novatel_gps_driver::NovatelGps::latest_insstdev_
novatel_gps_msgs::InsstdevPtr latest_insstdev_
Definition: novatel_gps.h:530
gpgsv.h
novatel_gps_driver::NovatelGps::novatel_xyz_positions_
boost::circular_buffer< novatel_gps_msgs::NovatelXYZPtr > novatel_xyz_positions_
Definition: novatel_gps.h:513
novatel_gps_driver::NovatelGps::GenerateImuMessages
void GenerateImuMessages()
Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them...
Definition: novatel_gps.cpp:918
novatel_gps_driver::NovatelGps::insstdev_msgs_
boost::circular_buffer< novatel_gps_msgs::InsstdevPtr > insstdev_msgs_
Definition: novatel_gps.h:511
novatel_gps_driver::NovatelGps::GetGprmcMessages
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.
Definition: novatel_gps.cpp:493
dual_antenna_heading.h
novatel_gps_driver::NovatelGps::SetImuRate
void SetImuRate(double imu_rate, bool force=true)
Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.
Definition: novatel_gps.cpp:1010
novatel_gps_driver::NovatelGps::inspvax_msgs_
boost::circular_buffer< novatel_gps_msgs::InspvaxPtr > inspvax_msgs_
Definition: novatel_gps.h:510
novatel_gps_driver::NovatelGps::gpgsv_parser_
GpgsvParser gpgsv_parser_
Definition: novatel_gps.h:487
novatel_gps_driver::NovatelGps::GetNovatelHeading2Messages
void GetNovatelHeading2Messages(std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
Provides any HEADING2 messages that have been received since the last time this was called.
Definition: novatel_gps.cpp:439
novatel_gps_driver::NovatelGps::IsConnected
bool IsConnected()
Definition: novatel_gps.h:286
novatel_gps_driver::NovatelGps::gpgga_msgs_
boost::circular_buffer< novatel_gps_msgs::GpggaPtr > gpgga_msgs_
Definition: novatel_gps.h:502
novatel_gps_driver::NovatelGps::io_service_
boost::asio::io_service io_service_
Definition: novatel_gps.h:453
novatel_gps_driver::NovatelGps::heading2_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelHeading2Ptr > heading2_msgs_
Definition: novatel_gps.h:518
inscov.h
novatel_gps_driver::NovatelGps::ReadResult
ReadResult
Definition: novatel_gps.h:100
novatel_gps_driver::NovatelGps::error_msg_
std::string error_msg_
Definition: novatel_gps.h:441
novatel_gps_driver::NovatelGps::gpgsa_parser_
GpgsaParser gpgsa_parser_
Definition: novatel_gps.h:486
ros::Time
novatel_gps_driver::NovatelGps::MAX_BUFFER_SIZE
static constexpr size_t MAX_BUFFER_SIZE
Definition: novatel_gps.h:433
novatel_gps_driver::NovatelGps::imu_rate_
double imu_rate_
Definition: novatel_gps.h:532
novatel_gps_driver::NovatelGps::GetGpggaMessages
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.
Definition: novatel_gps.cpp:465
novatel_gps_driver::NovatelGps::inspva_msgs_
boost::circular_buffer< novatel_gps_msgs::InspvaPtr > inspva_msgs_
Definition: novatel_gps.h:509
novatel_gps_driver::NovatelGps::GetInspvaMessages
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.
Definition: novatel_gps.cpp:507
novatel_gps_driver::NovatelGps::READ_SUCCESS
@ READ_SUCCESS
Definition: novatel_gps.h:102
novatel_gps_driver::NovatelGps::psrdop2_msgs_
boost::circular_buffer< novatel_gps_msgs::NovatelPsrdop2Ptr > psrdop2_msgs_
Definition: novatel_gps.h:520
novatel_gps_driver::NovatelGps::GetNovatelDualAntennaHeadingMessages
void GetNovatelDualAntennaHeadingMessages(std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
Provides any DUALANTENNAHEADING messages that have been received since the last time this was called.
Definition: novatel_gps.cpp:445
novatel_gps_driver::NovatelGps::SYNC_BUFFER_SIZE
static constexpr size_t SYNC_BUFFER_SIZE
Definition: novatel_gps.h:434
bestvel.h
novatel_gps_driver::NovatelGps::gprmc_msgs_
boost::circular_buffer< novatel_gps_msgs::GprmcPtr > gprmc_msgs_
Definition: novatel_gps.h:506
novatel_gps_driver::NovatelGps::DEGREES_TO_RADIANS
static constexpr double DEGREES_TO_RADIANS
Definition: novatel_gps.h:437
novatel_gps_driver::NovatelGps
Definition: novatel_gps.h:95
novatel_gps_driver::NovatelMessageExtractor
Definition: novatel_message_extractor.h:58
novatel_gps_driver::NovatelGps::GetInsstdevMessages
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.
Definition: novatel_gps.cpp:521
swri_serial_util::SerialPort
novatel_gps_driver::NovatelGps::gpgga_parser_
GpggaParser gpgga_parser_
Definition: novatel_gps.h:485
novatel_gps_driver::NovatelGps::DEFAULT_TCP_PORT
static constexpr uint16_t DEFAULT_TCP_PORT
Definition: novatel_gps.h:431
novatel_gps_driver::NovatelGps::udp_socket_
boost::shared_ptr< boost::asio::ip::udp::socket > udp_socket_
Definition: novatel_gps.h:455
novatel_gps_driver::NovatelGps::Disconnect
void Disconnect()
Definition: novatel_gps.cpp:152
novatel_gps_driver::NovatelGps::ReadData
ReadResult ReadData()
Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.
Definition: novatel_gps.cpp:721
novatel_gps_driver::NovatelGps::trackstat_msgs_
boost::circular_buffer< novatel_gps_msgs::TrackstatPtr > trackstat_msgs_
Definition: novatel_gps.h:523
novatel_gps_driver::InsstdevParser
Definition: insstdev.h:38
novatel_gps_driver::NovatelGps::GetFixMessages
void GetFixMessages(std::vector< gps_common::GPSFixPtr > &fix_messages)
Provides any GPSFix messages that have been generated since the last time this was called.
Definition: novatel_gps.cpp:323
novatel_gps_driver::NovatelGps::psrdop2_parser_
Psrdop2Parser psrdop2_parser_
Definition: novatel_gps.h:494
novatel_gps_driver::NovatelGps::gphdt_parser_
GphdtParser gphdt_parser_
Definition: novatel_gps.h:488
novatel_gps_driver::BestvelParser
Definition: bestvel.h:39
novatel_gps_driver::NovatelGps::connection_
ConnectionType connection_
Definition: novatel_gps.h:439
novatel_gps_driver::NovatelGps::IMU_TOLERANCE_S
static constexpr double IMU_TOLERANCE_S
Definition: novatel_gps.h:436
novatel_gps_driver::NovatelGps::CreateSerialConnection
bool CreateSerialConnection(const std::string &device, NovatelMessageOpts const &opts)
Establishes a serial port connection with a NovAtel device.
Definition: novatel_gps.cpp:572
novatel_gps_driver::NovatelGps::dual_antenna_heading_parser_
DualAntennaHeadingParser dual_antenna_heading_parser_
Definition: novatel_gps.h:482
novatel_gps_driver::NovatelGps::Write
bool Write(const std::string &command)
Writes the given string of characters to a connected NovAtel device.
Definition: novatel_gps.cpp:1397
novatel_gps_driver::NovatelGps::NovatelGps
NovatelGps()
Definition: novatel_gps.cpp:45
novatel_gps_driver::NovatelGps::serial_baud_
int32_t serial_baud_
Definition: novatel_gps.h:449
novatel_gps_driver::NovatelGps::last_tcp_packet_
std::vector< uint8_t > last_tcp_packet_
Definition: novatel_gps.h:471
novatel_gps_driver::NovatelGps::novatel_utm_positions_
boost::circular_buffer< novatel_gps_msgs::NovatelUtmPositionPtr > novatel_utm_positions_
Definition: novatel_gps.h:514
novatel_gps_driver::NmeaSentence
Definition: nmea_sentence.h:41
novatel_gps_driver::NovatelGps::is_connected_
bool is_connected_
Definition: novatel_gps.h:443
novatel_gps_driver::CorrImuDataParser
Definition: corrimudata.h:38
novatel_gps_driver::NovatelGps::CreateIpConnection
bool CreateIpConnection(const std::string &endpoint, NovatelMessageOpts const &opts)
Establishes an IP connection with a NovAtel device.
Definition: novatel_gps.cpp:606
novatel_gps_driver::NovatelGps::ParseNmeaSentence
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...
Definition: novatel_gps.cpp:1165
novatel_gps_driver::NovatelGps::bestvel_sync_buffer_
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > bestvel_sync_buffer_
Definition: novatel_gps.h:517
bestpos.h
gpgga.h
novatel_gps_driver::NovatelGps::pcap_errbuf_
char pcap_errbuf_[MAX_BUFFER_SIZE]
Definition: novatel_gps.h:470
novatel_gps_driver::Heading2Parser
Definition: heading2.h:40
novatel_gps_driver::NovatelGps::SERIAL
@ SERIAL
Definition: novatel_gps.h:98
gphdt.h
novatel_gps_driver::NovatelGps::SECONDS_PER_WEEK
static constexpr uint32_t SECONDS_PER_WEEK
Definition: novatel_gps.h:435
novatel_gps_driver::NovatelGps::GetGpgsaMessages
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.
Definition: novatel_gps.cpp:472
novatel_gps_driver::NovatelGps::pcap_
pcap_t * pcap_
pcap device for testing
Definition: novatel_gps.h:468
novatel_gps_driver::NovatelGps::inspvax_parser_
InspvaxParser inspvax_parser_
Definition: novatel_gps.h:492
novatel_gps_driver::NovatelGps::DEFAULT_UDP_PORT
static constexpr uint16_t DEFAULT_UDP_PORT
Definition: novatel_gps.h:432
novatel_gps_driver::TimeParser
Definition: time.h:37
novatel_gps_driver::NovatelGps::clocksteering_parser_
ClockSteeringParser clocksteering_parser_
Definition: novatel_gps.h:483
novatel_gps_driver::NovatelGps::corrimudata_parser_
CorrImuDataParser corrimudata_parser_
Definition: novatel_gps.h:484


novatel_gps_driver
Author(s):
autogenerated on Sun Oct 1 2023 02:58:57