cmpute / pcl.py

Templated python inferface for Point Cloud Library (PCL) based on Cython
BSD 3-Clause "New" or "Revised" License
71 stars 15 forks source link
computer-vision numpy pcl point-cloud python

pcl.py

Build Status PyPI - Python Version

Cython bindings of Point Cloud Library (PCL)

Principles

Target for this library if to implement an easy-to-use cython API to the PCL (Point Cloud Library), combined with scipy and numpy. This library wraps pcl::PCLPointCloud2 class into python (using structured NumPy array) and users can pass data from numpy to PointCloud<PointT> easily with this library and headers.

Nevertheless, this library focuses on simplicity, readability and accessibility, the heavily templatized part of original PCL is not implemented in this library due to the limitation of cython. However, the templated cython headers are added and you can still write this part of code in C++ and then wrap the input and output in python easily with this library.

Interface

The major classes in this library are pcl.PointCloud, pcl.Visualizer. Most methods from C++ library are directly wrapped into Python, while methods with get and set prefix are changed into Python object properties.

Since Cython doesn't support a template technique similar to "covariant" in its template support, so the code which need this technique is not wrapped or header-provided as stated above.

Cython files are organized in the same structure as C++ library, which means the code you write in cython can be easily transferred to C++

Advantage over python-pcl and pclpy


Compatibility

Installation


Basic Usage

Simple examples

import pcl
import numpy as np

cloud = pcl.PointCloud([(1,2,3), (4,5,6)])
# <PointCloud of 2 points>

cloud.ptype
# 'XYZ'

array = cloud.to_ndarray()  # zero-copy!
# array([(1., 2., 3.), (4., 5., 6.)],
#       dtype={'names':['x','y','z'], 'formats':['<f4','<f4','<f4'], 'offsets':[0,4,8], 'itemsize':16})

cloud.xyz[0] = (3, 2, 1)  # access and modify coordinates by .xyz
cloud.xyz
# array([[3., 2., 1.],
#        [4., 5., 6.]], dtype=float32)

import pandas as pd
pd.DataFrame(cloud)
#                  0
# 0  [1.0, 2.0, 3.0]
# 1  [4.0, 5.0, 6.0]

pd.DataFrame(cloud.to_ndarray())
#      x    y    z
# 0  1.0  2.0  3.0
# 1  4.0  5.0  6.0

random_cloud = pcl.create_xyz(np.random.rand(10000, 3))
# <PointCloud of 10000 points>

from pcl.visualization import Visualizer, RenderingProperties
vis = Visualizer()  # create a point cloud visualizer and open a window
vis.addPointCloud(random_cloud, id="some_id")  # add the point cloud with a given identifier
vis.setPointCloudRenderingProperties(RenderingProperties.PointSize, 2, id="some_id")  # modify its rendering property
vis.spin()  # update the contents in the window and show the cloud

The final statement will show following window

Random point cloud shown in a PCL Visualizer

*Please check test codes for more usage examples and typing files (.pyi files such as PointCloud.pyi) for the complete list of API.**

Commonly-used APIs

ROS integration

Use the integration with ROS is as simple as cloud = pcl.PointCloud(msg) and msg = cloud.to_msg(). To build the PointCloud from a message object, the message doesn't need to have the exact sensor_msgs.msg.PointCloud2 type, rather it can have any type with proper fields defined. This is convenient when you receive messages from other machines and ROS sometimes will generate anonymous type to deserialized the data.

Common incorrect usages