gokulp01 / ros2-ublox-zedf9p

ROS2 drivers for U-blox ZED F9P
31 stars 13 forks source link
gnss gps gps-driver ros-driver ros2 ros2-foxy ros2-galactic ublox ublox-gps ublox-gps-driver ublox-gps-modules

Description

This package provides ROS2 support for u-blox ZED F9P GPS receivers. Most of this driver has been written based off the original ROS(1) driver that can be found here. Changes made to support the latest firmware are listed below:

Features:

Supports:

- Ubuntu 20.04 (Tested)
- Ubuntu 22.04 (Untested)
- ROS2 Foxy and ROS2 Galactic (Tested)
- ROS2 Humble (Untested)
- Colcon
- Firmware 9

Note: This driver has to be installed locally:

mkdir -p ublox_ws/src
cd ublox_ws/src
git clone https://github.com/gokulp01/ros2-ublox-zedf9p.git
cd ..
colcon build

To run the driver:

ros2 launch ublox_gps ublox_gps_node_zedf9p-launch.py

Note: Values are published on /fix topic

alt text alt text

Some common errors and how to fix them (this list will be updated as and when new issues are raised).

  1. Could NOT find asio (missing: ASIO_INCLUDE_DIR): To fix it, install the asio package on your system.

    sudo apt-get install libasio-dev Source and build again.

Options

The ublox_gps node supports the following parameters for all products and firmware versions:

For UDR/ADR devices:

For HPG Reference devices:

For HPG Rover devices:

For TIM devices:

For FTS devices:

Fix Topics

~fix(sensor_msgs/NavSatFix)

Navigation Satellite fix.

~fix_velocity(geometry_msgs/TwistWithCovarianceStamped)

Velocity in local ENU frame.

INF messages

To enable printing INF messages to the ROS console, set the parameters below.

Additional Topics

To publish a given u-blox message to a ROS topic, set the parameter shown below to true. The node sets the rate of the u-blox messages to 1 measurement cycle.

All messages

AID messages

RXM messages

MON messages

NAV messages

ESF messages

HNR messages

TIM messages

Adding new parameters

  1. Modify the getRosParams() method in the appropriate implementation of ComponentInterface (e.g. UbloxNode, UbloxFirmware8, HpgRefProduct, etc.) and get the parameter. Group multiple related parameters into a namespace. Use all lower case names for parameters and namespaces separated with underscores.
    • If the type is an unsigned integer (of any size) or vector of unsigned integers, use the ublox_node::getRosUint method which will verify the bounds of the parameter.
    • If the type is an int8 or int16 or vector of int8's or int16's, use the ublox_nod::getRosInt method which will verify the bounds of the parameter. (This method can also be used for int32's but ROS has methods to get int32 parameters as well).
  2. If the parameter is used during configuration also modify the ComponentInterface's configureUblox() method to send the appropriate configuration message. Do not send configuration messages in getRosParams().
  3. Modify this README file and add the parameter name and description in the appropriate section. State whether there is a default value or if the parameter is required.
  4. Modify one of the sample .yaml configuration files in ublox_gps/config to include the parameter or add a new sample .yaml for your device.

Debugging

For debugging messages set the debug parameter to > 0. The range for debug is 0-4. At level 1 it prints configuration messages and checksum errors, at level 2 it also prints ACK/NACK messages and sent messages. At level 3 it prints the received bytes being decoded by a specific message reader. At level 4 it prints the incoming buffer before it is split by message header.

Links

Consult the official protocol spec for details on packets supported by u-blox devices.