Analyze large datasets of point clouds recorded over time in an efficient way.
- Handles point clouds over time
- Directly read ROS files and many pointcloud file formats.
- Generate a dataset from multiple pointclouds. For example from thousands of .las files.
- Building complex pipelines with a clean and maintainable code
newpointcloud = pointcloud.limit("x",-5,5).filter("quantile","reflectivity", ">",0.5)- Apply arbitrary functions to datasets of point clouds
def isolate_target(frame: PointCloud) -> PointCloud:
return frame.limit("x",0,1).limit("y",0,1)
def diff_to_pointcloud(pointcloud: PointCloud, to_compare: PointCloud) -> PointCloud:
return pointcloud.diff("pointcloud", to_compare)
result = dataset.apply(isolate_target).apply(diff_to_pointcloud, to_compare=dataset[0])- Includes powerful aggregation method agg similar to pandas
dataset.agg(["min","max","mean","std"])- Support for large files with lazy evaluation and parallel processing
- Support for numerical data per point (intensity, range, noise …)
- Interactive 3D visualisation
- High level processing based on dask, pandas, scipy, scikit-learn
- Docker image is available
- Optimised - but not limited to - automotive lidar
- A command line tool to convert ROS 1 & 2 files
- Post processing and analytics of a lidar dataset recorded by ROS
- A collection of multiple lidar scans from a terrestrial laser scanner
- Comparison of multiple point clouds to a ground truth
- Analytics of point clouds over time
- Developing algorithms on a single frame and then applying them to huge datasets
Install python package with pip:
pip install pointcloudsetThe easiest way to get started is to use the pre-build docker tgoelles/pointcloudset.
Reading ROS1 or ROS2 files:
import pointcloudset as pcs
from pathlib import Path
import urllib.request
urllib.request.urlretrieve(
"https://github.com/virtual-vehicle/pointcloudset/raw/master/tests/testdata/test.bag", "test.bag"
)
dataset = pcs.Dataset.from_file(Path("test.bag"), topic="/os1_cloud_node/points", keep_zeros=False)
pointcloud = dataset[1]
pointcloud.plot("x", hover_data=True)You can also generate a dataset from multiple pointclouds from formats like las, pcd, csv, and xyz.
PointCloud.to_file(...) currently writes csv, xyz, las, and pcd.
For text formats, csv defaults to writing a header and also supports header=False;
xyz defaults to headerless output and also supports header=True.
When reading files, PointCloud.from_file(...) supports normalize_xyz (default False).
If a file uses uppercase coordinate headers X, Y, Z, reading fails unless you pass normalize_xyz=True.
This makes the conversion explicit while keeping internal processing consistent with lowercase x, y, z.
import pointcloudset as pcs
from pathlib import Path
import urllib.request
urllib.request.urlretrieve(
"https://github.com/virtual-vehicle/pointcloudset/raw/master/tests/testdata/las_files/test_tree.las",
"test_tree.las",
)
urllib.request.urlretrieve(
"https://github.com/virtual-vehicle/pointcloudset/raw/master/tests/testdata/pcd_files/test_tree.pcd",
"test_tree.pcd",
)
las_pc = pcs.PointCloud.from_file(Path("test_tree.las"), normalize_xyz=True)
pcd_pc = pcs.PointCloud.from_file(Path("test_tree.pcd"))
dataset = pcs.Dataset.from_instance("pointclouds", [las_pc, pcd_pc])
pointcloud = dataset[1]
pointcloud.plot("z", hover_data=True)- Read the html documentation.
- Have a look at the tutorial notebooks in the documentation folder
- For even more usage examples you can have a look at the tests
The package includes a CLI to convert pointclouds in ROS1 and ROS2 files into pointcloudset directories or native file formats.
It currently writes csv, xyz, las, and pcd files and handles both mcap and db3 ROS2 inputs.
pointcloudset convert test.bag --output-format las --output-dir converted_lasYou can view PointCloud2 messages with
pointcloudset topics test.bagTipp: If you have uv installed you can simply run:
uvx pointcloudset --help- ROS - bagfiles can contain many point clouds from different sensors. The downside of the format is that it is only suitable for serial access and not well suited for data analytics and post processing.
- pyntcloud - Only for single point clouds. This package is used as the basis for the PointCloud object. Last update in 2022, and the project seems to be inactive. Pointcloudset has removed the dependency on pyntcloud.
- open3d - Only for single point clouds.
- pdal - Works also with pipelines on point clouds but is mostly focused on single point cloud processing. Pointcloudset is purely in python and based on pandas DataFrames. In addition pointcloudset works in parallel to process large datasets.

Please cite our JOSS paper if you use pointcloudset.
@article{Goelles2021,
doi = {10.21105/joss.03471},
url = {https://doi.org/10.21105/joss.03471},
year = {2021},
publisher = {The Open Journal},
volume = {6},
number = {65},
pages = {3471},
author = {Thomas Goelles and Birgit Schlager and Stefan Muckenhuber and Sarah Haas and Tobias Hammer},
title = {`pointcloudset`: Efficient Analysis of Large Datasets of Point Clouds Recorded Over Time},
journal = {Journal of Open Source Software}
}

