Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
novatel_gps_driver::NovatelGps Class Reference

#include <novatel_gps.h>

Public Types

enum  ConnectionType {
  SERIAL, TCP, UDP, PCAP,
  INVALID
}
 
enum  ReadResult {
  READ_SUCCESS = 0, READ_INSUFFICIENT_DATA = 1, READ_TIMEOUT = 2, READ_INTERRUPTED = 3,
  READ_ERROR = -1, READ_PARSE_FAILED = -2
}
 

Public Member Functions

void ApplyVehicleBodyRotation (const bool &apply_rotation)
 Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN frame to match up with the ROS coordinate frame. More...
 
bool Connect (const std::string &device, ConnectionType connection)
 
bool Connect (const std::string &device, ConnectionType connection, NovatelMessageOpts const &opts)
 
void Disconnect ()
 
std::string ErrorMsg () const
 
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. More...
 
void GetFixMessages (std::vector< gps_common::GPSFixPtr > &fix_messages)
 Provides any GPSFix messages that have been generated since the last time this was called. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
void GetImuMessages (std::vector< sensor_msgs::ImuPtr > &imu_messages)
 Provides any Imu messages that have been generated since the last time this was called. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
void GetNovatelDualAntennaHeadingMessages (std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &headings)
 Provides any DUALANTENNAHEADING messages that have been received since the last time this was called. More...
 
void GetNovatelHeading2Messages (std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &headings)
 Provides any HEADING2 messages that have been received since the last time this was called. More...
 
void GetNovatelPositions (std::vector< novatel_gps_msgs::NovatelPositionPtr > &positions)
 Provides any BESTPOS messages that have been received since the last time this was called. More...
 
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. More...
 
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. More...
 
void GetNovatelVelocities (std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
 Provides any BESTVEL messages that have been received since the last time this was called. More...
 
void GetNovatelXYZPositions (std::vector< novatel_gps_msgs::NovatelXYZPtr > &positions)
 Provides any BESTXYZ messages that have been received since the last time this was called. More...
 
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. More...
 
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. More...
 
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. More...
 
bool IsConnected ()
 
 NovatelGps ()
 
ReadResult ProcessData ()
 Processes any data that has been received from the device since the last time this message was called. May result in any number of messages being placed in the individual message buffers. More...
 
void SetImuRate (double imu_rate, bool force=true)
 Sets the IMU rate; necessary for producing sensor_msgs/Imu messages. More...
 
void SetSerialBaud (int32_t serial_baud)
 Sets the serial baud rate; should be called before configuring a serial connection. More...
 
bool Write (const std::string &command)
 Writes the given string of characters to a connected NovAtel device. More...
 
 ~NovatelGps ()
 

Static Public Member Functions

static ConnectionType ParseConnection (const std::string &connection)
 Converts the strings "udp", "tcp", or "serial" into the corresponding enum values. More...
 

Public Attributes

double gpsfix_sync_tol_
 
bool wait_for_sync_
 

Private Member Functions

bool Configure (NovatelMessageOpts const &opts)
 (Re)configure the driver with a set of message options More...
 
bool CreateIpConnection (const std::string &endpoint, NovatelMessageOpts const &opts)
 Establishes an IP connection with a NovAtel device. More...
 
bool CreatePcapConnection (const std::string &device, NovatelMessageOpts const &opts)
 Creates a pcap device for playing back recorded data. More...
 
bool CreateSerialConnection (const std::string &device, NovatelMessageOpts const &opts)
 Establishes a serial port connection with a NovAtel device. More...
 
void GenerateImuMessages ()
 Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them. More...
 
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 appropriate buffer. More...
 
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 buffer. More...
 
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 appropriate buffer. More...
 
ReadResult ReadData ()
 Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_. More...
 

Private Attributes

bool apply_vehicle_body_rotation_
 
BestposParser bestpos_parser_
 
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > bestpos_sync_buffer_
 
BestutmParser bestutm_parser_
 
BestvelParser bestvel_parser_
 
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > bestvel_sync_buffer_
 
BestxyzParser bestxyz_parser_
 
boost::circular_buffer< novatel_gps_msgs::ClockSteeringPtr > clocksteering_msgs_
 
ClockSteeringParser clocksteering_parser_
 
ConnectionType connection_
 
boost::circular_buffer< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_msgs_
 
CorrImuDataParser corrimudata_parser_
 
std::queue< novatel_gps_msgs::NovatelCorrectedImuDataPtr > corrimudata_queue_
 
std::vector< uint8_t > data_buffer_
 
boost::circular_buffer< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > dual_antenna_heading_msgs_
 
DualAntennaHeadingParser dual_antenna_heading_parser_
 
std::string error_msg_
 
NovatelMessageExtractor extractor_
 Used to extract messages from the incoming data stream. More...
 
boost::circular_buffer< novatel_gps_msgs::GpggaPtr > gpgga_msgs_
 
GpggaParser gpgga_parser_
 
boost::circular_buffer< novatel_gps_msgs::GpgsaPtr > gpgsa_msgs_
 
GpgsaParser gpgsa_parser_
 
boost::circular_buffer< novatel_gps_msgs::GpgsvPtr > gpgsv_msgs_
 
GpgsvParser gpgsv_parser_
 
boost::circular_buffer< novatel_gps_msgs::GphdtPtr > gphdt_msgs_
 
GphdtParser gphdt_parser_
 
boost::circular_buffer< novatel_gps_msgs::GprmcPtr > gprmc_msgs_
 
GprmcParser gprmc_parser_
 
boost::circular_buffer< novatel_gps_msgs::NovatelHeading2Ptr > heading2_msgs_
 
Heading2Parser heading2_parser_
 
boost::circular_buffer< sensor_msgs::ImuPtr > imu_msgs_
 
double imu_rate_
 
bool imu_rate_forced_
 
boost::circular_buffer< novatel_gps_msgs::InscovPtr > inscov_msgs_
 
InscovParser inscov_parser_
 
boost::circular_buffer< novatel_gps_msgs::InspvaPtr > inspva_msgs_
 
InspvaParser inspva_parser_
 
std::queue< novatel_gps_msgs::InspvaPtr > inspva_queue_
 
boost::circular_buffer< novatel_gps_msgs::InspvaxPtr > inspvax_msgs_
 
InspvaxParser inspvax_parser_
 
boost::circular_buffer< novatel_gps_msgs::InsstdevPtr > insstdev_msgs_
 
InsstdevParser insstdev_parser_
 
boost::asio::io_service io_service_
 
bool is_connected_
 
std::vector< uint8_t > last_tcp_packet_
 
novatel_gps_msgs::InscovPtr latest_inscov_
 
novatel_gps_msgs::InsstdevPtr latest_insstdev_
 
novatel_gps_msgs::NovatelPsrdop2Ptr latest_psrdop2_
 
std::string nmea_buffer_
 Buffer containing incomplete data from message parsing. More...
 
boost::circular_buffer< novatel_gps_msgs::NovatelPositionPtr > novatel_positions_
 
boost::circular_buffer< novatel_gps_msgs::NovatelUtmPositionPtr > novatel_utm_positions_
 
boost::circular_buffer< novatel_gps_msgs::NovatelVelocityPtr > novatel_velocities_
 
boost::circular_buffer< novatel_gps_msgs::NovatelXYZPtr > novatel_xyz_positions_
 
pcap_t * pcap_
 pcap device for testing More...
 
char pcap_errbuf_ [MAX_BUFFER_SIZE]
 
bpf_program pcap_packet_filter_
 
boost::circular_buffer< novatel_gps_msgs::NovatelPsrdop2Ptr > psrdop2_msgs_
 
Psrdop2Parser psrdop2_parser_
 
boost::circular_buffer< novatel_gps_msgs::RangePtr > range_msgs_
 
RangeParser range_parser_
 
swri_serial_util::SerialPort serial_
 
int32_t serial_baud_
 
boost::array< uint8_t, 10000 > socket_buffer_
 Fixed-size buffer for reading directly from sockets. More...
 
boost::asio::ip::tcp::socket tcp_socket_
 
boost::circular_buffer< novatel_gps_msgs::TimePtr > time_msgs_
 
TimeParser time_parser_
 
boost::circular_buffer< novatel_gps_msgs::TrackstatPtr > trackstat_msgs_
 
TrackstatParser trackstat_parser_
 
boost::shared_ptr< boost::asio::ip::udp::endpoint > udp_endpoint_
 
boost::shared_ptr< boost::asio::ip::udp::socket > udp_socket_
 
double utc_offset_
 

Static Private Attributes

static constexpr uint16_t DEFAULT_TCP_PORT = 3001
 
static constexpr uint16_t DEFAULT_UDP_PORT = 3002
 
static constexpr double DEGREES_TO_RADIANS = M_PI / 180.0
 
static constexpr double IMU_TOLERANCE_S = 0.0002
 
static constexpr size_t MAX_BUFFER_SIZE = 100
 
static constexpr uint32_t SECONDS_PER_WEEK = 604800
 
static constexpr size_t SYNC_BUFFER_SIZE = 10
 

Detailed Description

Definition at line 95 of file novatel_gps.h.

Member Enumeration Documentation

Enumerator
SERIAL 
TCP 
UDP 
PCAP 
INVALID 

Definition at line 98 of file novatel_gps.h.

Enumerator
READ_SUCCESS 
READ_INSUFFICIENT_DATA 
READ_TIMEOUT 
READ_INTERRUPTED 
READ_ERROR 
READ_PARSE_FAILED 

Definition at line 100 of file novatel_gps.h.

Constructor & Destructor Documentation

novatel_gps_driver::NovatelGps::NovatelGps ( )

Definition at line 45 of file novatel_gps.cpp.

novatel_gps_driver::NovatelGps::~NovatelGps ( )

Definition at line 84 of file novatel_gps.cpp.

Member Function Documentation

void novatel_gps_driver::NovatelGps::ApplyVehicleBodyRotation ( const bool &  apply_rotation)

Determines whether or not to apply a 90 degree counter-clockwise rotation about Z to the Novatel SPAN frame to match up with the ROS coordinate frame.

Parameters
apply_rotationA bool indicating whether or not to apply the rotation.

Definition at line 185 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::Configure ( NovatelMessageOpts const &  opts)
private

(Re)configure the driver with a set of message options

Parameters
optsA map from message name to log period (seconds)
Returns
True on successful configuration

Definition at line 1447 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::Connect ( const std::string &  device,
ConnectionType  connection 
)

Connect and configure with default message options.

Parameters
deviceFor serial connections, a path to a device file handle, e.g. /dev/TTYUSB0; for IP connections, a host:port specification, e.g. "192.168.1.10:3001"
connectionThe type of connection.
Returns
True on success

Definition at line 89 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::Connect ( const std::string &  device,
ConnectionType  connection,
NovatelMessageOpts const &  opts 
)

Connect and configure with the given message options

Parameters
deviceFor serial connections, a path to a device file handle, e.g. /dev/TTYUSB0; for IP connections, a host:port specification, e.g. "192.168.1.10:3001"
connectionThe type of connection.
optsMessage options to use
Returns
True on success

Definition at line 102 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::CreateIpConnection ( const std::string &  endpoint,
NovatelMessageOpts const &  opts 
)
private

Establishes an IP connection with a NovAtel device.

Based on the current value in connection_, this will create either a TCP or UDP socket; then, based on the value in endpoint, it will either create a connection to a NovAtel device on a specific port or wait for a connection from one. In any case, this method will block until a connection is either established or failed.

After it has been called, Configure() will be called on the device and provided opts in order to configure which logs it will produce. After that, ReadData() and Write() may be used to communicate with the device.

Parameters
endpointA host and port specification; e. g., "192.168.1.10:1000". If the host host is omitted, it will listen for a connection the specified port. If the port is omitted, DEFAULT_TCP_PORT will be used for TCP connections and DEFAULT_UDP_PORT for UDP connections.
optsA map of logs and periods the device should produce.
Returns
false if it failed to create a connection, true otherwise.

Definition at line 606 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::CreatePcapConnection ( const std::string &  device,
NovatelMessageOpts const &  opts 
)
private

Creates a pcap device for playing back recorded data.

Parameters
device
opts
Returns

Definition at line 556 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::CreateSerialConnection ( const std::string &  device,
NovatelMessageOpts const &  opts 
)
private

Establishes a serial port connection with a NovAtel device.

It will create a connection set at the baud set by SetSerialBaudRate(), no parity, no flow control, and 8N1 bits, then it will call Configure() on that connection. After this method has succeeded, RedData() and Write() can be used to communicate with the device.

Parameters
deviceThe device node to connect to; e. g., "/dev/ttyUSB0"
optsA map of logs and periods the device should produce.
Returns
false if it failed to create a connection, true otherwise.

Definition at line 572 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::Disconnect ( )

Disconnects from a connected device

Definition at line 152 of file novatel_gps.cpp.

std::string novatel_gps_driver::NovatelGps::ErrorMsg ( ) const
inline
Returns
The most recent error message

Definition at line 142 of file novatel_gps.h.

void novatel_gps_driver::NovatelGps::GenerateImuMessages ( )
private

Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them.

Definition at line 918 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetClockSteeringMessages ( std::vector< novatel_gps_msgs::ClockSteeringPtr > &  clocksteering_msgs)

Provides any CLOCKSTEERING messages that have been received since the last time this was called.

Parameters
[out]clocksteering_msgsNew CLOCKSTEERING messages.

Definition at line 549 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetFixMessages ( std::vector< gps_common::GPSFixPtr > &  fix_messages)

Provides any GPSFix messages that have been generated since the last time this was called.

Parameters
[out]fix_messagesNew GPSFix messages.

Definition at line 323 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetGpggaMessages ( std::vector< novatel_gps_msgs::GpggaPtr > &  gpgga_messages)

Provides any GPGGA messages that have been received since the last time this was called.

Parameters
[out]gpgga_messagesNew GPGGA messages.

Definition at line 465 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetGpgsaMessages ( std::vector< novatel_gps_msgs::GpgsaPtr > &  gpgsa_messages)

Provides any GPGSA messages that have been received since the last time this was called.

Parameters
[out]gpgsa_messagesNew GPGSA messages.

Definition at line 472 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetGpgsvMessages ( std::vector< novatel_gps_msgs::GpgsvPtr > &  gpgsv_messages)

Provides any GPGSV messages that have been received since the last time this was called.

Parameters
[out]gpgsv_messagesNew GPGSV messages.

Definition at line 479 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetGphdtMessages ( std::vector< novatel_gps_msgs::GphdtPtr > &  gphdt_messages)

Provides any GPHDT messages that have been received since the last time this was called.

Parameters
[out]gpgsv_messagesNew GPHDT messages.

Definition at line 486 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetGprmcMessages ( std::vector< novatel_gps_msgs::GprmcPtr > &  gprmc_messages)

Provides any GPRMC messages that have been received since the last time this was called.

Parameters
[out]gprmc_messagesNew GPRMC messages.

Definition at line 493 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetImuMessages ( std::vector< sensor_msgs::ImuPtr > &  imu_messages)

Provides any Imu messages that have been generated since the last time this was called.

Parameters
[out]imu_messageNew Imu messages.

Definition at line 911 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetInscovMessages ( std::vector< novatel_gps_msgs::InscovPtr > &  inscov_messages)

Provides any INSCOV messages that have been received since the last time this was called.

Parameters
[out]inscov_messagesNew INSCOV messages.

Definition at line 500 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetInspvaMessages ( std::vector< novatel_gps_msgs::InspvaPtr > &  inspva_messages)

Provides any INSPVA messages that have been received since the last time this was called.

Parameters
[out]inspva_messagesNew INSPVA messages.

Definition at line 507 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetInspvaxMessages ( std::vector< novatel_gps_msgs::InspvaxPtr > &  inspvax_messages)

Provides any INSPVAX messages that have been received since the last time this was called.

Parameters
[out]inspvax_messagesNew INSPVAX messages.

Definition at line 514 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetInsstdevMessages ( std::vector< novatel_gps_msgs::InsstdevPtr > &  insstdev_messages)

Provides any INSSTDEV messages that have been received since the last time this was called.

Parameters
[out]insstdev_messagesNew INSSTDEV messages.

Definition at line 521 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelCorrectedImuData ( std::vector< novatel_gps_msgs::NovatelCorrectedImuDataPtr > &  imu_messages)

Provides any CORRIMUDATA messages that have been received since the last time this was called.

Parameters
[out]imu_messagesNew CORRIMUDATA messages.

Definition at line 451 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelDualAntennaHeadingMessages ( std::vector< novatel_gps_msgs::NovatelDualAntennaHeadingPtr > &  headings)

Provides any DUALANTENNAHEADING messages that have been received since the last time this was called.

Parameters
[out]headingsNew DUALANTENNAHEADING messages.

Definition at line 445 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelHeading2Messages ( std::vector< novatel_gps_msgs::NovatelHeading2Ptr > &  headings)

Provides any HEADING2 messages that have been received since the last time this was called.

Parameters
[out]headingsNew HEADING2 messages.

Definition at line 439 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelPositions ( std::vector< novatel_gps_msgs::NovatelPositionPtr > &  positions)

Provides any BESTPOS messages that have been received since the last time this was called.

Parameters
[out]positionsNew BESTPOS messages.

Definition at line 295 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelPsrdop2Messages ( std::vector< novatel_gps_msgs::NovatelPsrdop2Ptr > &  psrdop2_messages)

Provides any PSRDOP2 messages that have been received since the last time this was called.

Parameters
[out]psrdop2_messagesNew PSRDOP2 messages.

Definition at line 458 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelUtmPositions ( std::vector< novatel_gps_msgs::NovatelUtmPositionPtr > &  utm_positions)

Provides any BESTUTM messages that have been received since the last time this was called.

Parameters
[out]positionsNew BESTUTM messages.

Definition at line 309 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelVelocities ( std::vector< novatel_gps_msgs::NovatelVelocityPtr > &  velocities)

Provides any BESTVEL messages that have been received since the last time this was called.

Parameters
[out]velocitiesNew BESTVEL messages.

Definition at line 316 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetNovatelXYZPositions ( std::vector< novatel_gps_msgs::NovatelXYZPtr > &  positions)

Provides any BESTXYZ messages that have been received since the last time this was called.

Parameters
[out]positionsNew BESTXYZ messages.

Definition at line 302 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetRangeMessages ( std::vector< novatel_gps_msgs::RangePtr > &  range_messages)

Provides any RANGE messages that have been received since the last time this was called.

Parameters
[out]range_messagesNew RANGE messages.

Definition at line 528 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetTimeMessages ( std::vector< novatel_gps_msgs::TimePtr > &  time_messages)

Provides any TIME messages that have been received since the last time this was called.

Parameters
[out]time_messagesNew TIME messages.

Definition at line 535 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::GetTrackstatMessages ( std::vector< novatel_gps_msgs::TrackstatPtr > &  trackstat_msgs)

Provides any TRACKSTAT messages that have been received since the last time this was called.

Parameters
[out]trackstat_msgsNew TRACKSTAT messages.

Definition at line 542 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::IsConnected ( )
inline
Returns
true if we are connected to a NovAtel device, false otherwise.

Definition at line 286 of file novatel_gps.h.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ParseBinaryMessage ( const BinaryMessage msg,
const ros::Time stamp 
)
privatenoexcept

Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appropriate buffer.

Parameters
[in]msgA valid binary message
[in]stampA timestamp to set in the ROS message header.
Returns
A value indicating the success of the operation.

Definition at line 1026 of file novatel_gps.cpp.

NovatelGps::ConnectionType novatel_gps_driver::NovatelGps::ParseConnection ( const std::string &  connection)
static

Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.

Parameters
connectionA string indicating the connection type.
Returns
The corresponding enum value.

Definition at line 130 of file novatel_gps.cpp.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ParseNmeaSentence ( const NmeaSentence sentence,
const ros::Time stamp,
double  most_recent_utc_time 
)
privatenoexcept

Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate buffer.

Parameters
[in]sentenceA valid NMEA sentence
[in]stampA timestamp to set in the ROS message header.
most_recent_utc_timeThe most recently received time in any GPGGA or GPRMC message; used to adjust timestamps in ROS message headers.
Returns
A value indicating the success of the operation.

Definition at line 1165 of file novatel_gps.cpp.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ParseNovatelSentence ( const NovatelSentence sentence,
const ros::Time stamp 
)
privatenoexcept

Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the appropriate buffer.

Parameters
[in]msgA valid ASCII NovAtel message message
[in]stampA timestamp to set in the ROS message header.
Returns
A value indicating the success of the operation.

Definition at line 1222 of file novatel_gps.cpp.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ProcessData ( )

Processes any data that has been received from the device since the last time this message was called. May result in any number of messages being placed in the individual message buffers.

Returns
A code indicating the success of reading from the device.

Definition at line 190 of file novatel_gps.cpp.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ReadData ( )
private

Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.

Returns
The status of the read operation.

Definition at line 721 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::SetImuRate ( double  imu_rate,
bool  force = true 
)

Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.

Parameters
imu_rateThe IMU rate in Hz.
forceIf this value should be used instead of an autodetected one

Definition at line 1010 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::SetSerialBaud ( int32_t  serial_baud)

Sets the serial baud rate; should be called before configuring a serial connection.

Parameters
serial_baud_rateThe serial baud rate.

Definition at line 1020 of file novatel_gps.cpp.

bool novatel_gps_driver::NovatelGps::Write ( const std::string &  command)

Writes the given string of characters to a connected NovAtel device.

Parameters
commandA string to transmit.
Returns
true if we successfully wrote all of the data, false otherwise.

Definition at line 1397 of file novatel_gps.cpp.

Member Data Documentation

bool novatel_gps_driver::NovatelGps::apply_vehicle_body_rotation_
private

Definition at line 535 of file novatel_gps.h.

BestposParser novatel_gps_driver::NovatelGps::bestpos_parser_
private

Definition at line 477 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> novatel_gps_driver::NovatelGps::bestpos_sync_buffer_
private

Definition at line 516 of file novatel_gps.h.

BestutmParser novatel_gps_driver::NovatelGps::bestutm_parser_
private

Definition at line 479 of file novatel_gps.h.

BestvelParser novatel_gps_driver::NovatelGps::bestvel_parser_
private

Definition at line 480 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelVelocityPtr> novatel_gps_driver::NovatelGps::bestvel_sync_buffer_
private

Definition at line 517 of file novatel_gps.h.

BestxyzParser novatel_gps_driver::NovatelGps::bestxyz_parser_
private

Definition at line 478 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::ClockSteeringPtr> novatel_gps_driver::NovatelGps::clocksteering_msgs_
private

Definition at line 500 of file novatel_gps.h.

ClockSteeringParser novatel_gps_driver::NovatelGps::clocksteering_parser_
private

Definition at line 483 of file novatel_gps.h.

ConnectionType novatel_gps_driver::NovatelGps::connection_
private

Definition at line 439 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_gps_driver::NovatelGps::corrimudata_msgs_
private

Definition at line 501 of file novatel_gps.h.

CorrImuDataParser novatel_gps_driver::NovatelGps::corrimudata_parser_
private

Definition at line 484 of file novatel_gps.h.

std::queue<novatel_gps_msgs::NovatelCorrectedImuDataPtr> novatel_gps_driver::NovatelGps::corrimudata_queue_
private

Definition at line 528 of file novatel_gps.h.

std::vector<uint8_t> novatel_gps_driver::NovatelGps::data_buffer_
private

Variable-length buffer that has data continually appended to it until messages are parsed from it

Definition at line 461 of file novatel_gps.h.

constexpr uint16_t novatel_gps_driver::NovatelGps::DEFAULT_TCP_PORT = 3001
staticprivate

Definition at line 431 of file novatel_gps.h.

constexpr uint16_t novatel_gps_driver::NovatelGps::DEFAULT_UDP_PORT = 3002
staticprivate

Definition at line 432 of file novatel_gps.h.

constexpr double novatel_gps_driver::NovatelGps::DEGREES_TO_RADIANS = M_PI / 180.0
staticprivate

Definition at line 437 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelDualAntennaHeadingPtr> novatel_gps_driver::NovatelGps::dual_antenna_heading_msgs_
private

Definition at line 519 of file novatel_gps.h.

DualAntennaHeadingParser novatel_gps_driver::NovatelGps::dual_antenna_heading_parser_
private

Definition at line 482 of file novatel_gps.h.

std::string novatel_gps_driver::NovatelGps::error_msg_
private

Definition at line 441 of file novatel_gps.h.

NovatelMessageExtractor novatel_gps_driver::NovatelGps::extractor_
private

Used to extract messages from the incoming data stream.

Definition at line 474 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::GpggaPtr> novatel_gps_driver::NovatelGps::gpgga_msgs_
private

Definition at line 502 of file novatel_gps.h.

GpggaParser novatel_gps_driver::NovatelGps::gpgga_parser_
private

Definition at line 485 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::GpgsaPtr> novatel_gps_driver::NovatelGps::gpgsa_msgs_
private

Definition at line 503 of file novatel_gps.h.

GpgsaParser novatel_gps_driver::NovatelGps::gpgsa_parser_
private

Definition at line 486 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::GpgsvPtr> novatel_gps_driver::NovatelGps::gpgsv_msgs_
private

Definition at line 504 of file novatel_gps.h.

GpgsvParser novatel_gps_driver::NovatelGps::gpgsv_parser_
private

Definition at line 487 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::GphdtPtr> novatel_gps_driver::NovatelGps::gphdt_msgs_
private

Definition at line 505 of file novatel_gps.h.

GphdtParser novatel_gps_driver::NovatelGps::gphdt_parser_
private

Definition at line 488 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::GprmcPtr> novatel_gps_driver::NovatelGps::gprmc_msgs_
private

Definition at line 506 of file novatel_gps.h.

GprmcParser novatel_gps_driver::NovatelGps::gprmc_parser_
private

Definition at line 489 of file novatel_gps.h.

double novatel_gps_driver::NovatelGps::gpsfix_sync_tol_

Definition at line 330 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelHeading2Ptr> novatel_gps_driver::NovatelGps::heading2_msgs_
private

Definition at line 518 of file novatel_gps.h.

Heading2Parser novatel_gps_driver::NovatelGps::heading2_parser_
private

Definition at line 481 of file novatel_gps.h.

boost::circular_buffer<sensor_msgs::ImuPtr> novatel_gps_driver::NovatelGps::imu_msgs_
private

Definition at line 507 of file novatel_gps.h.

double novatel_gps_driver::NovatelGps::imu_rate_
private

Definition at line 532 of file novatel_gps.h.

bool novatel_gps_driver::NovatelGps::imu_rate_forced_
private

Definition at line 444 of file novatel_gps.h.

constexpr double novatel_gps_driver::NovatelGps::IMU_TOLERANCE_S = 0.0002
staticprivate

Definition at line 436 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::InscovPtr> novatel_gps_driver::NovatelGps::inscov_msgs_
private

Definition at line 508 of file novatel_gps.h.

InscovParser novatel_gps_driver::NovatelGps::inscov_parser_
private

Definition at line 490 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::InspvaPtr> novatel_gps_driver::NovatelGps::inspva_msgs_
private

Definition at line 509 of file novatel_gps.h.

InspvaParser novatel_gps_driver::NovatelGps::inspva_parser_
private

Definition at line 491 of file novatel_gps.h.

std::queue<novatel_gps_msgs::InspvaPtr> novatel_gps_driver::NovatelGps::inspva_queue_
private

Definition at line 529 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::InspvaxPtr> novatel_gps_driver::NovatelGps::inspvax_msgs_
private

Definition at line 510 of file novatel_gps.h.

InspvaxParser novatel_gps_driver::NovatelGps::inspvax_parser_
private

Definition at line 492 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::InsstdevPtr> novatel_gps_driver::NovatelGps::insstdev_msgs_
private

Definition at line 511 of file novatel_gps.h.

InsstdevParser novatel_gps_driver::NovatelGps::insstdev_parser_
private

Definition at line 493 of file novatel_gps.h.

boost::asio::io_service novatel_gps_driver::NovatelGps::io_service_
private

Definition at line 453 of file novatel_gps.h.

bool novatel_gps_driver::NovatelGps::is_connected_
private

Definition at line 443 of file novatel_gps.h.

std::vector<uint8_t> novatel_gps_driver::NovatelGps::last_tcp_packet_
private

Definition at line 471 of file novatel_gps.h.

novatel_gps_msgs::InscovPtr novatel_gps_driver::NovatelGps::latest_inscov_
private

Definition at line 531 of file novatel_gps.h.

novatel_gps_msgs::InsstdevPtr novatel_gps_driver::NovatelGps::latest_insstdev_
private

Definition at line 530 of file novatel_gps.h.

novatel_gps_msgs::NovatelPsrdop2Ptr novatel_gps_driver::NovatelGps::latest_psrdop2_
private

Definition at line 525 of file novatel_gps.h.

constexpr size_t novatel_gps_driver::NovatelGps::MAX_BUFFER_SIZE = 100
staticprivate

Definition at line 433 of file novatel_gps.h.

std::string novatel_gps_driver::NovatelGps::nmea_buffer_
private

Buffer containing incomplete data from message parsing.

Definition at line 463 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> novatel_gps_driver::NovatelGps::novatel_positions_
private

Definition at line 512 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelUtmPositionPtr> novatel_gps_driver::NovatelGps::novatel_utm_positions_
private

Definition at line 514 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelVelocityPtr> novatel_gps_driver::NovatelGps::novatel_velocities_
private

Definition at line 515 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelXYZPtr> novatel_gps_driver::NovatelGps::novatel_xyz_positions_
private

Definition at line 513 of file novatel_gps.h.

pcap_t* novatel_gps_driver::NovatelGps::pcap_
private

pcap device for testing

Definition at line 468 of file novatel_gps.h.

char novatel_gps_driver::NovatelGps::pcap_errbuf_[MAX_BUFFER_SIZE]
private

Definition at line 470 of file novatel_gps.h.

bpf_program novatel_gps_driver::NovatelGps::pcap_packet_filter_
private

Definition at line 469 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelPsrdop2Ptr> novatel_gps_driver::NovatelGps::psrdop2_msgs_
private

Definition at line 520 of file novatel_gps.h.

Psrdop2Parser novatel_gps_driver::NovatelGps::psrdop2_parser_
private

Definition at line 494 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::RangePtr> novatel_gps_driver::NovatelGps::range_msgs_
private

Definition at line 521 of file novatel_gps.h.

RangeParser novatel_gps_driver::NovatelGps::range_parser_
private

Definition at line 495 of file novatel_gps.h.

constexpr uint32_t novatel_gps_driver::NovatelGps::SECONDS_PER_WEEK = 604800
staticprivate

Definition at line 435 of file novatel_gps.h.

swri_serial_util::SerialPort novatel_gps_driver::NovatelGps::serial_
private

Definition at line 450 of file novatel_gps.h.

int32_t novatel_gps_driver::NovatelGps::serial_baud_
private

Definition at line 449 of file novatel_gps.h.

boost::array<uint8_t, 10000> novatel_gps_driver::NovatelGps::socket_buffer_
private

Fixed-size buffer for reading directly from sockets.

Definition at line 465 of file novatel_gps.h.

constexpr size_t novatel_gps_driver::NovatelGps::SYNC_BUFFER_SIZE = 10
staticprivate

Definition at line 434 of file novatel_gps.h.

boost::asio::ip::tcp::socket novatel_gps_driver::NovatelGps::tcp_socket_
private

Definition at line 454 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::TimePtr> novatel_gps_driver::NovatelGps::time_msgs_
private

Definition at line 522 of file novatel_gps.h.

TimeParser novatel_gps_driver::NovatelGps::time_parser_
private

Definition at line 496 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::TrackstatPtr> novatel_gps_driver::NovatelGps::trackstat_msgs_
private

Definition at line 523 of file novatel_gps.h.

TrackstatParser novatel_gps_driver::NovatelGps::trackstat_parser_
private

Definition at line 497 of file novatel_gps.h.

boost::shared_ptr<boost::asio::ip::udp::endpoint> novatel_gps_driver::NovatelGps::udp_endpoint_
private

Definition at line 456 of file novatel_gps.h.

boost::shared_ptr<boost::asio::ip::udp::socket> novatel_gps_driver::NovatelGps::udp_socket_
private

Definition at line 455 of file novatel_gps.h.

double novatel_gps_driver::NovatelGps::utc_offset_
private

Definition at line 446 of file novatel_gps.h.

bool novatel_gps_driver::NovatelGps::wait_for_sync_

Definition at line 331 of file novatel_gps.h.


The documentation for this class was generated from the following files:


novatel_gps_driver
Author(s):
autogenerated on Thu Jul 16 2020 03:17:31