#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 |
Definition at line 95 of file novatel_gps.h.
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.
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.
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.
apply_rotation | A bool indicating whether or not to apply the rotation. |
Definition at line 185 of file novatel_gps.cpp.
|
private |
(Re)configure the driver with a set of message options
opts | A map from message name to log period (seconds) |
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.
device | For 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" |
connection | The type of connection. |
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
device | For 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" |
connection | The type of connection. |
opts | Message options to use |
Definition at line 102 of file novatel_gps.cpp.
|
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.
endpoint | A 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. |
opts | A map of logs and periods the device should produce. |
Definition at line 606 of file novatel_gps.cpp.
|
private |
Creates a pcap device for playing back recorded data.
device | |
opts |
Definition at line 556 of file novatel_gps.cpp.
|
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.
device | The device node to connect to; e. g., "/dev/ttyUSB0" |
opts | A map of logs and periods the device should produce. |
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.
|
inline |
Definition at line 142 of file novatel_gps.h.
|
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.
[out] | clocksteering_msgs | New 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.
[out] | fix_messages | New 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.
[out] | gpgga_messages | New 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.
[out] | gpgsa_messages | New 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.
[out] | gpgsv_messages | New 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.
[out] | gpgsv_messages | New 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.
[out] | gprmc_messages | New 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.
[out] | imu_message | New 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.
[out] | inscov_messages | New 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.
[out] | inspva_messages | New 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.
[out] | inspvax_messages | New 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.
[out] | insstdev_messages | New 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.
[out] | imu_messages | New 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.
[out] | headings | New 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.
[out] | headings | New 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.
[out] | positions | New 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.
[out] | psrdop2_messages | New 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.
[out] | positions | New 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.
[out] | velocities | New 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.
[out] | positions | New 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.
[out] | range_messages | New 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.
[out] | time_messages | New 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.
[out] | trackstat_msgs | New TRACKSTAT messages. |
Definition at line 542 of file novatel_gps.cpp.
|
inline |
Definition at line 286 of file novatel_gps.h.
|
privatenoexcept |
Converts a BinaryMessage object into a ROS message of the appropriate type and places it in the appropriate buffer.
[in] | msg | A valid binary message |
[in] | stamp | A timestamp to set in the ROS message header. |
Definition at line 1026 of file novatel_gps.cpp.
|
static |
Converts the strings "udp", "tcp", or "serial" into the corresponding enum values.
connection | A string indicating the connection type. |
Definition at line 130 of file novatel_gps.cpp.
|
privatenoexcept |
Converts an NMEA sentence into a ROS message of the appropriate type and places it in the appropriate buffer.
[in] | sentence | A valid NMEA sentence |
[in] | stamp | A timestamp to set in the ROS message header. |
most_recent_utc_time | The most recently received time in any GPGGA or GPRMC message; used to adjust timestamps in ROS message headers. |
Definition at line 1165 of file novatel_gps.cpp.
|
privatenoexcept |
Converts a NovatelSentence object into a ROS message of the appropriate type and places it in the appropriate buffer.
[in] | msg | A valid ASCII NovAtel message message |
[in] | stamp | A timestamp to set in the ROS message header. |
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.
Definition at line 190 of file novatel_gps.cpp.
|
private |
Reads data from a connected NovAtel device. Any read data will be appended to data_buffer_.
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.
imu_rate | The IMU rate in Hz. |
force | If 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.
serial_baud_rate | The 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.
command | A string to transmit. |
Definition at line 1397 of file novatel_gps.cpp.
|
private |
Definition at line 535 of file novatel_gps.h.
|
private |
Definition at line 477 of file novatel_gps.h.
|
private |
Definition at line 516 of file novatel_gps.h.
|
private |
Definition at line 479 of file novatel_gps.h.
|
private |
Definition at line 480 of file novatel_gps.h.
|
private |
Definition at line 517 of file novatel_gps.h.
|
private |
Definition at line 478 of file novatel_gps.h.
|
private |
Definition at line 500 of file novatel_gps.h.
|
private |
Definition at line 483 of file novatel_gps.h.
|
private |
Definition at line 439 of file novatel_gps.h.
|
private |
Definition at line 501 of file novatel_gps.h.
|
private |
Definition at line 484 of file novatel_gps.h.
|
private |
Definition at line 528 of file novatel_gps.h.
|
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.
|
staticprivate |
Definition at line 431 of file novatel_gps.h.
|
staticprivate |
Definition at line 432 of file novatel_gps.h.
|
staticprivate |
Definition at line 437 of file novatel_gps.h.
|
private |
Definition at line 519 of file novatel_gps.h.
|
private |
Definition at line 482 of file novatel_gps.h.
|
private |
Definition at line 441 of file novatel_gps.h.
|
private |
Used to extract messages from the incoming data stream.
Definition at line 474 of file novatel_gps.h.
|
private |
Definition at line 502 of file novatel_gps.h.
|
private |
Definition at line 485 of file novatel_gps.h.
|
private |
Definition at line 503 of file novatel_gps.h.
|
private |
Definition at line 486 of file novatel_gps.h.
|
private |
Definition at line 504 of file novatel_gps.h.
|
private |
Definition at line 487 of file novatel_gps.h.
|
private |
Definition at line 505 of file novatel_gps.h.
|
private |
Definition at line 488 of file novatel_gps.h.
|
private |
Definition at line 506 of file novatel_gps.h.
|
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.
|
private |
Definition at line 518 of file novatel_gps.h.
|
private |
Definition at line 481 of file novatel_gps.h.
|
private |
Definition at line 507 of file novatel_gps.h.
|
private |
Definition at line 532 of file novatel_gps.h.
|
private |
Definition at line 444 of file novatel_gps.h.
|
staticprivate |
Definition at line 436 of file novatel_gps.h.
|
private |
Definition at line 508 of file novatel_gps.h.
|
private |
Definition at line 490 of file novatel_gps.h.
|
private |
Definition at line 509 of file novatel_gps.h.
|
private |
Definition at line 491 of file novatel_gps.h.
|
private |
Definition at line 529 of file novatel_gps.h.
|
private |
Definition at line 510 of file novatel_gps.h.
|
private |
Definition at line 492 of file novatel_gps.h.
|
private |
Definition at line 511 of file novatel_gps.h.
|
private |
Definition at line 493 of file novatel_gps.h.
|
private |
Definition at line 453 of file novatel_gps.h.
|
private |
Definition at line 443 of file novatel_gps.h.
|
private |
Definition at line 471 of file novatel_gps.h.
|
private |
Definition at line 531 of file novatel_gps.h.
|
private |
Definition at line 530 of file novatel_gps.h.
|
private |
Definition at line 525 of file novatel_gps.h.
|
staticprivate |
Definition at line 433 of file novatel_gps.h.
|
private |
Buffer containing incomplete data from message parsing.
Definition at line 463 of file novatel_gps.h.
|
private |
Definition at line 512 of file novatel_gps.h.
|
private |
Definition at line 514 of file novatel_gps.h.
|
private |
Definition at line 515 of file novatel_gps.h.
|
private |
Definition at line 513 of file novatel_gps.h.
|
private |
pcap device for testing
Definition at line 468 of file novatel_gps.h.
|
private |
Definition at line 470 of file novatel_gps.h.
|
private |
Definition at line 469 of file novatel_gps.h.
|
private |
Definition at line 520 of file novatel_gps.h.
|
private |
Definition at line 494 of file novatel_gps.h.
|
private |
Definition at line 521 of file novatel_gps.h.
|
private |
Definition at line 495 of file novatel_gps.h.
|
staticprivate |
Definition at line 435 of file novatel_gps.h.
|
private |
Definition at line 450 of file novatel_gps.h.
|
private |
Definition at line 449 of file novatel_gps.h.
|
private |
Fixed-size buffer for reading directly from sockets.
Definition at line 465 of file novatel_gps.h.
|
staticprivate |
Definition at line 434 of file novatel_gps.h.
|
private |
Definition at line 454 of file novatel_gps.h.
|
private |
Definition at line 522 of file novatel_gps.h.
|
private |
Definition at line 496 of file novatel_gps.h.
|
private |
Definition at line 523 of file novatel_gps.h.
|
private |
Definition at line 497 of file novatel_gps.h.
|
private |
Definition at line 456 of file novatel_gps.h.
|
private |
Definition at line 455 of file novatel_gps.h.
|
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.