Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Static Private Attributes
novatel_gps_driver::NovatelGps Class Reference

#include <novatel_gps.h>

List of all members.

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

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 GetFixMessages (std::vector< gps_common::GPSFixPtr > &fix_messages)
 Provides any GPSFix messages that have been generated since the last time this was called.
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.
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 GetGpgsvMessages (std::vector< novatel_gps_msgs::GpgsvPtr > &gpgsv_messages)
 Provides any GPGSV messages that have been received 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.
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 GetInscovMessages (std::vector< novatel_gps_msgs::InscovPtr > &inscov_messages)
 Provides any INSCOV messages that have been received since the last time this was called.
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.
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.
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.
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 GetNovatelVelocities (std::vector< novatel_gps_msgs::NovatelVelocityPtr > &velocities)
 Provides any BESTVEL messages that have been received since the last time this was called.
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.
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.
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 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.
void SetImuRate (double imu_rate)
 Sets the IMU rate; necessary for producing sensor_msgs/Imu messages.
bool Write (const std::string &command)
 Writes the given string of characters to a connected NovAtel device.
 ~NovatelGps ()

Static Public Member Functions

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

Public Attributes

double gpgga_gprmc_sync_tol_
double gpgga_position_sync_tol_
bool wait_for_position_

Private Member Functions

bool Configure (NovatelMessageOpts const &opts)
 (Re)configure the driver with a set of message options
bool CreateIpConnection (const std::string &endpoint, NovatelMessageOpts const &opts)
 Establishes an IP connection with a NovAtel device.
bool CreatePcapConnection (const std::string &device, NovatelMessageOpts const &opts)
 Creates a pcap device for playing back recorded data.
bool CreateSerialConnection (const std::string &device, NovatelMessageOpts const &opts)
 Establishes a serial port connection with a NovAtel device.
void GenerateImuMessages ()
 Processes any messages in our corrimudata & inspva queues in order to generate Imu messages from them.
NovatelGps::ReadResult ParseBinaryMessage (const BinaryMessage &msg, const ros::Time &stamp) throw (ParseException)
 Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appropriate buffer.
NovatelGps::ReadResult ParseNmeaSentence (const NmeaSentence &sentence, const ros::Time &stamp, double most_recent_utc_time) throw (ParseException)
 Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate buffer.
NovatelGps::ReadResult ParseNovatelSentence (const NovatelSentence &sentence, const ros::Time &stamp) throw (ParseException)
 Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the appropriate buffer.
ReadResult ReadData ()
 Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.

Private Attributes

BestposParser bestpos_parser_
BestvelParser bestvel_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_
std::string error_msg_
NovatelMessageExtractor extractor_
 Used to extract messages from the incoming data stream.
boost::circular_buffer
< novatel_gps_msgs::GpggaPtr > 
gpgga_msgs_
GpggaParser gpgga_parser_
boost::circular_buffer
< novatel_gps_msgs::Gpgga > 
gpgga_sync_buffer_
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::GprmcPtr > 
gprmc_msgs_
GprmcParser gprmc_parser_
boost::circular_buffer
< novatel_gps_msgs::Gprmc > 
gprmc_sync_buffer_
boost::circular_buffer
< sensor_msgs::ImuPtr > 
imu_msgs_
double imu_rate_
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::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_
std::string nmea_buffer_
 Buffer containing incomplete data from message parsing.
boost::circular_buffer
< novatel_gps_msgs::NovatelPositionPtr > 
novatel_positions_
boost::circular_buffer
< novatel_gps_msgs::NovatelVelocityPtr > 
novatel_velocities_
pcap_t * pcap_
 pcap device for testing
char pcap_errbuf_ [MAX_BUFFER_SIZE]
bpf_program pcap_packet_filter_
boost::circular_buffer
< novatel_gps_msgs::NovatelPositionPtr > 
position_sync_buffer_
boost::circular_buffer
< novatel_gps_msgs::RangePtr > 
range_msgs_
RangeParser range_parser_
swri_serial_util::SerialPort serial_
boost::array< uint8_t, 10000 > socket_buffer_
 Fixed-size buffer for reading directly from sockets.
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 82 of file novatel_gps.h.


Member Enumeration Documentation

Enumerator:
SERIAL 
TCP 
UDP 
PCAP 
INVALID 

Definition at line 85 of file novatel_gps.h.

Enumerator:
READ_SUCCESS 
READ_INSUFFICIENT_DATA 
READ_TIMEOUT 
READ_INTERRUPTED 
READ_ERROR 
READ_PARSE_FAILED 

Definition at line 87 of file novatel_gps.h.


Constructor & Destructor Documentation

Definition at line 45 of file novatel_gps.cpp.

Definition at line 75 of file novatel_gps.cpp.


Member Function Documentation

(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 1267 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 80 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 93 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 562 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 512 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 115200 baud, 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 528 of file novatel_gps.cpp.

Disconnects from a connected device

Definition at line 143 of file novatel_gps.cpp.

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

Definition at line 129 of file novatel_gps.h.

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

Definition at line 874 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 295 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 442 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 449 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 456 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 463 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 867 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 470 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 477 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 484 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 435 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 281 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 288 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 491 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 498 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 505 of file novatel_gps.cpp.

Returns:
true if we are connected to a NovAtel device, false otherwise.

Definition at line 225 of file novatel_gps.h.

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 972 of file novatel_gps.cpp.

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 121 of file novatel_gps.cpp.

NovatelGps::ReadResult novatel_gps_driver::NovatelGps::ParseNmeaSentence ( const NmeaSentence sentence,
const ros::Time stamp,
double  most_recent_utc_time 
) throw (ParseException) [private]

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 1067 of file novatel_gps.cpp.

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 1137 of file novatel_gps.cpp.

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 176 of file novatel_gps.cpp.

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 677 of file novatel_gps.cpp.

void novatel_gps_driver::NovatelGps::SetImuRate ( double  imu_rate)

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

Parameters:
imu_rateThe IMU rate in Hz.

Definition at line 966 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 1217 of file novatel_gps.cpp.


Member Data Documentation

Definition at line 403 of file novatel_gps.h.

Definition at line 404 of file novatel_gps.h.

Definition at line 367 of file novatel_gps.h.

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

Definition at line 418 of file novatel_gps.h.

Definition at line 405 of file novatel_gps.h.

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

Definition at line 437 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 387 of file novatel_gps.h.

constexpr uint16_t novatel_gps_driver::NovatelGps::DEFAULT_TCP_PORT = 3001 [static, private]

Definition at line 359 of file novatel_gps.h.

constexpr uint16_t novatel_gps_driver::NovatelGps::DEFAULT_UDP_PORT = 3002 [static, private]

Definition at line 360 of file novatel_gps.h.

constexpr double novatel_gps_driver::NovatelGps::DEGREES_TO_RADIANS = M_PI / 180.0 [static, private]

Definition at line 365 of file novatel_gps.h.

Definition at line 369 of file novatel_gps.h.

Used to extract messages from the incoming data stream.

Definition at line 400 of file novatel_gps.h.

Definition at line 256 of file novatel_gps.h.

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

Definition at line 419 of file novatel_gps.h.

Definition at line 406 of file novatel_gps.h.

Definition at line 257 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::Gpgga> novatel_gps_driver::NovatelGps::gpgga_sync_buffer_ [private]

Definition at line 420 of file novatel_gps.h.

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

Definition at line 421 of file novatel_gps.h.

Definition at line 407 of file novatel_gps.h.

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

Definition at line 422 of file novatel_gps.h.

Definition at line 408 of file novatel_gps.h.

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

Definition at line 423 of file novatel_gps.h.

Definition at line 409 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::Gprmc> novatel_gps_driver::NovatelGps::gprmc_sync_buffer_ [private]

Definition at line 424 of file novatel_gps.h.

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

Definition at line 425 of file novatel_gps.h.

Definition at line 441 of file novatel_gps.h.

constexpr double novatel_gps_driver::NovatelGps::IMU_TOLERANCE_S = 0.0002 [static, private]

Definition at line 364 of file novatel_gps.h.

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

Definition at line 426 of file novatel_gps.h.

Definition at line 410 of file novatel_gps.h.

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

Definition at line 427 of file novatel_gps.h.

Definition at line 411 of file novatel_gps.h.

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

Definition at line 438 of file novatel_gps.h.

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

Definition at line 428 of file novatel_gps.h.

Definition at line 412 of file novatel_gps.h.

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

Definition at line 379 of file novatel_gps.h.

Definition at line 371 of file novatel_gps.h.

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

Definition at line 397 of file novatel_gps.h.

novatel_gps_msgs::InscovPtr novatel_gps_driver::NovatelGps::latest_inscov_ [private]

Definition at line 440 of file novatel_gps.h.

novatel_gps_msgs::InsstdevPtr novatel_gps_driver::NovatelGps::latest_insstdev_ [private]

Definition at line 439 of file novatel_gps.h.

constexpr size_t novatel_gps_driver::NovatelGps::MAX_BUFFER_SIZE = 100 [static, private]

Definition at line 361 of file novatel_gps.h.

Buffer containing incomplete data from message parsing.

Definition at line 389 of file novatel_gps.h.

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

Definition at line 429 of file novatel_gps.h.

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

Definition at line 430 of file novatel_gps.h.

pcap device for testing

Definition at line 394 of file novatel_gps.h.

Definition at line 396 of file novatel_gps.h.

Definition at line 395 of file novatel_gps.h.

boost::circular_buffer<novatel_gps_msgs::NovatelPositionPtr> novatel_gps_driver::NovatelGps::position_sync_buffer_ [private]

Definition at line 431 of file novatel_gps.h.

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

Definition at line 432 of file novatel_gps.h.

Definition at line 413 of file novatel_gps.h.

constexpr uint32_t novatel_gps_driver::NovatelGps::SECONDS_PER_WEEK = 604800 [static, private]

Definition at line 363 of file novatel_gps.h.

Definition at line 376 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 391 of file novatel_gps.h.

constexpr size_t novatel_gps_driver::NovatelGps::SYNC_BUFFER_SIZE = 10 [static, private]

Definition at line 362 of file novatel_gps.h.

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

Definition at line 380 of file novatel_gps.h.

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

Definition at line 433 of file novatel_gps.h.

Definition at line 414 of file novatel_gps.h.

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

Definition at line 434 of file novatel_gps.h.

Definition at line 415 of file novatel_gps.h.

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

Definition at line 382 of file novatel_gps.h.

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

Definition at line 381 of file novatel_gps.h.

Definition at line 373 of file novatel_gps.h.

Definition at line 258 of file novatel_gps.h.


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


novatel_gps_driver
Author(s):
autogenerated on Sun Oct 8 2017 02:40:29