This is a C++ ROS driver for NovAtel GPS / GNSS Receivers.
Features:
BESTPOS
, BESTVEL
, and PSRDOP2
logs together in order to produce
gps_common/GPSFix messagesIt has been tested primarily on NovAtel OEM628 receivers, but it has been used with various OEM4, OEM6, and OEM7 devices. Please let the maintainers know of your success or failure in using this with other devices so we can update this page appropriately.
The driver should function on ROS 2 Dashing, and binary packages are available for both of them. To install them, first install ROS, then just run:
sudo apt-get install ros-dashing-novatel-gps-driver
If you'd like to build it from source:
mkdir -p novatel/src
cd novatel/src
git clone https://github.com/swri-robotics/novatel_gps_driver
rosdep install . --from-paths -i
cd ../..
colcon build
Then create a .launch.py
file and configure it as desired:
"""Launch an example driver that communicates using TCP"""
from launch import LaunchDescription
import launch_ros.actions
def generate_launch_description():
container = launch_ros.actions.ComposableNodeContainer(
name='novatel_gps_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
launch_ros.descriptions.ComposableNode(
package='novatel_gps_driver',
plugin='novatel_gps_driver::NovatelGpsNode',
name='novatel_gps',
parameters=[{
'connection_type': 'serial',
'device': '/dev/ttyUSB0',
'verbose': True,
'publish_novatel_positions': True,
'publish_novatel_velocity': True,
'publish_novatel_psrdop2': True,
'frame_id': '/gps'
}]
)
],
output='screen'
)
return LaunchDescription([container])
gps_common/GPSFix
messages will always be published, but by default, other message
types are not. See the config parameters for a list of which other message types can be
enabled.
novatel_gps_msgs
ROS messages that represent NovAtel message logs. Each supported log should have its own message type. A list of official log types can be found at http://docs.novatel.com/OEM7/Content/Logs/Log_Reference.htm .
novatel_gps_driver
A C++ library with an accompanying ROS node and node that can connect to a NovAtel device over a serial, TCP, or UDP connection and translate NovAtel logs into ROS messages.
novatel_gps_driver/novatel_gps_nodelet
connection_type
: Type of physical connection to the device
serial
, tcp
, udp
, or pcap
serial
device
: Location of device connection.
serial
connections, the device node; e. g., /dev/ttyUSB0
tcp
or udp
connections, a host:port
specification.
3001
will be used as the default for TCP connections
and 3002
as the default for UDP connections.pcap
connections, the location of a .pcap
capture file.
Note that the node will exit automatically after finishing playback.frame_id
: ROS TF frame to place in the header of published messages.
imu_frame_id
: TF frame id to use in IMU messages.
imu_rate
: Desired logging rate in Hz for IMU messages.
CORRIMUDATA
logs.100
imu_sample_rate
: Sample rate of the connected IMU. Normally this is automatically detected based on the IMU type.polling_period
: Desired period between GPS messages.
GPGGA
, GPRMC
, GPGSA
, BESTPOS
,
and BESTVEL
logs.0.05
(20 Hz)expected_rate
: Expected publish rate of GPS messages.
polling_period
parameter: 20.0
(20Hz)publish_clocksteering
: true
to publish novatel_gps_msgs/ClockSteering messages.
false
publish_diagnostics
: true
to publish node diagnostics.
true
publish_gpgsa
: true
to publish novatel_gps_msgs/Gpgsa messages.
false
publish_gpgsv
: true
to publish novatel_gps_msgs/Gpgsv messages.
false
publish_gphdt
: true
to publish novatel_gps_msgs/Gphdt messages.
false
publish_imu_messages
: true
to publish novatel_gps_msgs/NovatelCorrectedImuData, novatel_gps_msgs/Inspva,
novatel_gps_msgs/Inspvax, novatel_gps_msgs/Insstdev, and sensor_msgs/Imu messages.
false
publish_nmea_messages
: true
to publish novatel_gps_msgs/Gpgga and novatel_gps_msgs/Gprmc messages.
false
publish_novatel_dual_antenna_heading
: true
to publish novatel_gps_msgs/NovatelDualAntennaHeading messages.
false
publish_novatel_heading2
: true
to publish novatel_gps_msgs/Heading2 messages.
false
publish_novatel_positions
: true
to publish novatel_gps_msgs/NovatelPosition messages. Note that even if
this is false, these logs will always be requested from the receiver in order to generate gps_msgs/GPSFix
messages.
false
publish_novatel_psrdop2
: true
to publish novatel_gps_msgs/NovatelPsrdop2 messages. If set, the data from
these messages will be used to fill in the DoP values in gps_msgs/GPSFix
messages. Note that these messages
are only published when the values change, not at the standard polling rate.
false
publish_novatel_utm_positions
: true
to publish novatel_gps_msgs/NovatelUtmPosition messages.
false
publish_novatel_velocity
: true
to publish novatel_gps_msgs/NovatelVelocity messages. If set, the data
from these messages will be used to fill in the speed and track values in gps_msgs/GPSFix
messages.
false
publish_novatel_xyz_positions
: true
to publish novatel_gps_msgs/NovatelXYZ messages.
false
publish_range_messages
: true
to publish novatel_gps_msgs/Range messages.
false
publish_sync_diagnostic
: If true, publish a time Sync diagnostic.
publish_diagnostics
is false.true
publish_dual_antenna_diagnostic
: If true, publish diagnostics for the second antenna.
publish_diagnostics
is false.publish_novatel_dual_antenna_heading
publish_time_messages
: true
to publish novatel_gps_msgs/Time messages.
false
publish_trackstat
: true
to publish novatel_gps_msgs/Trackstat messages.
false
publish_invalid_gpsfix
: true
to publish the /gps
topic, even if the status of the GPS fix is STATUS_NO_FIX
.
false
reconnect_delay_s
: Second delay between reconnection attempts.
0.5
serial_baud
: Select the serial baud rate to be used in a serial connection.
115200
spam_frame_to_ros_frame
: Translate the SPAN coordinate frame to a ROS coordinate frame using the VEHICLEBODYROTATION and APPLYVEHICLEBODYROTATION commands.
false
use_binary_messages
: true
to request binary NovAtel logs, false
to request ASCII.
false
wait_for_sync
: true
in order to wait for both BESTPOS and BESTVEL messages to arrive before publishing
gps_msgs/GPSFix
messages. If this is false
, GPSFix messages will be published immediately when BESTPOS
messages are received, but a side effect is that the driver will often be unable to fill in the speed & track
fields. This has no effect if publish_novatel_velocity
is false
.
true
/gps_sync
(std_msgs/Time): (optional) Timestamped sync pulses from a DIO module.
These are used to improve the accuracy of the time stamps of the messages published./bestpos
(novatel_gps_msgs/NovatelPosition): BESTPOS logs/bestutm
(novatel_gps_msgs/NovatelUtmPosition): BESTUTM logs/bestvel
(novatel_gps_msgs/NovatelVelocity): BESTVEL logs/bestxyz
(novatel_gps_msgs/NovatelXYZ): BESTXYZ logs/clocksteering
(novatel_gps_msgs/ClockSteering): CLOCKSTEERING logs/corrimudata
(novatel_gps_msgs/NovatelCorrectedImuData): CORRIMUDATA logs/diagnostics
(diagnostic_msgs/DiagnosticArray): ROS diagnostics/dual_antenna_heading
(novatel_gps_msgs/NovatelDualAntennaHeading): DUALANTENNAHEADING logs/fix
(sensor_msgs/NavSatFix): GPSFix messages converted to NavSatFix messages/gpgga
(novatel_gps_msgs/Gpgga): GPGGA logs/gpgsa
(novatel_gps_msgs/Gpgsa): GPGSA logs/gpgsv
(novatel_gps_msgs/Gpgsv): GPGSV logs/gprmc
(novatel_gps_msgs/Gprmc): GPRMC logs/gps
(gps_msgs/GPSFix): Fixes produced by combining BESTVEL, PSRDOP2 and BESTPOS messages together
/heading2
(novatel_gps_msgs/NovatelHeadin2): HEADING2 logs/imu
(sensor_msgs/Imu): CORRIMUDATA logs converted to Imu messages/inspva
(novatel_gps_msgs/Inspva): INSPVA logs/inspvax
(novatel_gps_msgs/Inspvax): INSPVAX logs/insstdev
(novatel_gps_msgs/Insstdev): INSSTDEV logs/psrdop2
(novatel_gps_msgs/Psrdop2): PSRDOP2 logs/range
(novatel_gps_msgs/Range): RANGE logs/rosout
(rosgraph_msgs/Log): Console output/time
(novatel_gps_msgs/Time): TIME logs/trackstat
(novatel_gps_msgs/Trackstat): TRACKSTAT logsDo you need support for a new log type? Follow these steps:
novatel_gps_msgs
package.novatel_gps_driver
package that extends the novatel_gps_driver::MessageParser
class that
can parse the log and return the appropriate ROS message.
UniquePtr
s to messages because this is more efficient for intraprocess
communications. Some MessageParsers have to produce SharedPtr
s because multiple references to their messages are
kept for synchronization or other purposes. Choose the appropriate pointer type based on your needs and look at
other messages as examples.novatel_gps_driver::NovatelGps
class:
NovatelGps::ParseBinaryMessage
, NovatelGps::ParseNovatelSentence
,
or NovatelGps::ParseNmeaSentence
methods to use your parser to parse the new message type
and store it in the appropriate buffer.novatel_gps_driver::NovatelGpsNodelet
class:
NovatelGpsNodelet::CheckDeviceForData
to retrieve messages from
the appropriate buffer and publish them.novatel_gps_driver/tests/parser_tests.cpp
to test your parser.