Skip to main content
Version: ROS 2 Humble

GPS Receivers

GPS receivers are all devices that publish a sensor_msgs/NavSatFix message, which provides a latitude and longitude position.

SwiftNav Duro

gps:
- model: swiftnav_duro
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
duro_node:
gps_receiver_frame_id: gps_0_link
ip_address: 192.168.131.30
ip_port: 55555
imu_frame_id: gps_0_link

Package and Setup

The SwiftNav Duro uses the duro_gps_driver ROS 2 driver. The driver is open source, maintained by the autonomous vehicle development team of Széchenyi University, and hosted on GitHub.

The duro_gps_driver and its dependency libsbp, the Swift binary protocol libray, must be built from source.

Build and install the libsbp:


# Install build dependencies.
sudo apt-get install build-essential pkg-config cmake doxygen check
# Clone driver to home directory
cd ~
git clone https://github.com/swift-nav/libsbp.git
# Checkout latest supported branch
cd libsbp
git checkout e149901e63ddcdb0d818adcd8f8e4dbd0e2738d6
# Update submodules
cd c
git submodule update --init --recursive
# Build and install
mkdir build; cd build
cmake ../
make
sudo make install

Build the duro_gps_driver in the ROS workspace.


# Clone driver to source directory
cd ~/colcon_ws/src
git clone https://github.com/szenergy/duro_gps_driver -b ros2-humble
# Build the driver
cd ~/colcon_ws
colcon build --packages-select duro_gps_driver

For specifics on the way Clearpath's configuration system launches the duro_gps_driver, see the SwiftNav Duro launch file and the default parameter file in clearpath_sensors.

Garmin 18X

gps:
- model: garmin_18x
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: "/dev/clearpath/gps"
baud: 115200

Package and Setup

The Garmin 18x GPS sensor uses the nmea_navsat_driver ROS 2 driver. The driver is open source, maintained by the community, and hosted on GitHub.

For specifics on the way Clearpath's configuration system launches the sensor driver, see the Garmin 18x launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the Garmin 18x. To simplify this process, use the /dev/clearpath/gps path. This path is only available when the Clearpath robot UDEV rules are installed. These are installed alongside the clearpath_robot package. If the receiver is connected, but the /dev/clearpath/gps device is not, check the file /lib/udev/rules.d/60-ros-humble-clearpath-robot.rules exists.

Novatel Smart6

gps:
- model: novatel_smart6
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: "/dev/clearpath/gps"
baud: 115200

Package and Setup

The Novatel Smart6 GNSS antenna uses the nmea_navsat_driver ROS 2 driver. The driver is open source, maintained by the community, and hosted on GitHub.

For specifics on the way Clearpath's configuration system launches the sensor driver, see the Novatel Smart6 launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the Novatel Smart6. To simplify this process, use the /dev/clearpath/gps path. This path is only available when the Clearpath robot UDEV rules are installed. These are installed alongside the clearpath_robot package. If the receiver is connected, but the /dev/clearpath/gps device is not, check the file /lib/udev/rules.d/60-ros-humble-clearpath-robot.rules exists.

Novatel Smart7

gps:
- model: novatel_smart7
urdf_enabled: true
launch_enabled: true
parent: base_link
xyz: [0.0, 0.0, 0.0]
rpy: [0.0, 0.0, 0.0]
ros_parameters:
nmea_navsat_driver:
frame_id: gps_0_link
port: "/dev/clearpath/gps"
baud: 115200

Package and Setup

The Novatel Smart7 GNSS antenna uses the nmea_navsat_driver ROS 2 driver. The driver is open source, maintained by the community, and hosted on GitHub.

For specifics on the way Clearpath's configuration system launches the sensor driver, see the Navsat Smart7 launch file and the default parameter file in clearpath_sensors.

Device Path

The port ROS parameter must be set to the device path of the Novatel Smart7. To simplify this process, use the /dev/clearpath/gps path. This path is only available when the Clearpath robot UDEV rules are installed. These are installed alongside the clearpath_robot package. If the receiver is connected, but the /dev/clearpath/gps device is not, check the file /lib/udev/rules.d/60-ros-humble-clearpath-robot.rules exists.