Skip to content

Commit d758448

Browse files
committed
Rename KittiInput to GenericPointInput
1 parent c6280ef commit d758448

File tree

4 files changed

+60
-53
lines changed

4 files changed

+60
-53
lines changed

README.md

Lines changed: 50 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -39,33 +39,35 @@ Get PDF [here](https://arxiv.org/abs/2311.13976).
3939

4040
## Acknowledgement
4141

42-
The authors gratefully acknowledge funding by the Federal Office of Bundeswehr Equipment, Information Technology and In-Service Support (BAAINBw).
42+
The authors gratefully acknowledge funding by the Federal Office of Bundeswehr Equipment, Information Technology and
43+
In-Service Support (BAAINBw).
4344

4445
## Overview
46+
4547
- [Examples](#examples)
4648
- [Run it yourself](#run-it-yourself)
4749
- [1. Download Sensor Data](#1-download-sensor-data)
48-
- [1.1. SemanticKitti](#11-semantickitti)
49-
- [1.2. Rosbag of our test vehicle VW Touareg](#12-rosbag-of-our-test-vehicle-vw-touareg)
50+
- [1.1. SemanticKitti](#11-semantickitti)
51+
- [1.2. Rosbag of our test vehicle VW Touareg](#12-rosbag-of-our-test-vehicle-vw-touareg)
5052
- [2. Setup Environment](#2-setup-environment)
51-
- [2.1. Option: Docker + GUI (VNC)](#21-option-docker--gui-vnc)
52-
- [2.2. Option: Locally on Ubuntu 20.04 (Focal) and ROS Noetic](#22-option-locally-on-ubuntu-2004-focal-and-ros-noetic)
53+
- [2.1. Option: Docker + GUI (VNC)](#21-option-docker--gui-vnc)
54+
- [2.2. Option: Locally on Ubuntu 20.04 (Focal) and ROS Noetic](#22-option-locally-on-ubuntu-2004-focal-and-ros-noetic)
5355
- [3. Run Continuous Clustering](#3-run-continuous-clustering)
5456
- [Evaluation on SemanticKITTI Dataset](#evaluation-on-semantickitti-dataset)
55-
- [1. Evaluation Results](#1-evaluation-results)
56-
- [1.1. Clustering](#11-clustering)
57-
- [1.2. Ground Point Segmentation](#12-ground-point-segmentation)
58-
- [2. Get Ground Truth Labels](#2-get-ground-truth-labels)
59-
- [2.1. Option: Download pre-generated labels](#21-option-download-pre-generated-labels-fastest)
60-
- [2.2. Option: Generate with GUI & ROS setup](#22-option-generate-with-gui--ros-setup-assumes-prepared-ros-setup-see-above-useful-for-debugging-etc)
61-
- [2.3. Option: Generate without GUI or ROS within Minimal Docker Container](#23-option-generate-without-gui-or-ros-within-minimal-docker-container)
62-
- [3. Run Evaluation](#3-run-evaluation)
63-
- [3.1. Option: Evaluate with GUI & ROS setup](#31-option-evaluate-with-gui--ros-setup-assumes-prepared-ros-setup-useful-for-debugging)
64-
- [3.2. Option: Evaluate without GUI or ROS within Minimal Docker Container](#32-option-evaluate-without-gui-or-ros-within-minimal-docker-container)
57+
- [1. Evaluation Results](#1-evaluation-results)
58+
- [1.1. Clustering](#11-clustering)
59+
- [1.2. Ground Point Segmentation](#12-ground-point-segmentation)
60+
- [2. Get Ground Truth Labels](#2-get-ground-truth-labels)
61+
- [2.1. Option: Download pre-generated labels](#21-option-download-pre-generated-labels-fastest)
62+
- [2.2. Option: Generate with GUI & ROS setup](#22-option-generate-with-gui--ros-setup-assumes-prepared-ros-setup-see-above-useful-for-debugging-etc)
63+
- [2.3. Option: Generate without GUI or ROS within Minimal Docker Container](#23-option-generate-without-gui-or-ros-within-minimal-docker-container)
64+
- [3. Run Evaluation](#3-run-evaluation)
65+
- [3.1. Option: Evaluate with GUI & ROS setup](#31-option-evaluate-with-gui--ros-setup-assumes-prepared-ros-setup-useful-for-debugging)
66+
- [3.2. Option: Evaluate without GUI or ROS within Minimal Docker Container](#32-option-evaluate-without-gui-or-ros-within-minimal-docker-container)
6567
- [Info about our LiDAR Drivers](#info-about-our-lidar-drivers)
66-
- [Velodyne](#velodyne)
67-
- [Ouster](#ouster)
68-
- [Tips for Rviz Visualization](#tips-for-rviz-visualization)
68+
- [1. Velodyne](#1-velodyne)
69+
- [2. Ouster](#2-ouster)
70+
- [3. Generic Points](#3-generic-points)
6971
- [TODOs](#todos)
7072

7173
# Examples:
@@ -88,7 +90,7 @@ filtering potential fog points.
8890
## Works on German Highway
8991

9092
There are often no speed limits on the German Highway. So it is not uncommon to see cars with velocities of 180 km/h or
91-
much higher. A latency of e.g. 200ms leads to positional errors of `(180 / 3.6) m/s * 0.2s = 10m`. This shows the need
93+
much higher. A latency of e.g. 200ms leads to positional errors of `(180 / 3.6) m/s * 0.2s = 10m`. This shows the need
9294
to keep latencies at a minimum.
9395

9496
[![Video GIF](https://user-images.githubusercontent.com/74038190/235294007-de441046-823e-4eff-89bf-d4df52858b65.gif)](https://www.youtube.com/watch?v=DZKuAQBngNE&t=98s)
@@ -134,12 +136,16 @@ our [Google Drive](https://drive.google.com/file/d/1zM4xPRahgxdJXJGHNXYUpM_g4-9U
134136
environment variable `ROSBAG_PATH` accordingly: `export ROSBAG_PATH=/parent/folder/of/rosbag`
135137

136138
Available bags:
137-
- `gdown 1zM4xPRahgxdJXJGHNXYUpM_g4-9UrcwC` (3.9GB, [Manual Download](https://drive.google.com/file/d/1zM4xPRahgxdJXJGHNXYUpM_g4-9UrcwC/view?usp=sharing))
138-
- Long recording in urban scenario (no camera to reduce file size, no Ouster sensors)
139-
- `gdown 1qjCG6-nWBZ_2wJwoP80jj0gGopBT2c23` (2.4GB, [Manual Download](https://drive.google.com/file/d/1qjCG6-nWBZ_2wJwoP80jj0gGopBT2c23/view?usp=sharing))
140-
- Recording including Ouster 32 sensor data (blurred camera for privacy reasons)
141-
- `gdown 146IaBdEmkfBWdIgGV5HzrEYDTol84a1H` (0.7GB, [Manual Download](https://drive.google.com/file/d/146IaBdEmkfBWdIgGV5HzrEYDTol84a1H/view?usp=sharing))
142-
- Short recording of German Highway (blurred camera for privacy reasons)
139+
140+
- `gdown 1zM4xPRahgxdJXJGHNXYUpM_g4-9UrcwC` (
141+
3.9GB, [Manual Download](https://drive.google.com/file/d/1zM4xPRahgxdJXJGHNXYUpM_g4-9UrcwC/view?usp=sharing))
142+
- Long recording in urban scenario (no camera to reduce file size, no Ouster sensors)
143+
- `gdown 1qjCG6-nWBZ_2wJwoP80jj0gGopBT2c23` (
144+
2.4GB, [Manual Download](https://drive.google.com/file/d/1qjCG6-nWBZ_2wJwoP80jj0gGopBT2c23/view?usp=sharing))
145+
- Recording including Ouster 32 sensor data (blurred camera for privacy reasons)
146+
- `gdown 146IaBdEmkfBWdIgGV5HzrEYDTol84a1H` (
147+
0.7GB, [Manual Download](https://drive.google.com/file/d/146IaBdEmkfBWdIgGV5HzrEYDTol84a1H/view?usp=sharing))
148+
- Short recording of German Highway (blurred camera for privacy reasons)
143149

144150
## 2. Setup Environment
145151

@@ -193,12 +199,12 @@ roslaunch continuous_clustering demo_touareg.launch bag_file:=${ROSBAG_PATH}/vw_
193199
```
194200

195201
> [!Tip]
196-
> For the latter launch file, you can use `--wait_for_tf:=false` (default: `true`) argument. It controls whether to wait
197-
> for the transform from velodyne to fixed frame (e.g. odometry frame) with a timestamp larger than the one of the
198-
> firing or whether to use the latest available (probably incorrect) transform. The former is the accurate approach
199-
> (that's why it is the default) but the columns are published in larger batches/slices because they are accumulated
200-
> between two transforms. The size of a slice depends on the update rate of the transform (i.e. transforms with 50Hz
201-
> lead to batches/slices of 1/5 rotation for a LiDAR rotating with 10Hz). So for a nice visualization where the columns
202+
> For the latter launch file, you can use `--wait_for_tf:=false` (default: `true`) argument. It controls whether to wait
203+
> for the transform from velodyne to fixed frame (e.g. odometry frame) with a timestamp larger than the one of the
204+
> firing or whether to use the latest available (probably incorrect) transform. The former is the accurate approach
205+
> (that's why it is the default) but the columns are published in larger batches/slices because they are accumulated
206+
> between two transforms. The size of a slice depends on the update rate of the transform (i.e. transforms with 50Hz
207+
> lead to batches/slices of 1/5 rotation for a LiDAR rotating with 10Hz). So for a nice visualization where the columns
202208
> are published one by one like it the GIF at the top of the page you should disable this flag.
203209
204210
# Evaluation on SemanticKITTI Dataset
@@ -280,8 +286,8 @@ rosrun continuous_clustering gt_label_generator_tool ${KITTI_SEQUENCES_PATH} --n
280286
```
281287

282288
> [!TIP]
283-
> If you want to visualize the generated ground truth labels in an online fashion then remove the `--no-ros` flag and
284-
> use just one thread (default). You can then subscribe to the corresponding topic in Rviz and visualize the point
289+
> If you want to visualize the generated ground truth labels in an online fashion then remove the `--no-ros` flag and
290+
> use just one thread (default). You can then subscribe to the corresponding topic in Rviz and visualize the point
285291
> labels.
286292
287293
### 2.3. Option: Generate without GUI or ROS within Minimal Docker Container
@@ -326,18 +332,14 @@ docker run --rm -v ${KITTI_SEQUENCES_PATH}:/mnt/kitti_sequences --name build_no_
326332
docker stop build_no_ros
327333
```
328334

329-
# Tips for Rviz Visualization
330-
331-
TODO
332-
333335
# Info about our LiDAR Drivers
334336

335337
Our clustering algorithm is able to process the UDP packets from the LiDAR sensor. So the firings can be processed
336338
immediately. We directly process the raw UDP packets from the corresponding sensor, which makes the input
337339
manufacturer/sensor specific. Luckily, we can use external libraries, so it is not necessary reimplement the decoding
338340
part (UDP Packet -> Euclidean Point Positions). Currently, we support following sensor manufacturers:
339341

340-
## Velodyne
342+
## 1. Velodyne
341343

342344
- Tested Sensors: VLS 128
343345
- All other rotating Velodyne LiDARs should work, too
@@ -367,7 +369,7 @@ part (UDP Packet -> Euclidean Point Positions). Currently, we support following
367369
from [ros-drivers/velodyne](https://github.com/ros-drivers/velodyne) to decode packets to euclidean points
368370
- See source code at: [velodyne_input.hpp](include/continuous_clustering/ros/velodyne_input.hpp)
369371

370-
## Ouster
372+
## 2. Ouster
371373

372374
- Tested Sensors: OS 32
373375
- All other rotating Ouster LiDARs should work, too
@@ -379,7 +381,15 @@ part (UDP Packet -> Euclidean Point Positions). Currently, we support following
379381
from [ouster-lidar/ouster-ros](https://github.com/ouster-lidar/ouster-ros) to decode packets to euclidean points
380382
- See source code at: [ouster_input.hpp](include/continuous_clustering/ros/ouster_input.hpp)
381383

382-
## TODOs
384+
## 3. Generic Points
385+
386+
Alternatively, you can also launch the clustering with parameter `sensor_manufacturer:="generic_points"`. Then it
387+
subscribes to `<namespace>/raw_data` topic and expects `sensor_msgs::PointCloud2` messages, which should represent one
388+
firing. It has to be an organized point cloud with `width=1` and `height=<number-of-lasers>`. Required point fields are
389+
`x`, `y`, `z` (w.r.t. sensor origin), and `intensity`. Missing returns should be represented by `NaN`.
390+
See [launch/sensor_kitti.launch](launch/sensor_kitti.launch) for such an example.
391+
392+
# TODOs
383393

384394
- Port it to ROS2: planned soon
385395
- Add features:

include/continuous_clustering/ros/kitti_input.hpp renamed to include/continuous_clustering/ros/generic_points_input.hpp

Lines changed: 6 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
1-
#ifndef CONTINUOUS_CLUSTERING_KITTI_INPUT_HPP
2-
#define CONTINUOUS_CLUSTERING_KITTI_INPUT_HPP
1+
#ifndef CONTINUOUS_CLUSTERING_GENERIC_POINTS_INPUT_HPP
2+
#define CONTINUOUS_CLUSTERING_GENERIC_POINTS_INPUT_HPP
33

44
#include <ros/ros.h>
55
#include <sensor_msgs/PointCloud2.h>
@@ -10,10 +10,10 @@
1010
namespace continuous_clustering
1111
{
1212

13-
class KittiInput : public RosSensorInput<sensor_msgs::PointCloud2>
13+
class GenericPointsInput : public RosSensorInput<sensor_msgs::PointCloud2>
1414
{
1515
public:
16-
KittiInput(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private) : RosSensorInput(nh, nh_private)
16+
GenericPointsInput(const ros::NodeHandle& nh, const ros::NodeHandle& nh_private) : RosSensorInput(nh, nh_private)
1717
{
1818
}
1919

@@ -33,21 +33,18 @@ class KittiInput : public RosSensorInput<sensor_msgs::PointCloud2>
3333
sensor_msgs::PointCloud2ConstIterator<float> iter_y_in(*m, "y");
3434
sensor_msgs::PointCloud2ConstIterator<float> iter_z_in(*m, "z");
3535
sensor_msgs::PointCloud2ConstIterator<uint8_t> iter_intensity_in(*m, "intensity");
36-
sensor_msgs::PointCloud2ConstIterator<double> iter_kitti_index_in(*m, "original_kitti_index");
3736

3837
int row_index = 0;
3938
uint64_t stamp = m->header.stamp.toNSec();
40-
for (; iter_x_in != iter_x_in.end();
41-
++iter_x_in, ++iter_y_in, ++iter_z_in, ++iter_intensity_in, ++iter_kitti_index_in, ++row_index)
39+
for (; iter_x_in != iter_x_in.end(); ++iter_x_in, ++iter_y_in, ++iter_z_in, ++iter_intensity_in, ++row_index)
4240
{
4341
current_firing->points[row_index].stamp = stamp;
4442
current_firing->points[row_index].firing_index = firing_index;
4543
current_firing->points[row_index].x = *iter_x_in;
4644
current_firing->points[row_index].y = *iter_y_in;
4745
current_firing->points[row_index].z = *iter_z_in;
4846
current_firing->points[row_index].intensity = static_cast<uint8_t>(*iter_intensity_in * 255);
49-
current_firing->points[row_index].globally_unique_point_index =
50-
*(reinterpret_cast<const uint64_t*>(&(*iter_kitti_index_in))); // PointCloud2 does not support UINT64
47+
current_firing->points[row_index].globally_unique_point_index = 0; // only required for evaluation
5148
}
5249

5350
keepTrackOfMinAndMaxStamp(stamp); // same for firing -> enough to call once

launch/sensor_kitti.launch

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
<arg name="use_rviz" default="true" doc="whether to start rviz"/>
44

55
<!-- lidar sensor -->
6-
<arg name="sensor_manufacturer" default="kitti"/>
6+
<arg name="sensor_manufacturer" default="generic_points"/>
77
<arg name="sensor_model" default="kitti"/>
88
<arg name="sensor_position" default="roof"/>
99
<arg name="sensor_frame" default="velo_link"/>

src/ros/continuous_clustering_node.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
#include <continuous_clustering/ContinuousClusteringConfig.h>
2-
#include <continuous_clustering/ros/kitti_input.hpp>
2+
#include <continuous_clustering/ros/generic_points_input.hpp>
33
#include <continuous_clustering/ros/ouster_input.hpp>
44
#include <continuous_clustering/ros/ros_transform_synchronizer.hpp>
55
#include <continuous_clustering/ros/ros_utils.hpp>
@@ -42,8 +42,8 @@ class RosContinuousClustering
4242
sensor_input_.reset(new VelodyneInput(nh, nh_private));
4343
else if (sensor_manufacturer == "ouster")
4444
sensor_input_.reset(new OusterInput(nh, nh_private));
45-
else if (sensor_manufacturer == "kitti")
46-
sensor_input_.reset(new KittiInput(nh, nh_private));
45+
else if (sensor_manufacturer == "generic_points")
46+
sensor_input_.reset(new GenericPointsInput(nh, nh_private));
4747
else
4848
throw std::runtime_error("Unknown manufacturer: " + sensor_manufacturer);
4949
sensor_input_->subscribe();

0 commit comments

Comments
 (0)