This package implements a ROS 2 node that wraps the GSeg3D ground segmentation algorithm and exposes it as a real-time perception component for robotic systems.
The node subscribes to LiDAR point clouds (optionally synchronized with IMU data), performs two-phase grid-based ground segmentation, and publishes ground and obstacle point clouds for downstream navigation and perception modules.
You can watch a video of GSeg3D's segmentation results on various datasets at the following link.
The node:
- Receives a
sensor_msgs/PointCloud2input - Optionally fuses IMU orientation for gravity alignment
- Applies GSeg3D Phase I (coarse) and Phase II (refinement) segmentation
- Publishes:
- Ground points
- Obstacle (non-ground) points
- Raw filtered input cloud
| Topic | Type | Description |
|---|---|---|
/ground_segmentation/input_pointcloud |
sensor_msgs/msg/PointCloud2 |
Input LiDAR point cloud |
/ground_segmentation/input_imu |
sensor_msgs/msg/Imu |
IMU orientation (optional) |
IMU synchronization is enabled via the parameter use_imu_orientation.
| Topic | Type | Description |
|---|---|---|
/ground_segmentation/ground_points |
sensor_msgs/msg/PointCloud2 |
Segmented ground points |
/ground_segmentation/obstacle_points |
sensor_msgs/msg/PointCloud2 |
Segmented non-ground points |
/ground_segmentation/raw_points |
sensor_msgs/msg/PointCloud2 |
Filtered input cloud |
-
Input Filtering
- ROI cropping (min/max X, Y, Z)
- Optional voxel downsampling
-
Synthetic Ground Injection
- Injects a ground seed beneath the robot
- Ensures reliable ground region initialization
-
Frame Alignment
- Transforms point cloud into
robot_frame - Uses TF2 for frame lookup
- Uses IMU data (if enabled) to compute gravity-aligned orientation
- Transforms point cloud into
-
Two-Phase Ground Segmentation
- Phase I: Coarse grid segmentation (large Z resolution)
- Phase II: Fine grid refinement (small Z resolution)
-
Post-Processing
- Radius-based filtering around the robot
- Final ground / obstacle separation
-
Publishing
- Results published as ROS 2 PointCloud2 messages
| Parameter | Description |
|---|---|
robot_frame |
Target frame for segmentation |
use_imu_orientation |
Enable IMU-based gravity alignment |
cellSizeX, cellSizeY, cellSizeZ |
Grid resolution (Phase I) (m) |
cellSizeZPhase2 |
Grid resolution in z (Phase II) (m) |
slopeThresholdDegrees |
Max slope for ground (degrees). Controls which planes are considered drivable. |
groundInlierThreshold |
Plane fitting inlier threshold (m). Controls how far points may lie from the estimated plane. |
centroidSearchRadius |
KD-tree expansion radius (m) |
lidar_to_ground |
Lidar to ground distance (m) |
transform_tolerance |
Tolerance for fetching transforms from TF (sec) |
show_benchmark |
Enable precision/recall evaluation |
maxGroundHeightDeviation |
Controls allowed centroid height difference in meters during phase 2 expansion. |
OS: Ubuntu 22.04, Ubuntu 24.04
ROS2: Humble, Jazzy
Before building the ROS 2 wrapper, install dependencies and clone the core ground_segmentation library into your ROS 2 workspace:
sudo apt update
sudo apt install cmake libpcl-dev libeigen3-dev libgtest-dev libnanoflann-dev openjdk-17-jremkdir -p ~/ros2_ws/src && cd ~/ros2_ws/src
git clone git@github.com:dfki-ric/ground_segmentation.gitClone the wrapper into your ROS 2 workspace src folder and build it:
cd ~/ros2_ws/src
git clone git@github.com:dfki-ric/ground_segmentation_ros2.git
cd ~/ros2_ws && source /opt/ros/YOUR_ROS_DISTRO/setup.bash
colcon build --packages-up-to ground_segmentation_ros2 --cmake-args -DCMAKE_BUILD_TYPE=RELEASE
source install/setup.bashAfter building the package, launch the ground segmentation node using the provided ROS 2 launch file.
Note:
- Launch argument
imu_topicis optional and is used only when parameteruse_imu_orientationis true. - If launch file crashes due to a jwt or jvm error then apply fix mentioned here
ros2 launch ground_segmentation_ros2 ground_segmentation.launch.py \
pointcloud_topic:=<POINTCLOUD_TOPIC> \
imu_topic:=<IMU_TOPIC> \
sim:=<true/false>Replace <POINTCLOUD_TOPIC> and <IMU_TOPIC> with the topics published by your LiDAR and IMU drivers.
sim (boolean)
Controls whether simulation time is used.
Behavior:
true→ uses/clock(simulation or bag playback)false→ uses system wall-clock time
Example:
sim:=true- Parameters are loaded from:
ground_segmentation_ros2/config/parameters.yaml - Topic remapping is handled at launch time, allowing the node to remain independent of sensor-specific topic names.
On some systems, the node may fail to start with:
error while loading shared libraries: libjawt.so: cannot open shared object file
Ensure the JVM libraries are discoverable
Option A (recommended for local development):
export JAVA_HOME=$(dirname $(dirname $(readlink -f $(which javac))))
export LD_LIBRARY_PATH=$JAVA_HOME/lib:$JAVA_HOME/lib/server:$LD_LIBRARY_PATH
Option B (system-wide configuration):
export JAVA_HOME=$(dirname $(dirname $(readlink -f $(which javac))))
echo "$JAVA_HOME/lib" | sudo tee /etc/ld.so.conf.d/java.conf
echo "$JAVA_HOME/lib/server" | sudo tee -a /etc/ld.so.conf.d/java.conf
sudo ldconfig
When show_benchmark=true:
- Runtime statistics are printed to console
- Real-time ground segmentation for mobile robots
- Safety-critical navigation and obstacle detection
- Traversability analysis
- Research
- Requires a valid TF tree between sensor, IMU, and robot frames
- Designed for CPU real-time execution
BSD-3 Clause License.
If you use this work, please cite:
Muhammad Haider Khan Lodhi and Christoph Hertzberg, "GSeg3D: A High-Precision Grid-Based Algorithm for Safety-Critical Ground Segmentation in LiDAR Point Clouds" in 2025 7th International Conference on Robotics and Computer Vision (ICRCV), pp. 119-126, 2025. doi: 10.1109/ICRCV67407.2025.11349133
© DFKI Robotics Innovation Center