Introduction
This is a small python binding to the pointcloud library. Currently, the following parts of the API are wrapped (all methods operate on PointXYZ) point types
- I/O and integration; saving and loading PCD files
- segmentation
- SAC
- smoothing
- filtering
- registration (ICP, GICP, ICP_NL)
The code tries to follow the Point Cloud API, and also provides helper function for interacting with NumPy. For example (from tests/test.py)
import pcl
import numpy as np
p = pcl.PointCloud(np.array([[1, 2, 3], [3, 4, 5]], dtype=np.float32))
seg = p.make_segmenter()
seg.set_model_type(pcl.SACMODEL_PLANE)
seg.set_method_type(pcl.SAC_RANSAC)
indices, model = seg.segment()
or, for smoothing
import pcl
p = pcl.load("C/table_scene_lms400.pcd")
fil = p.make_statistical_outlier_filter()
fil.set_mean_k (50)
fil.set_std_dev_mul_thresh (1.0)
fil.filter().to_file("inliers.pcd")
Point clouds can be viewed as NumPy arrays, so modifying them is possible using all the familiar NumPy functionality:
import numpy as np
import pcl
p = pcl.PointCloud(10) # "empty" point cloud
a = np.asarray(p) # NumPy view on the cloud
a[:] = 0 # fill with zeros
print(p[3]) # prints (0.0, 0.0, 0.0)
a[:, 0] = 1 # set x coordinates to 1
print(p[3]) # prints (1.0, 0.0, 0.0)
More samples can be found in the examples directory, and in the unit tests.
This work was supported by Strawlab.
Requirements
This release has been tested on Linux Ubuntu 16.04 with
- Python 2.7.6, 3.5.x
- pcl 1.7.2(apt install)
- Cython <= 0.25.2
This release has been tested on Linux Ubuntu 18.04 with
- Python 2.7.6, 3.5.x
- pcl 1.8.1(apt install)
- Cython <= 0.25.2
and MacOS with
- Python 2.7.6, 3.5.x
- pcl 1.9.1(use homebrew)
- Cython <= 0.25.2
and Windows with
- (Miniconda/Anaconda) - Python 3.4
- pcl 1.6.0(VS2010)
- Cython <= 0.25.2
- Gtk+
and Windows with
- (Miniconda/Anaconda) - Python 3.5
- pcl 1.8.1(VS2015)
- Cython <= 0.25.2
- Gtk+
and Windows with
- (Miniconda/Anaconda) - Python 3.6
- pcl 1.8.1(VS2017[Priority High]/VS2015[not VS2017 Install])
- Cython == 0.25.2
- Gtk+
Installation
Linux(Ubuntu)
before Install module
Ubuntu16.04/18.04 (use official package)
- Install PCL Module.
$ sudo apt-get update -y $ sudo apt-get install libpcl-dev -y Reference `here <https://packages.ubuntu.com/search?keywords=libpcl-dev>`_.
PCL 1.8.x/1.9.x and Ubuntu16.04/18.04(build module)([CI Test Timeout])
Build Module
Reference here.
MacOSX
before Install module
Case1. use homebrew(PCL 1.9.1 - 2018/12/25 current)
Install PCL Module.
$ brew tap homebrew/science
$ brew install pcl
Case1. use old homebrew(PCL 1.8.1 - 2017/11/13 current)
Check git log.
$ cd /usr/local/Library/Formula
$ git log ...
git checkout (target hash) pcl.rb
write after.
Warning:
Current Installer (2017/10/02) Not generated pcl-2d-1.8.pc file.(Issue #119)
Reference PointCloudLibrary Issue.
circumvent:
copy travis/pcl-2d-1.8.pc file to /usr/local/lib/pkgconfig folder.
Windows
Using pip with a precompiled wheel
This is the simpliest method on windows. The wheel contains the PCL binaries _ and thus you do not need to install the original PCL library.
- Go in the history on the appveyor page
- Click on the last successful revision (green) and click on the job corresponding to your python version
- Go in the artfacts section for that job and download the wheel (the file with extension whl)
- In the command line, move to your download folder and run the following command (replacing XXX by the right string)
pip install python_pcl-XXX.whl
Compiling the binding from source
If the method using the procompiled wheel does not work you can compile the binding from the source.
before Install module
Case1. use PCL 1.6.0
Windows SDK 7.1
64 bitOpenNI2[(PCL Install FolderPath)\3rdParty\OpenNI\OpenNI-(win32/x64)-1.3.2-Dev.msi]
Case2. use 1.8.1/1.9.1
Visual Studio 2015 C++ Compiler Tools(use Python 2.7/3.5/3.6/3.7)
Visual Studio 2017 C++ Compiler Tools(use Python 3.6.x/3.7.x)
1.8.1
1.9.1
OpenNI2[(PCL Install FolderPath)\3rdParty\OpenNI2\OpenNI-Windows-(win32/x64)-2.2.msi]
Common setting
- Windows Gtk+ Download Download file unzip. Copy bin Folder to pkg-config Folder
Download file unzip. Copy bin Folder to pkg-config Folder
or execute powershell file [Install-GTKPlus.ps1].
Python Version use VisualStudio Compiler
set before Environment variable
- PCL_ROOT
set PCL_ROOT=(PCL Install/Build_Binary FolderPath)
2. PATH
(pcl 1.6.0)
set PATH=%PCL_ROOT%/bin/;%OPEN_NI_ROOT%/Tools;%VTK_ROOT%/bin;%PATH%
(pcl 1.8.1/1.9.1)
set PATH=%PCL_ROOT%/bin/;%OPEN_NI2_ROOT%/Tools;%VTK_ROOT%/bin;%PATH%
Common setting
- pip module install.
pip install --upgrade pip
pip install cython
pip install numpy
- install python module
python setup.py build_ext -i
python setup.py install
- install python-pcl with conda (solved)
-> conda create -n ipk # create a new conda env. -> conda activate ipk # activate env.
-> conda update -n base -c defaults conda # update conda
-> conda config --add channels conda-forge # add conda-forge channels -> conda install -c sirokujira python-pcl # pcl installation -> conda install -c jithinpr2 gtk3 # Gtk+ Gui dependency -> conda install -y ipython # install ipython -> conda install -y jupyter # install jupyter
After that, run jupyter notebook or ipython shell to test pcl installation.
Build & Test Status
windows(1.6.0/1.8.1/1.9.1)
Mac OSX(1.9.1)/Ubuntu16.04(1.7.2)
A note about types
Point Cloud is a heavily templated API, and consequently mapping this into Python using Cython is challenging.
It is written in Cython, and implements enough hard bits of the API (from Cythons perspective, i.e the template/smart_ptr bits) to provide a foundation for someone wishing to carry on.
API Documentation
For deficiencies in this documentation, please consult the PCL API docs, and the PCL tutorials.