Class NovatelGps

Class Documentation

class NovatelGps

Public Types

enum ConnectionType

Values:

enumerator SERIAL
enumerator TCP
enumerator UDP
enumerator PCAP
enumerator INVALID
enum ReadResult

Values:

enumerator READ_SUCCESS
enumerator READ_INSUFFICIENT_DATA
enumerator READ_TIMEOUT
enumerator READ_INTERRUPTED
enumerator READ_ERROR
enumerator READ_PARSE_FAILED

Public Functions

explicit NovatelGps(rclcpp::Node &Node)
~NovatelGps()
bool Connect(const std::string &device, ConnectionType connection)

Connect and configure with default message options.

Parameters:
  • 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.

Returns:

True on success

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

Connect and configure with the given message options

Parameters:
  • 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

Returns:

True on success

void Disconnect()

Disconnects from a connected device

inline std::string ErrorMsg() const
Returns:

The most recent error message

void GetFixMessages(std::vector<gps_msgs::msg::GPSFix::UniquePtr> &fix_messages)

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

Parameters:

fix_messages[out] New GPSFix messages.

void GetGpggaMessages(std::vector<novatel_gps_driver::GpggaParser::MessageType> &gpgga_messages)

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

Parameters:

gpgga_messages[out] New GPGGA messages.

void GetGpgsaMessages(std::vector<novatel_gps_driver::GpgsaParser::MessageType> &gpgsa_messages)

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

Parameters:

gpgsa_messages[out] New GPGSA messages.

void GetGpgsvMessages(std::vector<novatel_gps_driver::GpgsvParser::MessageType> &gpgsv_messages)

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

Parameters:

gpgsv_messages[out] New GPGSV messages.

void GetGphdtMessages(std::vector<novatel_gps_driver::GphdtParser::MessageType> &gphdt_messages)

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

Parameters:

gpgsv_messages[out] New GPHDT messages.

void GetGprmcMessages(std::vector<novatel_gps_driver::GprmcParser::MessageType> &gprmc_messages)

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

Parameters:

gprmc_messages[out] New GPRMC messages.

void GetNovatelHeading2Messages(std::vector<novatel_gps_driver::Heading2Parser::MessageType> &headings)

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

Parameters:

headings[out] New HEADING2 messages.

void GetNovatelDualAntennaHeadingMessages(std::vector<novatel_gps_driver::DualAntennaHeadingParser::MessageType> &headings)

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

Parameters:

headings[out] New DUALANTENNAHEADING messages.

void GetNovatelPsrdop2Messages(std::vector<novatel_gps_driver::Psrdop2Parser::MessageType> &psrdop2_messages)

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

Parameters:

psrdop2_messages[out] New PSRDOP2 messages.

void GetImuMessages(std::vector<sensor_msgs::msg::Imu::SharedPtr> &imu_messages)

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

Parameters:

imu_message[out] New Imu messages.

void GetInscovMessages(std::vector<novatel_gps_driver::InscovParser::MessageType> &inscov_messages)

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

Parameters:

inscov_messages[out] New INSCOV messages.

void GetInspvaMessages(std::vector<novatel_gps_driver::InspvaParser::MessageType> &inspva_messages)

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

Parameters:

inspva_messages[out] New INSPVA messages.

void GetInspvaxMessages(std::vector<novatel_gps_driver::InspvaxParser::MessageType> &inspvax_messages)

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

Parameters:

inspvax_messages[out] New INSPVAX messages.

void GetInsstdevMessages(std::vector<novatel_gps_driver::InsstdevParser::MessageType> &insstdev_messages)

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

Parameters:

insstdev_messages[out] New INSSTDEV messages.

void GetNovatelCorrectedImuData(std::vector<novatel_gps_driver::CorrImuDataParser::MessageType> &imu_messages)

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

Parameters:

imu_messages[out] New CORRIMUDATA messages.

void GetNovatelPositions(std::vector<novatel_gps_driver::BestposParser::MessageType> &positions)

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

Parameters:

positions[out] New BESTPOS messages.

void GetNovatelXYZPositions(std::vector<novatel_gps_driver::BestxyzParser::MessageType> &positions)

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

Parameters:

positions[out] New BESTXYZ messages.

void GetNovatelUtmPositions(std::vector<novatel_gps_driver::BestutmParser::MessageType> &utm_positions)

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

Parameters:

positions[out] New BESTUTM messages.

void GetNovatelVelocities(std::vector<novatel_gps_driver::BestvelParser::MessageType> &velocities)

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

Parameters:

velocities[out] New BESTVEL messages.

void GetRangeMessages(std::vector<novatel_gps_driver::RangeParser::MessageType> &range_messages)

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

Parameters:

range_messages[out] New RANGE messages.

void GetTimeMessages(std::vector<novatel_gps_driver::TimeParser::MessageType> &time_messages)

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

Parameters:

time_messages[out] New TIME messages.

void GetTrackstatMessages(std::vector<novatel_gps_driver::TrackstatParser::MessageType> &trackstat_msgs)

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

Parameters:

trackstat_msgs[out] New TRACKSTAT messages.

void GetClockSteeringMessages(std::vector<novatel_gps_driver::ClockSteeringParser::MessageType> &clocksteering_msgs)

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

Parameters:

clocksteering_msgs[out] New CLOCKSTEERING messages.

inline bool IsConnected()
Returns:

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

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.

Parameters:

apply_rotation – A bool indicating whether or not to apply the rotation.

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.

Returns:

A code indicating the success of reading from the device.

void SetImuRate(double imu_rate, bool force = true)

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

Parameters:
  • imu_rate – The IMU rate in Hz.

  • force – If this value should be used instead of an autodetected one

void SetSerialBaud(int32_t serial_baud)

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

Parameters:

serial_baud_rate – The serial baud rate.

bool Write(const std::string &command)

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

Parameters:

command – A string to transmit.

Returns:

true if we successfully wrote all of the data, false otherwise.

Public Members

double gpsfix_sync_tol_
bool wait_for_sync_

Public Static Functions

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

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

Parameters:

connection – A string indicating the connection type.

Returns:

The corresponding enum value.