Travis Quality-score Coverage

Introduction

This is a small python binding to the pointcloud library. Currently, the following parts of the API are wrapped (all methods operate on PointXYZRGB) point types

  • I/O and integration; saving and loading PCD files
  • segmentation
  • SAC
  • smoothing
  • filtering

The code tries to follow the Point Cloud API, and also provides helper function for interacting with NumPy.

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 library is developed for use in our Project Patty, see this repository for more interesting examples. Also, the reading and writing of LAS files is implemented there.

This work was supported by Strawlab and the Netherlands eScience Center

Requirements

This release has been tested on Linux Mint 17 with

  • Python 2.7.9
  • pcl 1.7.2
  • Cython 0.22

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 API documentation, look at our gh-pages branch For deficiencies in this documentation, please consult the PCL API docs, and the PCL tutorials.

Pointcloud class

class pcl.BasePointCloud
extract(self, pyindices, bool negative=False)

Given a list of indices of points in the pointcloud, return a new pointcloud containing only those points.

from_array(self, ndarray arr)

Fill this object from a 2D numpy array (float32)

from_file(self, char *f)

Fill this pointcloud from a file (a local path). Only pcd files supported currently.

Deprecated; use pcl.load instead.

from_list(self, _list)

Fill this pointcloud from a list of 3-tuples

get_point(self, npy_intp row, npy_intp col)

Return a point (6-tuple) at the given row/column

height

property containing the height of the point cloud

is_dense

property containing whether the cloud is dense or not

make_kdtree_flann(self)

Return a pcl.kdTreeFLANN object with this object set as the input-cloud

Deprecated: use the pcl.KdTreeFLANN constructor on this cloud.

make_moving_least_squares(self)

Return a pcl.MovingLeastSquares object with this object as input cloud.

make_octree(self, double resolution)

Return a pcl.octree object with this object set as the input-cloud

make_passthrough_filter(self)

Return a pcl.PassThroughFilter object with this object set as the input-cloud

make_segmenter(self)

Return a pcl.Segmentation object with this object set as the input-cloud

make_segmenter_normals(self, int ksearch=-1, double searchRadius=-1.0)

Return a pcl.SegmentationNormal object with this object set as the input-cloud

make_statistical_outlier_filter(self)

Return a pcl.StatisticalOutlierRemovalFilter object with this object set as the input-cloud

make_voxel_grid_filter(self)

Return a pcl.VoxelGridFilter object with this object set as the input-cloud

resize(self, npy_intp x)
sensor_orientation
sensor_origin
size

property containing the number of points in the point cloud

to_file(self, char const *fname, bool ascii=True)

Save pointcloud to a file in PCD format.

Deprecated: use pcl.save instead.

width

property containing the width of the point cloud

class pcl.BasePyPointCloud
to_list()

Return this object as a list of tuples.

transform(t)

Apply rigid transformation t, in-place.

t : ndarray, shape (4, 4)
Rigid transformation.
self : point cloud
Returns self, for convenience.
class pcl.KdTreeFLANN

Finds k nearest neighbours from points in another pointcloud to points in a reference pointcloud.

Must be constructed from the reference point cloud, which is copied, so changed to pc are not reflected in KdTreeFLANN(pc).

nearest_k_search_for_cloud(self, BasePointCloud pc, int k=1)

Find the k nearest neighbours and squared distances for all points in the pointcloud. Results are in ndarrays, size (pc.size, k) Returns: (k_indices, k_sqr_distances)

nearest_k_search_for_point(self, BasePointCloud pc, int index, int k=1)

Find the k nearest neighbours and squared distances for the point at pc[index]. Results are in ndarrays, size (k) Returns: (k_indices, k_sqr_distances)

class pcl.MovingLeastSquares

Smoothing class which is an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation.

process(self)

Apply the smoothing according to the previously set values and return a new pointcloud

set_polynomial_fit(self, bool fit)

Sets whether the surface and normal are approximated using a polynomial, or only via tangent estimation.

set_polynomial_order(self, bool order)

Set the order of the polynomial to be fit.

set_search_radius(self, double radius)

Set the sphere radius that is to be used for determining the k-nearest neighbors used for fitting.

class pcl.OctreePointCloud(double resolution)

Octree pointcloud

add_points_from_input_cloud(self)

Add points from input point cloud to octree.

define_bounding_box(self)

Investigate dimensions of pointcloud data set and define corresponding bounding box for octree.

delete_tree(self)

Delete the octree structure and its leaf nodes.

delete_voxel_at_point(self, point)

Delete leaf node / voxel at given point.

get_occupied_voxel_centers(self)

Get list of centers of all occupied voxels.

is_voxel_occupied_at_point(self, point)

Check if voxel at given point coordinates exist.

set_input_cloud(self, BasePointCloud pc)

Provide a pointer to the input data set.

class pcl.OctreePointCloudSearch

Octree pointcloud search

Search for all neighbors of query point that are within a given radius.

Returns: (k_indices, k_sqr_distances)

class pcl.PassThroughFilter

Passes points in a cloud based on constraints for one particular field of the point type

filter(self)

Apply the filter according to the previously set parameters and return a new pointcloud

set_filter_field_name(self, field_name)
set_filter_limits(self, float filter_min, float filter_max)
class pcl.PointCloud

3-d point cloud (no color information).

get_point(row, col)

Return point (3-tuple) at the given row/column.

to_array()

Return this object as a 2D numpy array (float32).

class pcl.PointCloudXYZRGB

3-d point cloud with color information.

get_point(row, col)

Return point (3-tuple) at the given row/column.

to_array()

Return this object as a 2D numpy array (float32).

class pcl.Segmentation

Segmentation class for Sample Consensus methods and models

segment(self)
set_distance_threshold(self, float d)
set_method_type(self, int m)
set_model_type(self, SacModel m)
set_optimize_coefficients(self, bool b)
class pcl.SegmentationNormal

Segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation.

Due to Cython limitations this should derive from pcl.Segmentation, but is currently unable to do so.

segment(self)
set_axis(self, double ax, double ay, double az)
set_distance_threshold(self, float d)
set_eps_angle(self, double ea)
set_max_iterations(self, int i)
set_method_type(self, int m)
set_model_type(self, SacModel m)
set_normal_distance_weight(self, float f)
set_optimize_coefficients(self, bool b)
set_radius_limits(self, float f1, float f2)
class pcl.Sequence

All the operations on a read-only sequence.

Concrete subclasses must override __new__ or __init__, __getitem__, and __len__.

count(value) → integer -- return number of occurrences of value
index(value) → integer -- return first index of value.

Raises ValueError if the value is not present.

class pcl.StatisticalOutlierRemovalFilter

Filter class uses point neighborhood statistics to filter outlier data.

filter(self)

Apply the filter according to the previously set parameters and return a new pointcloud

mean_k
negative
set_mean_k(self, int k)

Set the number of points (k) to use for mean distance estimation.

set_negative(self, bool negative)

Set whether the indices should be returned, or all points except the indices.

set_std_dev_mul_thresh(self, double std_mul)

Set the standard deviation multiplier threshold.

stddev_mul_thresh
class pcl.VoxelGridFilter

Assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.

filter(self)

Apply the filter according to the previously set parameters and return a new pointcloud

set_leaf_size(self, float x, float y, float z)

Set the voxel grid leaf size.

pcl.float_to_rgb(p_rgb)
pcl.load(path, format=None, loadRGB=True)

Load pointcloud from path.

Currently supports PCD and PLY files.

Format should be “pcd”, “ply”, or None to infer from the pathname.

An optional loadRGB parameter is included to provide the option of loading or ignoring colour information.

pcl.save(cloud, path, format=None, binary=False)

Save pointcloud to file.

Format should be “pcd”, “ply”, or None to infer from the pathname.

Registration functions

pcl.registration.gicp(BasePointCloud source, BasePointCloud target, max_iter=None)

Align source to target using generalized iterative closest point (GICP).

source : point cloud
Source point cloud.
target : point cloud
Target point cloud.
max_iter : integer, optional
Maximum number of iterations. If not given, uses the default number hardwired into PCL.
converged : bool
Whether the ICP algorithm converged in at most max_iter steps.
transf : np.ndarray, shape = [4, 4]
Transformation matrix.
estimate : point cloud
Transformed version of source. Will be of the same type as source.
fitness : float
Sum of squares error in the estimated transformation.
pcl.registration.ia_ransac(BasePointCloud source, BasePointCloud target, max_iter=None, radius=0.05, minSampleDistance=0.05, maxCorrespondenceDistance=0.2)

An implementation of the initial alignment algorithm described in section IV of “Fast Point Feature Histograms (FPFH) for 3D Registration,” Rusu et al.

source : PointCloud
Source point cloud.
target : PointCloud
Target point cloud.
max_iter : integer, optional
Maximum number of iterations. If not given, uses the default number hardwired into PCL.
radius : double
Radius in which neighbours are searched for in the NormalEstimation algorithm.
minSampleDistance : double
Set the minimum distances between samples.
maxCorrespondenceDistance : double
Set the maximum distance threshold between two correspondent points in source <-> target.
converged : bool
Whether the ICP algorithm converged in at most max_iter steps.
estimate : PointCloud
Transformed version of source.
fitness : float
Sum of squares error in the estimated transformation.
pcl.registration.icp(BasePointCloud source, BasePointCloud target, max_iter=None, transformationEpsilon=None, euclideanFitnessEpsilon=None)

Align source to target using iterative closest point (ICP).

source : point cloud
Source point cloud.
target : point cloud
Target point cloud.
max_iter : integer, optional
Maximum number of iterations. If not given, uses the pcl default (10) hardwired into PCL.
transformationEpsilon : double, optional
Maximum difference between two consecutive transformations, before the algorithm is considered to have converged. If not given, uses the pcl default (0)
euclideanFitnessEpsilon : double, optional
Maximum Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. If not given, uses the pcl default (max)
converged : bool
Whether the ICP algorithm converged in at most max_iter steps.
transf : np.ndarray, shape = [4, 4]
Transformation matrix.
estimate : point cloud
Transformed version of source. Will be of the same type as source.
fitness : float
Sum of squares error in the estimated transformation.
pcl.registration.icp_nl(BasePointCloud source, BasePointCloud target, max_iter=None)

Align source to target using generalized non-linear ICP (ICP-NL).

source : point cloud
Source point cloud.
target : point cloud
Target point cloud.
max_iter : integer, optional
Maximum number of iterations. If not given, uses the default number hardwired into PCL.
converged : bool
Whether the ICP algorithm converged in at most max_iter steps.
transf : np.ndarray, shape = [4, 4]
Transformation matrix.
estimate : point cloud
Transformed version of source. Will be of the same type as source.
fitness : float
Sum of squares error in the estimated transformation.

Boundary detection

pcl.boundaries.estimate_boundaries(BasePointCloud pc, float angle_threshold, double search_radius, int normal_ksearch=-1, double normal_search_radius=-1)

Boundary estimation.

Returns an array of booleans (true = boundary point); one per point in the point cloud pc.