diff options
author | Lars Buitinck <l.buitinck@esciencecenter.nl> | 2014-07-03 19:52:21 +0200 |
---|---|---|
committer | Lars Buitinck <l.buitinck@esciencecenter.nl> | 2014-07-04 11:52:18 +0200 |
commit | e35cc9bc721da7d95976a3dd5ea4b1ec02e85459 (patch) | |
tree | 2ce2a8917a7de4235bc8d140b62372fa12892d13 /pcl | |
parent | 5cd702c3946c80097c11f67cd84d761bf9e1741a (diff) |
move to package structure
Allows splitting the big pcl.pyx module and writing parts
in pure Python to speed up compilation.
Diffstat (limited to 'pcl')
-rw-r--r-- | pcl/__init__.py | 1 | ||||
-rw-r--r-- | pcl/_pcl.pyx | 627 | ||||
-rw-r--r-- | pcl/minipcl.cpp | 46 | ||||
-rw-r--r-- | pcl/minipcl.h | 20 | ||||
-rw-r--r-- | pcl/pcl_defs.pxd | 205 | ||||
-rw-r--r-- | pcl/shared_ptr.pxd | 11 | ||||
-rw-r--r-- | pcl/vector.pxd | 68 |
7 files changed, 978 insertions, 0 deletions
diff --git a/pcl/__init__.py b/pcl/__init__.py new file mode 100644 index 0000000..cac326d --- /dev/null +++ b/pcl/__init__.py @@ -0,0 +1 @@ +from ._pcl import * diff --git a/pcl/_pcl.pyx b/pcl/_pcl.pyx new file mode 100644 index 0000000..d0d0305 --- /dev/null +++ b/pcl/_pcl.pyx @@ -0,0 +1,627 @@ +#cython: embedsignature=True + +import numpy as np + +cimport numpy as cnp + +cimport pcl_defs as cpp + +cimport cython +from cython.operator import dereference as deref +from libcpp.string cimport string +from libcpp cimport bool +from libcpp.vector cimport vector + +cdef extern from "minipcl.h": + void mpcl_compute_normals(cpp.PointCloud_t, int ksearch, double searchRadius, cpp.PointNormalCloud_t) + void mpcl_sacnormal_set_axis(cpp.SACSegmentationNormal_t, double ax, double ay, double az) + void mpcl_extract(cpp.PointCloud_t, cpp.PointCloud_t, cpp.PointIndices_t *, bool) + +SAC_RANSAC = cpp.SAC_RANSAC +SAC_LMEDS = cpp.SAC_LMEDS +SAC_MSAC = cpp.SAC_MSAC +SAC_RRANSAC = cpp.SAC_RRANSAC +SAC_RMSAC = cpp.SAC_RMSAC +SAC_MLESAC = cpp.SAC_MLESAC +SAC_PROSAC = cpp.SAC_PROSAC + +SACMODEL_PLANE = cpp.SACMODEL_PLANE +SACMODEL_LINE = cpp.SACMODEL_LINE +SACMODEL_CIRCLE2D = cpp.SACMODEL_CIRCLE2D +SACMODEL_CIRCLE3D = cpp.SACMODEL_CIRCLE3D +SACMODEL_SPHERE = cpp.SACMODEL_SPHERE +SACMODEL_CYLINDER = cpp.SACMODEL_CYLINDER +SACMODEL_CONE = cpp.SACMODEL_CONE +SACMODEL_TORUS = cpp.SACMODEL_TORUS +SACMODEL_PARALLEL_LINE = cpp.SACMODEL_PARALLEL_LINE +SACMODEL_PERPENDICULAR_PLANE = cpp.SACMODEL_PERPENDICULAR_PLANE +SACMODEL_PARALLEL_LINES = cpp.SACMODEL_PARALLEL_LINES +SACMODEL_NORMAL_PLANE = cpp.SACMODEL_NORMAL_PLANE +#SACMODEL_NORMAL_SPHERE = cpp.SACMODEL_NORMAL_SPHERE +SACMODEL_REGISTRATION = cpp.SACMODEL_REGISTRATION +SACMODEL_PARALLEL_PLANE = cpp.SACMODEL_PARALLEL_PLANE +SACMODEL_NORMAL_PARALLEL_PLANE = cpp.SACMODEL_NORMAL_PARALLEL_PLANE +SACMODEL_STICK = cpp.SACMODEL_STICK + + +cnp.import_array() + + +cdef class Segmentation: + """ + Segmentation class for Sample Consensus methods and models + """ + cdef cpp.SACSegmentation_t *me + def __cinit__(self): + self.me = new cpp.SACSegmentation_t() + def __dealloc__(self): + del self.me + + def segment(self): + cdef cpp.PointIndices ind + cdef cpp.ModelCoefficients coeffs + self.me.segment (ind, coeffs) + return [ind.indices[i] for i in range(ind.indices.size())],\ + [coeffs.values[i] for i in range(coeffs.values.size())] + + def set_optimize_coefficients(self, bool b): + self.me.setOptimizeCoefficients(b) + def set_model_type(self, cpp.SacModel m): + self.me.setModelType(m) + def set_method_type(self, int m): + self.me.setMethodType (m) + def set_distance_threshold(self, float d): + self.me.setDistanceThreshold (d) + +#yeah, I can't be bothered making this inherit from SACSegmentation, I forget the rules +#for how this works in cython templated extension types anyway +cdef class 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. + """ + cdef cpp.SACSegmentationNormal_t *me + def __cinit__(self): + self.me = new cpp.SACSegmentationNormal_t() + def __dealloc__(self): + del self.me + + def segment(self): + cdef cpp.PointIndices ind + cdef cpp.ModelCoefficients coeffs + self.me.segment (ind, coeffs) + return [ind.indices[i] for i in range(ind.indices.size())],\ + [coeffs.values[i] for i in range(coeffs.values.size())] + + def set_optimize_coefficients(self, bool b): + self.me.setOptimizeCoefficients(b) + def set_model_type(self, cpp.SacModel m): + self.me.setModelType(m) + def set_method_type(self, int m): + self.me.setMethodType (m) + def set_distance_threshold(self, float d): + self.me.setDistanceThreshold (d) + def set_optimize_coefficients(self, bool b): + self.me.setOptimizeCoefficients (b) + def set_normal_distance_weight(self, float f): + self.me.setNormalDistanceWeight (f) + def set_max_iterations(self, int i): + self.me.setMaxIterations (i) + def set_radius_limits(self, float f1, float f2): + self.me.setRadiusLimits (f1, f2) + def set_eps_angle(self, double ea): + self.me.setEpsAngle (ea) + def set_axis(self, double ax, double ay, double az): + mpcl_sacnormal_set_axis(deref(self.me),ax,ay,az) + +cdef class PointCloud: + """ + Represents a class of points, supporting the PointXYZ type. + """ + cdef cpp.PointCloud[cpp.PointXYZ] *thisptr + def __cinit__(self): + self.thisptr = new cpp.PointCloud[cpp.PointXYZ]() + def __dealloc__(self): + del self.thisptr + property width: + """ property containing the width of the point cloud """ + def __get__(self): return self.thisptr.width + property height: + """ property containing the height of the point cloud """ + def __get__(self): return self.thisptr.height + property size: + """ property containing the number of points in the point cloud """ + def __get__(self): return self.thisptr.size() + property is_dense: + """ property containing whether the cloud is dense or not """ + def __get__(self): return self.thisptr.is_dense + + @cython.boundscheck(False) + def from_array(self, cnp.ndarray[cnp.float32_t, ndim=2] arr not None): + """ + Fill this object from a 2D numpy array (float32) + """ + assert arr.shape[1] == 3 + + cdef cnp.npy_intp npts = arr.shape[0] + self.resize(npts) + self.thisptr.width = npts + self.thisptr.height = 1 + + cdef cpp.PointXYZ *p + for i in range(npts): + p = &self.thisptr.at(i) + p.x, p.y, p.z = arr[i, 0], arr[i, 1], arr[i, 2] + + @cython.boundscheck(False) + def to_array(self): + """ + Return this object as a 2D numpy array (float32) + """ + cdef float x,y,z + cdef cnp.npy_intp n = self.thisptr.size() + cdef cnp.ndarray[cnp.float32_t, ndim=2, mode="c"] result + cdef cpp.PointXYZ *p + + result = np.empty((n, 3), dtype=np.float32) + + for i in range(n): + p = &self.thisptr.at(i) + result[i, 0] = p.x + result[i, 1] = p.y + result[i, 2] = p.z + return result + + def from_list(self, _list): + """ + Fill this pointcloud from a list of 3-tuples + """ + cdef Py_ssize_t npts = len(_list) + cdef cpp.PointXYZ *p + + self.resize(npts) + self.thisptr.width = npts + self.thisptr.height = 1 + for i,l in enumerate(_list): + p = &self.thisptr.at(i) + p.x, p.y, p.z = l + + def to_list(self): + """ + Return this object as a list of 3-tuples + """ + return self.to_array().tolist() + + def resize(self, cnp.npy_intp x): + self.thisptr.resize(x) + + def get_point(self, cnp.npy_intp row, cnp.npy_intp col): + """ + Return a point (3-tuple) at the given row/column + """ + cdef cpp.PointXYZ *p = &self.thisptr.at(row, col) + return p.x, p.y, p.z + + def __getitem__(self, cnp.npy_intp idx): + cdef cpp.PointXYZ *p = &self.thisptr.at(idx) + return p.x, p.y, p.z + + def from_file(self, char *f): + """ + Fill this pointcloud from a file (a local path). + Only pcd files supported currently. + """ + cdef int ok = 0 + cdef string s = string(f) + if f.endswith(".pcd"): + with nogil: + ok = cpp.loadPCDFile(s, deref(self.thisptr)) + else: + raise ValueError("Incorrect file extension (must be .pcd)") + return ok + + def to_file(self, char *f, bool ascii=True): + """ + Save this pointcloud to a local file. + Only saving to binary or ascii pcd is supported + """ + cdef bool binary = not ascii + cdef int ok = 0 + cdef string s = string(f) + if f.endswith(".pcd"): + with nogil: + ok = cpp.savePCDFile(s, deref(self.thisptr), binary) + else: + raise ValueError("Incorrect file extension (must be .pcd)") + return ok + + def make_segmenter(self): + """ + Return a pcl.Segmentation object with this object set as the input-cloud + """ + seg = Segmentation() + cdef cpp.SACSegmentation_t *cseg = <cpp.SACSegmentation_t *>seg.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cseg.setInputCloud(ccloud.makeShared()) + return seg + + def make_segmenter_normals(self, int ksearch=-1, double searchRadius=-1.0): + """ + Return a pcl.SegmentationNormal object with this object set as the input-cloud + """ + cdef cpp.PointNormalCloud_t normals + mpcl_compute_normals(deref(self.thisptr), ksearch, searchRadius, normals) + + seg = SegmentationNormal() + cdef cpp.SACSegmentationNormal_t *cseg = <cpp.SACSegmentationNormal_t *>seg.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cseg.setInputCloud(ccloud.makeShared()) + cseg.setInputNormals (normals.makeShared()); + + return seg + + def make_statistical_outlier_filter(self): + """ + Return a pcl.StatisticalOutlierRemovalFilter object with this object set as the input-cloud + """ + fil = StatisticalOutlierRemovalFilter() + cdef cpp.StatisticalOutlierRemoval_t *cfil = <cpp.StatisticalOutlierRemoval_t *>fil.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cfil.setInputCloud(ccloud.makeShared()) + return fil + + def make_voxel_grid_filter(self): + """ + Return a pcl.VoxelGridFilter object with this object set as the input-cloud + """ + fil = VoxelGridFilter() + cdef cpp.VoxelGrid_t *cfil = <cpp.VoxelGrid_t *>fil.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cfil.setInputCloud(ccloud.makeShared()) + return fil + + def make_passthrough_filter(self): + """ + Return a pcl.PassThroughFilter object with this object set as the input-cloud + """ + fil = PassThroughFilter() + cdef cpp.PassThrough_t *cfil = <cpp.PassThrough_t *>fil.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cfil.setInputCloud(ccloud.makeShared()) + return fil + + def make_moving_least_squares(self): + """ + Return a pcl.MovingLeastSquares object with this object set as the input-cloud + """ + mls = MovingLeastSquares() + + cdef cpp.MovingLeastSquares_t *cmls = <cpp.MovingLeastSquares_t *>mls.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cmls.setInputCloud(ccloud.makeShared()) + return mls + + def make_kdtree_flann(self): + """ + Return a pcl.kdTreeFLANN object with this object set as the input-cloud + """ + kdtree = KdTreeFLANN() + cdef cpp.KdTreeFLANN_t *ckdtree = <cpp.KdTreeFLANN_t *>kdtree.me + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + ckdtree.setInputCloud(ccloud.makeShared()) + return kdtree + + def make_octree(self, double resolution): + """ + Return a pcl.octree object with this object set as the input-cloud + """ + octree = OctreePointCloud(resolution) + octree.set_input_cloud(self) + return octree + + def extract(self, pyindices, bool negative=False): + """ + Given a list of indices of points in the pointcloud, return a + new pointcloud containing only those points. + """ + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>self.thisptr + cdef cpp.PointCloud_t *out = new cpp.PointCloud_t() + cdef cpp.PointIndices_t *ind = new cpp.PointIndices_t() + + for i in pyindices: + ind.indices.push_back(i) + + mpcl_extract(deref(ccloud), deref(out), ind, negative) + + cdef PointCloud pycloud = PointCloud() + del pycloud.thisptr + pycloud.thisptr = out + + return pycloud + +cdef class StatisticalOutlierRemovalFilter: + """ + Filter class uses point neighborhood statistics to filter outlier data. + """ + cdef cpp.StatisticalOutlierRemoval_t *me + def __cinit__(self): + self.me = new cpp.StatisticalOutlierRemoval_t() + def __dealloc__(self): + del self.me + + def set_mean_k(self, int k): + """ + Set the number of points (k) to use for mean distance estimation. + """ + self.me.setMeanK(k) + + def set_std_dev_mul_thresh(self, double std_mul): + """ + Set the standard deviation multiplier threshold. + """ + self.me.setStddevMulThresh(std_mul) + + def set_negative(self, bool negative): + """ + Set whether the indices should be returned, or all points except the indices. + """ + self.me.setNegative(negative) + + def filter(self): + """ + Apply the filter according to the previously set parameters and return + a new pointcloud + """ + pc = PointCloud() + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + self.me.filter(deref(ccloud)) + return pc + +cdef class MovingLeastSquares: + """ + Smoothing class which is an implementation of the MLS (Moving Least Squares) + algorithm for data smoothing and improved normal estimation. + """ + cdef cpp.MovingLeastSquares_t *me + def __cinit__(self): + self.me = new cpp.MovingLeastSquares_t() + def __dealloc__(self): + del self.me + + def set_search_radius(self, double radius): + """ + Set the sphere radius that is to be used for determining the k-nearest neighbors used for fitting. + """ + self.me.setSearchRadius (radius) + + def set_polynomial_order(self, bool order): + """ + Set the order of the polynomial to be fit. + """ + self.me.setPolynomialOrder(order) + + def set_polynomial_fit(self, bint fit): + """ + Sets whether the surface and normal are approximated using a polynomial, + or only via tangent estimation. + """ + self.me.setPolynomialFit(fit) + + def process(self): + """ + Apply the smoothing according to the previously set values and return + a new pointcloud + """ + pc = PointCloud() + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + self.me.process(deref(ccloud)) + return pc + +cdef class VoxelGridFilter: + """ + Assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. + """ + cdef cpp.VoxelGrid_t *me + def __cinit__(self): + self.me = new cpp.VoxelGrid_t() + def __dealloc__(self): + del self.me + + def set_leaf_size (self, float x, float y, float z): + """ + Set the voxel grid leaf size. + """ + self.me.setLeafSize(x,y,z) + + def filter(self): + """ + Apply the filter according to the previously set parameters and return + a new pointcloud + """ + pc = PointCloud() + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + self.me.filter(deref(ccloud)) + return pc + +cdef class PassThroughFilter: + """ + Passes points in a cloud based on constraints for one particular field of the point type + """ + cdef cpp.PassThrough_t *me + def __cinit__(self): + self.me = new cpp.PassThrough_t() + def __dealloc__(self): + del self.me + + def set_filter_field_name(self, char *field_name): + cdef string s = string(field_name) + self.me.setFilterFieldName (s) + + def set_filter_limits(self, float filter_min, float filter_max): + self.me.setFilterLimits (filter_min, filter_max) + + def filter(self): + """ + Apply the filter according to the previously set parameters and return + a new pointcloud + """ + pc = PointCloud() + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + self.me.filter(deref(ccloud)) + return pc + +cdef class KdTreeFLANN: + """ + Finds k nearest neighbours from points in another pointcloud to points in + this pointcloud + """ + cdef cpp.KdTreeFLANN_t *me + def __cinit__(self): + self.me = new cpp.KdTreeFLANN_t() + def __dealloc__(self): + del self.me + + def nearest_k_search_for_cloud(self, PointCloud 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) + """ + n_points = pc.size + cdef cnp.ndarray[float, ndim=2] np_k_sqr_distances = np.zeros( + (n_points, k), dtype=np.float32) + cdef cnp.ndarray[int, ndim=2] np_k_indices= np.zeros( + (n_points, k), dtype=np.int32) + for i in range(pc.size): + k_i, k_sqr_d = self.nearest_k_search_for_point(pc, i, k) + np_k_indices[i,:] = k_i + np_k_sqr_distances[i,:] = k_sqr_d + return np_k_indices, np_k_sqr_distances + + def nearest_k_search_for_point(self, PointCloud 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) + """ + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + cdef vector[int] k_indices + cdef vector[float] k_sqr_distances + k_indices.resize(k) + k_sqr_distances.resize(k) + self.me.nearestKSearch(deref(ccloud), index, k, k_indices, k_sqr_distances) + cdef cnp.ndarray[float] np_k_sqr_distances = np.zeros(k, dtype=np.float32) + cdef cnp.ndarray[int] np_k_indices= np.zeros(k, dtype=np.int32) + for i in range(k): + np_k_sqr_distances[i] = k_sqr_distances[i] + np_k_indices[i] = k_indices[i] + return np_k_indices, np_k_sqr_distances + +cdef cpp.PointXYZ to_point_t(point): + cdef cpp.PointXYZ p + p.x = point[0] + p.y = point[1] + p.z = point[2] + return p + +cdef class OctreePointCloud: + """ + Octree pointcloud + """ + cdef cpp.OctreePointCloud_t *me + + def __cinit__(self, double resolution): + """ + Constructs octree pointcloud with given resolution at lowest octree level + """ + self.me = new cpp.OctreePointCloud_t(resolution) + + def __dealloc__(self): + del self.me + + def set_input_cloud(self, PointCloud pc): + """ + Provide a pointer to the input data set. + """ + cdef cpp.PointCloud_t *ccloud = <cpp.PointCloud_t *>pc.thisptr + self.me.setInputCloud(ccloud.makeShared()) + + def define_bounding_box(self): + """ + Investigate dimensions of pointcloud data set and define corresponding bounding box for octree. + """ + self.me.defineBoundingBox() + + def define_bounding_box(self, double min_x, double min_y, double min_z, double max_x, double max_y, double max_z): + """ + Define bounding box for octree. Bounding box cannot be changed once the octree contains elements. + """ + self.me.defineBoundingBox(min_x, min_y, min_z, max_x, max_y, max_z) + + def add_points_from_input_cloud(self): + """ + Add points from input point cloud to octree. + """ + self.me.addPointsFromInputCloud() + + def delete_tree(self): + """ + Delete the octree structure and its leaf nodes. + """ + self.me.deleteTree() + + def is_voxel_occupied_at_point(self, point): + """ + Check if voxel at given point coordinates exist. + """ + return self.me.isVoxelOccupiedAtPoint(point[0], point[1], point[2]) + + def get_occupied_voxel_centers(self): + """ + Get list of centers of all occupied voxels. + """ + cdef cpp.AlignedPointTVector_t points_v + cdef int num = self.me.getOccupiedVoxelCenters (points_v) + return [(points_v[i].x, points_v[i].y, points_v[i].z) for i in range(num)] + + def delete_voxel_at_point(self, point): + """ + Delete leaf node / voxel at given point. + """ + self.me.deleteVoxelAtPoint(to_point_t(point)) + +cdef class OctreePointCloudSearch(OctreePointCloud): + """ + Octree pointcloud search + """ + def __cinit__(self, double resolution): + """ + Constructs octree pointcloud with given resolution at lowest octree level + """ + self.me = <cpp.OctreePointCloud_t*> new cpp.OctreePointCloudSearch_t(resolution) + + def __dealloc__(self): + del self.me + + def radius_search (self, point, double radius, unsigned int max_nn = 0): + """ + Search for all neighbors of query point that are within a given radius. + + Returns: (k_indices, k_sqr_distances) + """ + cdef vector[int] k_indices + cdef vector[float] k_sqr_distances + if max_nn > 0: + k_indices.resize(max_nn) + k_sqr_distances.resize(max_nn) + cdef int k = (<cpp.OctreePointCloudSearch_t*>self.me).radiusSearch(to_point_t(point), radius, k_indices, k_sqr_distances, max_nn) + cdef cnp.ndarray[float] np_k_sqr_distances = np.zeros(k, dtype=np.float32) + cdef cnp.ndarray[int] np_k_indices = np.zeros(k, dtype=np.int32) + for i in range(k): + np_k_sqr_distances[i] = k_sqr_distances[i] + np_k_indices[i] = k_indices[i] + return np_k_indices, np_k_sqr_distances + diff --git a/pcl/minipcl.cpp b/pcl/minipcl.cpp new file mode 100644 index 0000000..74106d5 --- /dev/null +++ b/pcl/minipcl.cpp @@ -0,0 +1,46 @@ +#include <pcl/point_types.h> +#include <pcl/features/normal_3d.h> +#include <pcl/search/kdtree.h> +#include <pcl/filters/extract_indices.h> + +#include <Eigen/Dense> + +#include "minipcl.h" + +// set ksearch and radius to < 0 to disable +void mpcl_compute_normals(pcl::PointCloud<pcl::PointXYZ> &cloud, + int ksearch, + double searchRadius, + pcl::PointCloud<pcl::Normal> &out) +{ + pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ()); + pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne; + + ne.setSearchMethod (tree); + ne.setInputCloud (cloud.makeShared()); + if (ksearch >= 0) + ne.setKSearch (ksearch); + if (searchRadius >= 0.0) + ne.setRadiusSearch (searchRadius); + ne.compute (out); +} + +void mpcl_sacnormal_set_axis(pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal> &sac, + double ax, double ay, double az) +{ + Eigen::Vector3f vect(ax,ay,az); + sac.setAxis(vect); +} + +void mpcl_extract(pcl::PointCloud<pcl::PointXYZ> &incloud, + pcl::PointCloud<pcl::PointXYZ> &outcloud, + pcl::PointIndices *indices, + bool negative) +{ + pcl::PointIndices::Ptr indicesptr (indices); + pcl::ExtractIndices<pcl::PointXYZ> ext; + ext.setInputCloud(incloud.makeShared()); + ext.setIndices(indicesptr); + ext.setNegative (negative); + ext.filter (outcloud); +} diff --git a/pcl/minipcl.h b/pcl/minipcl.h new file mode 100644 index 0000000..cb35f79 --- /dev/null +++ b/pcl/minipcl.h @@ -0,0 +1,20 @@ +#ifndef _MINIPCL_H_ +#define _MINIPCL_H_ + +#include <pcl/point_types.h> +#include <pcl/segmentation/sac_segmentation.h> + +void mpcl_compute_normals(pcl::PointCloud<pcl::PointXYZ> &cloud, + int ksearch, + double searchRadius, + pcl::PointCloud<pcl::Normal> &out); + +void mpcl_sacnormal_set_axis(pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal> &sac, + double ax, double ay, double az); + +void mpcl_extract(pcl::PointCloud<pcl::PointXYZ> &incloud, + pcl::PointCloud<pcl::PointXYZ> &outcloud, + pcl::PointIndices *indices, + bool negative); + +#endif diff --git a/pcl/pcl_defs.pxd b/pcl/pcl_defs.pxd new file mode 100644 index 0000000..7f92ab0 --- /dev/null +++ b/pcl/pcl_defs.pxd @@ -0,0 +1,205 @@ +from libc.stddef cimport size_t + +from libcpp.vector cimport vector +from libcpp.string cimport string +from libcpp cimport bool + +from shared_ptr cimport shared_ptr +from vector cimport vector as vector2 + +cdef extern from "pcl/point_cloud.h" namespace "pcl": + cdef cppclass PointCloud[T]: + PointCloud() except + + PointCloud(unsigned int, unsigned int) except + + unsigned int width + unsigned int height + bool is_dense + void resize(size_t) except + + size_t size() + T& operator[](size_t) + T& at(size_t) + T& at(int, int) + shared_ptr[PointCloud[T]] makeShared() + +cdef extern from "pcl/point_types.h" namespace "pcl": + cdef struct PointXYZ: + PointXYZ() + float x + float y + float z + cdef struct Normal: + pass + +cdef extern from "pcl/features/normal_3d.h" namespace "pcl": + cdef cppclass NormalEstimation[T, N]: + NormalEstimation() + +cdef extern from "pcl/segmentation/sac_segmentation.h" namespace "pcl": + cdef cppclass SACSegmentationFromNormals[T, N]: + SACSegmentationFromNormals() + void setOptimizeCoefficients (bool) + void setModelType (SacModel) + void setMethodType (int) + void setNormalDistanceWeight (float) + void setMaxIterations (int) + void setDistanceThreshold (float) + void setRadiusLimits (float, float) + void setInputCloud (shared_ptr[PointCloud[T]]) + void setInputNormals (shared_ptr[PointCloud[N]]) + void setEpsAngle (double ea) + void segment (PointIndices, ModelCoefficients) + + cdef cppclass SACSegmentation[T]: + void setOptimizeCoefficients (bool) + void setModelType (SacModel) + void setMethodType (int) + void setDistanceThreshold (float) + void setInputCloud (shared_ptr[PointCloud[T]]) + void segment (PointIndices, ModelCoefficients) + +ctypedef SACSegmentation[PointXYZ] SACSegmentation_t +ctypedef SACSegmentationFromNormals[PointXYZ,Normal] SACSegmentationNormal_t + +cdef extern from "pcl/surface/mls.h" namespace "pcl": + cdef cppclass MovingLeastSquares[I,O]: + MovingLeastSquares() + void setInputCloud (shared_ptr[PointCloud[I]]) + void setSearchRadius (double) + void setPolynomialOrder(bool) + void setPolynomialFit(int) + void process (PointCloud[O]) + +ctypedef MovingLeastSquares[PointXYZ,PointXYZ] MovingLeastSquares_t + +cdef extern from "pcl/search/kdtree.h" namespace "pcl::search": + cdef cppclass KdTree[T]: + KdTree() + +cdef extern from "Eigen/src/Core/util/Memory.h" namespace "Eigen": + cdef cppclass aligned_allocator[T]: + pass + +ctypedef aligned_allocator[PointXYZ] aligned_allocator_t +ctypedef vector2[PointXYZ, aligned_allocator_t] AlignedPointTVector_t + +cdef extern from "pcl/octree/octree_pointcloud.h" namespace "pcl::octree": + cdef cppclass OctreePointCloud[T]: + OctreePointCloud(double) + void setInputCloud (shared_ptr[PointCloud[T]]) + void defineBoundingBox() + void defineBoundingBox(double, double, double, double, double, double) + void addPointsFromInputCloud() + void deleteTree() + bool isVoxelOccupiedAtPoint(double, double, double) + int getOccupiedVoxelCenters(AlignedPointTVector_t) + void deleteVoxelAtPoint(PointXYZ) + +ctypedef OctreePointCloud[PointXYZ] OctreePointCloud_t + +cdef extern from "pcl/octree/octree_search.h" namespace "pcl::octree": + cdef cppclass OctreePointCloudSearch[T]: + OctreePointCloudSearch(double) + int radiusSearch (PointXYZ, double, vector[int], vector[float], unsigned int) + +ctypedef OctreePointCloudSearch[PointXYZ] OctreePointCloudSearch_t + +cdef extern from "pcl/ModelCoefficients.h" namespace "pcl": + cdef struct ModelCoefficients: + vector[float] values + +cdef extern from "pcl/PointIndices.h" namespace "pcl": + #FIXME: I made this a cppclass so that it can be allocated using new (cython barfs otherwise), and + #hence passed to shared_ptr. This is needed because if one passes memory allocated + #using malloc (which is required if this is a struct) to shared_ptr it aborts with + #std::bad_alloc + # + #I don't know if this is actually a problem. It is cpp and there is no incompatibility in + #promoting struct to class in this instance + cdef cppclass PointIndices: + vector[int] indices + +ctypedef PointIndices PointIndices_t +ctypedef shared_ptr[PointIndices] PointIndicesPtr_t + +cdef extern from "pcl/io/pcd_io.h" namespace "pcl::io": + int loadPCDFile(string file_name, PointCloud[PointXYZ] cloud) nogil + int savePCDFile(string file_name, PointCloud[PointXYZ] cloud, + bool binary_mode) nogil + +#http://dev.pointclouds.org/issues/624 +#cdef extern from "pcl/io/ply_io.h" namespace "pcl::io": +# int loadPLYFile (string file_name, PointCloud[PointXYZ] cloud) +# int savePLYFile (string file_name, PointCloud[PointXYZ] cloud, bool binary_mode) + +cdef extern from "pcl/sample_consensus/model_types.h" namespace "pcl": + cdef enum SacModel: + SACMODEL_PLANE + SACMODEL_LINE + SACMODEL_CIRCLE2D + SACMODEL_CIRCLE3D + SACMODEL_SPHERE + SACMODEL_CYLINDER + SACMODEL_CONE + SACMODEL_TORUS + SACMODEL_PARALLEL_LINE + SACMODEL_PERPENDICULAR_PLANE + SACMODEL_PARALLEL_LINES + SACMODEL_NORMAL_PLANE + #SACMODEL_NORMAL_SPHERE + SACMODEL_REGISTRATION + SACMODEL_PARALLEL_PLANE + SACMODEL_NORMAL_PARALLEL_PLANE + SACMODEL_STICK + +cdef extern from "pcl/sample_consensus/method_types.h" namespace "pcl": + cdef enum: + SAC_RANSAC = 0 + SAC_LMEDS = 1 + SAC_MSAC = 2 + SAC_RRANSAC = 3 + SAC_RMSAC = 4 + SAC_MLESAC = 5 + SAC_PROSAC = 6 + +ctypedef PointCloud[PointXYZ] PointCloud_t +ctypedef PointCloud[Normal] PointNormalCloud_t +ctypedef shared_ptr[PointCloud[PointXYZ]] PointCloudPtr_t + +cdef extern from "pcl/filters/statistical_outlier_removal.h" namespace "pcl": + cdef cppclass StatisticalOutlierRemoval[T]: + StatisticalOutlierRemoval() + void setMeanK (int nr_k) + void setStddevMulThresh (double std_mul) + void setNegative (bool negative) + void setInputCloud (shared_ptr[PointCloud[T]]) + void filter(PointCloud[T] c) + +ctypedef StatisticalOutlierRemoval[PointXYZ] StatisticalOutlierRemoval_t + +cdef extern from "pcl/filters/voxel_grid.h" namespace "pcl": + cdef cppclass VoxelGrid[T]: + VoxelGrid() + void setLeafSize (float, float, float) + void setInputCloud (shared_ptr[PointCloud[T]]) + void filter(PointCloud[T] c) + +ctypedef VoxelGrid[PointXYZ] VoxelGrid_t + +cdef extern from "pcl/filters/passthrough.h" namespace "pcl": + cdef cppclass PassThrough[T]: + PassThrough() + void setFilterFieldName (string field_name) + void setFilterLimits (float, float) + void setInputCloud (shared_ptr[PointCloud[T]]) + void filter(PointCloud[T] c) + +ctypedef PassThrough[PointXYZ] PassThrough_t + +cdef extern from "pcl/kdtree/kdtree_flann.h" namespace "pcl": + cdef cppclass KdTreeFLANN[T]: + KdTreeFLANN() + void setInputCloud (shared_ptr[PointCloud[T]]) + int nearestKSearch (PointCloud[T], + int, int, vector[int], vector[float]) + +ctypedef KdTreeFLANN[PointXYZ] KdTreeFLANN_t diff --git a/pcl/shared_ptr.pxd b/pcl/shared_ptr.pxd new file mode 100644 index 0000000..c3192f5 --- /dev/null +++ b/pcl/shared_ptr.pxd @@ -0,0 +1,11 @@ +from libcpp cimport bool + +cdef extern from "boost/smart_ptr/shared_ptr.hpp" namespace "boost": + cdef cppclass shared_ptr[T]: + shared_ptr() + shared_ptr(T*) + T* get() + bool unique() + long use_count() + void swap(shared_ptr[T]) + void reset(T*) diff --git a/pcl/vector.pxd b/pcl/vector.pxd new file mode 100644 index 0000000..050c28c --- /dev/null +++ b/pcl/vector.pxd @@ -0,0 +1,68 @@ +cdef extern from "<vector>" namespace "std": + cdef cppclass vector[T, A]: + cppclass iterator: + T& operator*() nogil + iterator operator++() nogil + iterator operator--() nogil + bint operator==(iterator) nogil + bint operator!=(iterator) nogil + bint operator<(iterator) nogil + bint operator>(iterator) nogil + bint operator<=(iterator) nogil + bint operator>=(iterator) nogil + cppclass reverse_iterator: + T& operator*() nogil + iterator operator++() nogil + iterator operator--() nogil + bint operator==(reverse_iterator) nogil + bint operator!=(reverse_iterator) nogil + bint operator<(reverse_iterator) nogil + bint operator>(reverse_iterator) nogil + bint operator<=(reverse_iterator) nogil + bint operator>=(reverse_iterator) nogil + #cppclass const_iterator(iterator): + # pass + #cppclass const_reverse_iterator(reverse_iterator): + # pass + vector() nogil except + + vector(vector&) nogil except + + vector(size_t) nogil except + + vector(size_t, T&) nogil except + + #vector[input_iterator](input_iterator, input_iterator) + T& operator[](size_t) nogil + #vector& operator=(vector&) + bint operator==(vector&, vector&) nogil + bint operator!=(vector&, vector&) nogil + bint operator<(vector&, vector&) nogil + bint operator>(vector&, vector&) nogil + bint operator<=(vector&, vector&) nogil + bint operator>=(vector&, vector&) nogil + void assign(size_t, T&) nogil + #void assign[input_iterator](input_iterator, input_iterator) + T& at(size_t) nogil + T& back() nogil + iterator begin() nogil + #const_iterator begin() + size_t capacity() nogil + void clear() nogil + bint empty() nogil + iterator end() nogil + #const_iterator end() + iterator erase(iterator) nogil + iterator erase(iterator, iterator) nogil + T& front() nogil + iterator insert(iterator, T&) nogil + void insert(iterator, size_t, T&) nogil + void insert(iterator, iterator, iterator) nogil + size_t max_size() nogil + void pop_back() nogil + void push_back(T&) nogil + reverse_iterator rbegin() nogil + #const_reverse_iterator rbegin() + reverse_iterator rend() nogil + #const_reverse_iterator rend() + void reserve(size_t) nogil + void resize(size_t) nogil + void resize(size_t, T&) nogil + size_t size() nogil + void swap(vector&) nogil |