Fixposition ROS Driver
Introduction
The Fixposition ROS driver is designed to listen on a TCP or Serial port for the Fixposition I/O Messages, parse them, and then publish them as corresponding ROS messages. At the same time, the driver can subscribe to a speed input stream, which will be sent back to the Vision-RTK 2 sensor and provide an external speed input. Similarly, the user can send RTCM3 messages via the ROS driver to provide RTK corrections to the device without the need of an NTRIP client or establishing an additional connection.
For the output ROS messages, see this page.
For the input ROS messages for speed input, see Input Wheelspeed through the driver.
Supported versions
ROS1 Noetic
ROS2 Humble / Jazzy
ROS (both ROS1 and ROS2) Driver for Fixposition Vision-RTK 2.
The latest version of the ROS driver (tag 7.0.3) is only compatible with FW2.85.3 onward. For previous releases (e.g., FW2.77.2), please use tag 6.2.1. For a more complete compatibility list, please refer to Current software version.
The user must recompile the repository after every update (i.e., git pull). Sometimes, it might be necessary to clean the environment (i.e., remove /devel, /logs, and /install folders).
How to use it
The code is split in the following 3 parts:
fixposition_driver_lib
: common CMake library to parse Fixposition ASCII Messages. For more details and build instructions, see here.fixposition_driver_ros1
: ROS1 driver node to subscribe and publish in the ROS1 framework. For more details and build instructions, see here.fixposition_driver_ros2
: ROS2 driver node to subscribe and publish in the ROS2 framework. For more details and build instructions, see here.
For details on how to install or use the Fixposition ROS driver, please refer to Installation and usage.
Available ROS topics
Topic | Required I/O message | Message type | Rate |
---|---|---|---|
FP_A topics | |||
|
| 10 Hz * | |
|
| 10 Hz * | |
|
| 10 Hz * | |
|
| 10 Hz * | |
|
| 1 Hz | |
|
| 1 Hz | |
|
| - | |
|
| 1 Hz | |
|
| 10 Hz * | |
|
| 1 Hz | |
|
| 5 Hz (GNSS) 10 Hz * (Fusion) | |
NMEA topics | |||
| Multiple |
| 5 Hz |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
|
| 5 Hz | |
ROS-type topics | |||
|
| 10 Hz * | |
|
| 10 Hz * | |
|
| 10 Hz * | |
|
| 10 Hz * | |
Orientation topics | |||
|
| 10 Hz * | |
|
| 10 Hz * | |
IMU topics | |||
|
| 200 Hz | |
|
| 200 Hz | |
|
| 10 Hz * | |
GNSS topics | |||
|
| 5 Hz | |
|
| 5 Hz | |
Warning topics | |||
|
| 10 Hz * |
The '/fixposition/nmea' topic collects and combines all NMEA messages and outputs at the end of the GNSS epoch.
(*) Default value. Can be configured on the Web Interface.
By default, the ENU output is disabled even if the message is enabled on the I/O port. First, you must configure the ENU output reference frame in the 'Output generators' field of the Web Interface. See FP_A-ODOMENU for more information.
Additional information
Topic | Description |
---|---|
| Collects and combines all NMEA messages and outputs at the end of the GNSS epoch. From NMEA-GP-GGA_GNSS, NMEA-GP-RMC_GNSS, and NMEA-GP-ZDA_GNSS, at the configured frequency (default 5Hz): The Vision-RTK2 can also output an average GNSS-based LLH position (i.e., only GNSS, not Fusion) and heading estimate based on speed over ground (SOG) and course over ground (COG) - (i.e., the platform must be moving for it to be accurate) by utilizing several NMEA messages, which serves as an auxiliary output until Fusion is fully initialized. This message's output frequency equals the lowest frequency of any of these three message types. Note: This output should only be used until Fusion is fully initialized. Warning: This topic will only be populated when the sampling rate of all required NMEA messages is 1 (i.e., the default output frequency of the messages). |
| Position, Orientation from ECEF to FP_POI, Velocity and Angular Velocity in FP_POI. |
| Position from LLH (Latitude, Longitude and Height) to FP_POI. Based on WGS-84 ellipsoid. |
| Position, Orientation from ENU0 to FP_POI, Velocity and Angular Velocity in FP_POI. |
| Position, Orientation from ECEF to FP_POISH, Velocity and Angular Velocity in FP_POI. Based on smooth odometry output. |
| Bias Corrected acceleration and rotation rate in FP_POI. |
| x = Yaw, y = Pitch, z = Roll in radian. Euler angles representation of rotation between ENU and FP_POI. Only available after fusion initialization. |
| Latitude, Longitude and Height at the configured frequency, GNSS1 raw antenna position. |
| Latitude, Longitude and Height at the configured frequency, GNSS2 raw antenna position. |
| Raw (without bias correction) IMU acceleration and angular velocity data in FP_VRTK frame |
| Bias Corrected IMU acceleration and angular velocity data in FP_VRTK frame |
| x = 0.0, y = Pitch, z = Roll in radian. Euler angles representation of rotation between a local horizontal frame and P_POI. Rough estimation using IMU alone. |
| Optional warning if the change in position is greater than the estimated covariances. To enable this topic, change the ‘cov_warning’ field in the roslaunch configuration YAML file to ‘true’. |
ROS TF Tree
Explaination of frame ids
Frame ID | Explaination |
---|---|
FP_ECEF | Earth-Center-Earth-Fixed frame. |
FP_POI | Point-Of-Interest, configured from Vision-RTK2's web-interface with respect to the FP_VRTK frame. By default it is the same as FP_VRTK. |
FP_ENU0 | The global fixed East-North-Up coordinate frame with the origin at the configured ENU0 position on the web-interface. Also used as the MAP frame for Rviz. |
FP_POISH | Point-Of-Interest of the Smooth Odometry frame, configured from Vision-RTK2's web-interface with respect to the FP_VRTK frame. |
FP_IMUH | A local horizontal frame with the origin at the same location as FP_POI. This frame is a rough estimate determined by the IMU alone. |
FP_VRTK | The coordinate frame on the Vision-RTK2's housing on the Fixposition-Logo "X". |
FP_CAM | The camera coordinate frame of the Vision-RTK2. |
Enabling TF frames
To enable the desired transformation in the TF tree, the corresponding messages also has to be selected on the Fixposition Vision-RTK2's configuration interface. For more information, refer to the following table:
Frames | Topic | Required I/O message | Frequency |
---|---|---|---|
|
| 10 Hz * | |
|
| 1 Hz | |
|
| 10 Hz * | |
|
| 200 Hz | |
|
| 1 Hz | |
|
| 1 Hz |
Input Wheelspeed through the driver
The fp_ros_driver supports inputting a Speed msg (msg/Speed.msg
) through the /fixposition/speed
topic. The Speed msg is defined as a vector of WheelSensor msgs (msg/WheelSensor.msg
). This message in turn, is intended to be a simplified version of the FP_B-MEASUREMENTS, containing three integers (vx, vy, and vz), three booleans (validity of the three velocity integers), and a string indicating the sensor from which the measurement originates. The integer velocity values should be in [mm/s], to have enough precision when being converted into an integer format.
Internally, upon arriving to the ros driver, wheelspeed measurements are converted into a full FP_B-MEASUREMENTS message, and sent via the TCP or serial interface to the Vision-RTK2, where they will be further processed. For more details regarding the definition FP_B-MEASUREMENTS message, please refer to https://docs.fixposition.com/fd/fp_b-measurements, or to the Vision-RTK2 Integration manual.
Fixposition Odometry Converter
This is an extra node is provided to help with the integration of the wheel odometry on your vehicle. For details, see the subfolder fixposition_odometry_converter_ros1 (ROS 1) and fixposition_odometry_converter_ros2 (ROS 2). When building the ROS 1 version add a file named 'CATKIN_IGNORE' to the fixposition_odometry_converter_ros2
folder.
Streaming RTCM3 messages / RTK corrections
To stream RTCM3 messages to the Vision-RTK2 using the ROS driver, we suggest following the steps detailed in How to send RTCM3 messages / RTK corrections via ROS.