Skip to content

Commit

Permalink
BIG changes introduced - migration from KdTree to pcl::Search
Browse files Browse the repository at this point in the history
git-svn-id: svn+ssh://svn.pointclouds.org/pcl/trunk@2778 a9d63959-f2ad-4865-b262-bf0e56cfafb6
  • Loading branch information
aichim committed Oct 15, 2011
1 parent f039b8e commit 433c6da
Show file tree
Hide file tree
Showing 79 changed files with 314 additions and 1,457 deletions.
4 changes: 2 additions & 2 deletions apps/include/pcl/apps/dominant_plane_segmentation.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <pcl/filters/passthrough.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/features/normal_3d.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/pcl_search.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
Expand All @@ -36,7 +36,7 @@ namespace pcl
typedef pcl::PointCloud<PointType> Cloud;
typedef typename Cloud::Ptr CloudPtr;
typedef typename Cloud::ConstPtr CloudConstPtr;
typedef typename pcl::KdTree<PointType>::Ptr KdTreePtr;
typedef typename pcl::search::KdTree<PointType>::Ptr KdTreePtr;

DominantPlaneSegmentation ()
{
Expand Down
8 changes: 4 additions & 4 deletions apps/include/pcl/apps/impl/dominant_plane_segmentation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute (
CloudPtr cloud_objects_ (new Cloud ());
CloudPtr cluster_object_ (new Cloud ());

KdTreePtr normals_tree_ (new pcl::KdTreeFLANN<PointType>);
KdTreePtr clusters_tree_ (new pcl::KdTreeFLANN<PointType>);
typename pcl::search::KdTree<PointType>::Ptr normals_tree_ (new pcl::search::KdTree<PointType>);
typename pcl::search::KdTree<PointType>::Ptr clusters_tree_ (new pcl::search::KdTree<PointType>);
clusters_tree_->setEpsilon (1);

// Normal estimation parameters
Expand Down Expand Up @@ -197,8 +197,8 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_full (
CloudPtr cloud_objects_ (new Cloud ());
CloudPtr cluster_object_ (new Cloud ());

KdTreePtr normals_tree_ (new pcl::KdTreeFLANN<PointType>);
KdTreePtr clusters_tree_ (new pcl::KdTreeFLANN<PointType>);
KdTreePtr normals_tree_ (new pcl::search::KdTree<PointType>);
KdTreePtr clusters_tree_ (new pcl::search::KdTree<PointType>);
clusters_tree_->setEpsilon (1);

// Normal estimation parameters
Expand Down
2 changes: 1 addition & 1 deletion apps/include/pcl/apps/vfh_nn_classifier.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace pcl

// Create an empty kdtree representation, and pass it to the objects.
// Its content will be filled inside the object, based on the given input dataset (as no other search surface is given).
typename KdTreeFLANN<PointT>::Ptr tree (new KdTreeFLANN<PointT> ());
typename pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT> ());

// Create the normal estimation class, and pass the input dataset to it
NormalEstimation<PointT, Normal> ne;
Expand Down
4 changes: 2 additions & 2 deletions apps/src/multiscale_feature_persistence_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ subsampleAndCalculateNormals (PointCloud<PointXYZ>::Ptr &cloud,
cloud_subsampled_normals = PointCloud<Normal>::Ptr (new PointCloud<Normal> ());
NormalEstimation<PointXYZ, Normal> normal_estimation_filter;
normal_estimation_filter.setInputCloud (cloud_subsampled);
KdTreeFLANN<PointXYZ>::Ptr search_tree (new KdTreeFLANN<PointXYZ>);
pcl::search::KdTree<PointXYZ>::Ptr search_tree (new pcl::search::KdTree<PointXYZ>);
normal_estimation_filter.setSearchMethod (search_tree);
normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
normal_estimation_filter.compute (*cloud_subsampled_normals);
Expand Down Expand Up @@ -65,7 +65,7 @@ main (int argc, char **argv)
FPFHEstimation<PointXYZ, Normal, FPFHSignature33>::Ptr fpfh_estimation (new FPFHEstimation<PointXYZ, Normal, FPFHSignature33> ());
fpfh_estimation->setInputCloud (cloud_subsampled);
fpfh_estimation->setInputNormals (cloud_subsampled_normals);
KdTreeFLANN<PointXYZ>::Ptr tree (new KdTreeFLANN<PointXYZ> ());
pcl::search::KdTree<PointXYZ>::Ptr tree (new pcl::search::KdTree<PointXYZ> ());
fpfh_estimation->setSearchMethod (tree);
feature_persistence.setFeatureEstimator (fpfh_estimation);
feature_persistence.setDistanceMetric (pcl::CS);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_boundary_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class OpenNIIntegralImageNormalEstimation
pass_.setDownsampleAllData (true);
pass_.setLeafSize (0.005, 0.005, 0.005);

pcl::OrganizedDataIndex<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::OrganizedDataIndex<pcl::PointXYZRGBNormal>);
pcl::search::OrganizedNeighbor<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBNormal>);
be_.setRadiusSearch (0.02);
be_.setSearchMethod (tree);
}
Expand Down
4 changes: 2 additions & 2 deletions apps/src/openni_feature_persistence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,15 +97,15 @@ class OpenNIFeaturePersistence
std::cout << "\n";

subsampling_filter_.setLeafSize (subsampling_leaf_size, subsampling_leaf_size, subsampling_leaf_size);
typename pcl::KdTreeFLANN<PointType>::Ptr normal_search_tree (new typename pcl::KdTreeFLANN<PointType>);
typename pcl::search::KdTree<PointType>::Ptr normal_search_tree (new typename pcl::search::KdTree<PointType>);
normal_estimation_filter_.setSearchMethod (normal_search_tree);
normal_estimation_filter_.setRadiusSearch (normal_search_radius);

feature_persistence_.setScalesVector (scales_vector);
feature_persistence_.setAlpha (alpha);

fpfh_estimation_.reset (new typename pcl::FPFHEstimationOMP<PointType, pcl::Normal, pcl::FPFHSignature33> ());
typename pcl::KdTreeFLANN<PointType>::Ptr fpfh_tree (new typename pcl::KdTreeFLANN<PointType> ());
typename pcl::search::KdTree<PointType>::Ptr fpfh_tree (new typename pcl::search::KdTree<PointType> ());
fpfh_estimation_->setSearchMethod (fpfh_tree);
feature_persistence_.setFeatureEstimator (fpfh_estimation_);
feature_persistence_.setDistanceMetric (pcl::CS);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_mls_smoothing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ class OpenNISmoothing
smoother_.setPolynomialFit (use_polynomial_fit);
smoother_.setPolynomialOrder (polynomial_order);

typename pcl::KdTree<PointType>::Ptr tree (new typename pcl::KdTreeFLANN<PointType> ());
typename pcl::search::KdTree<PointType>::Ptr tree (new typename pcl::search::KdTree<PointType> ());
smoother_.setSearchMethod (tree);
pcl::PointCloud<pcl::Normal>::Ptr smoother_normals (new pcl::PointCloud<pcl::Normal> ());
smoother_.setOutputNormals (smoother_normals);
Expand Down
9 changes: 2 additions & 7 deletions apps/src/openni_tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,12 +40,7 @@

#include <pcl/surface/convex_hull.h>

#include <pcl/search/auto.h>
#include <pcl/search/kdtree.h>
#include <pcl/search/impl/kdtree.hpp>
#include <pcl/search/octree.h>
#include <pcl/search/organized_neighbor.h>

#include <pcl/search/pcl_search.h>
#include <pcl/common/transforms.h>

#include <boost/format.hpp>
Expand Down Expand Up @@ -90,7 +85,7 @@ class OpenNISegmentTracking
typedef ParticleFilterOMPTracker<RefPointType, ParticleT> ParticleFilter;
//typedef ParticleFilterTracker<RefPointType, ParticleT> ParticleFilter;
typedef typename ParticleFilter::CoherencePtr CoherencePtr;
typedef typename pcl::KdTreeFLANN<PointType> KdTree;
typedef typename pcl::search::KdTree<PointType> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
OpenNISegmentTracking (const std::string& device_id, int thread_nr, bool use_convex_hull, bool use_cog)
: viewer_ ("PCL OpenNI Tracking Viewer")
Expand Down
2 changes: 1 addition & 1 deletion apps/src/ppf_object_recognition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ subsampleAndCalculateNormals (PointCloud<PointXYZ>::Ptr cloud)
PointCloud<Normal>::Ptr cloud_subsampled_normals (new PointCloud<Normal> ());
NormalEstimation<PointXYZ, Normal> normal_estimation_filter;
normal_estimation_filter.setInputCloud (cloud_subsampled);
KdTreeFLANN<PointXYZ>::Ptr search_tree (new KdTreeFLANN<PointXYZ>);
search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ>);
normal_estimation_filter.setSearchMethod (search_tree);
normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
normal_estimation_filter.compute (*cloud_subsampled_normals);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/pyramid_surface_matching.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ subsampleAndCalculateNormals (PointCloud<PointXYZ>::Ptr &cloud,
cloud_subsampled_normals = PointCloud<Normal>::Ptr (new PointCloud<Normal> ());
NormalEstimation<PointXYZ, Normal> normal_estimation_filter;
normal_estimation_filter.setInputCloud (cloud_subsampled);
KdTreeFLANN<PointXYZ>::Ptr search_tree (new KdTreeFLANN<PointXYZ>);
search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ>);
normal_estimation_filter.setSearchMethod (search_tree);
normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
normal_estimation_filter.compute (*cloud_subsampled_normals);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/surfel_smoothing_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ main (int argc, char **argv)

NormalEstimation<PointXYZ, Normal> normal_estimation;
normal_estimation.setInputCloud (cloud);
KdTreeFLANN<PointXYZ>::Ptr search_tree (new KdTreeFLANN<PointXYZ>);
search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ>);
normal_estimation.setSearchMethod (search_tree);
normal_estimation.setRadiusSearch (normal_search_radius);
normal_estimation.compute (*normals);
Expand Down
27 changes: 25 additions & 2 deletions features/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
set(SUBSYS_NAME features)
set(SUBSYS_DESC "Point cloud features library")
set(SUBSYS_DEPS common kdtree range_image)
set(SUBSYS_DEPS common search kdtree octree range_image)

set(build TRUE)
PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ON)
Expand Down Expand Up @@ -119,13 +119,36 @@ if(build)
PCL_ADD_SSE_FLAGS(${LIB_NAME})
PCL_ADD_OPENMP_FLAGS(${LIB_NAME})
PCL_LINK_OPENMP(${LIB_NAME})
target_link_libraries(${LIB_NAME} pcl_range_image pcl_kdtree)
target_link_libraries(${LIB_NAME} pcl_range_image pcl_search pcl_kdtree pcl_octree)
PCL_MAKE_PKGCONFIG(${LIB_NAME} ${SUBSYS_NAME} "${SUBSYS_DESC}"
"${SUBSYS_DEPS}" "" "" "" "")
# Install headers
PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME} ${incs})
PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME}/feature_evaluation ${feature_evaluation_incs})
PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME}/impl ${impl_incs})

set(border_srcs src/boundary.cpp
src/range_image_border_extractor.cpp
)

set(border_incs include/pcl/${SUBSYS_NAME}/boundary.h
include/pcl/${SUBSYS_NAME}/range_image_border_extractor.h
)

set(border_impl_incs include/pcl/${SUBSYS_NAME}/impl/boundary.hpp
include/pcl/${SUBSYS_NAME}/impl/range_image_border_extractor.hpp
)

set(LIB_NAME pcl_range_image_border_extractor)
PCL_ADD_LIBRARY(${LIB_NAME} ${SUBSYS_NAME} ${border_srcs} ${border_incs} ${border_impl_incs})
PCL_ADD_OPENMP_FLAGS(${LIB_NAME})
target_link_libraries(${LIB_NAME} pcl_range_image pcl_search pcl_kdtree pcl_octree)
PCL_MAKE_PKGCONFIG(${LIB_NAME} ${SUBSYS_NAME}
"Point cloud range image border extractor library"
"${SUBSYS_DEPS}" "" "" "" "")
# Install headers
PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME} ${border_incs})
PCL_ADD_INCLUDES(${SUBSYS_NAME} ${SUBSYS_NAME}/impl ${border_impl_incs})

add_subdirectory(test)
endif(build)
7 changes: 3 additions & 4 deletions features/include/pcl/features/cvfh.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,7 @@
#include <pcl/features/feature.h>
#include <pcl/features/normal_3d.h>
#include <pcl/features/vfh.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/pcl_search.h>
#include <pcl/common/common.h>

namespace pcl
Expand All @@ -65,7 +64,7 @@ namespace pcl
using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename pcl::KdTree<PointNormal>::Ptr KdTreePtr;
typedef typename pcl::search::Search<PointNormal>::Ptr KdTreePtr;
typedef typename pcl::NormalEstimation<PointNormal, PointNormal> NormalEstimator;
typedef typename pcl::VFHEstimation<PointInT, PointNT, pcl::VFHSignature308> VFHEstimator;

Expand Down Expand Up @@ -242,7 +241,7 @@ namespace pcl
void
extractEuclideanClustersSmooth (const pcl::PointCloud<pcl::PointNormal> &cloud,
const pcl::PointCloud<pcl::PointNormal> &normals, float tolerance,
const pcl::KdTree<pcl::PointNormal>::Ptr &tree,
const pcl::search::Search<pcl::PointNormal>::Ptr &tree,
std::vector<pcl::PointIndices> &clusters, double eps_angle,
unsigned int min_pts_per_cluster = 1,
unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ());
Expand Down
8 changes: 3 additions & 5 deletions features/include/pcl/features/feature.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,7 @@
#include "pcl/common/eigen.h"
#include "pcl/common/centroid.h"

#include "pcl/kdtree/kdtree.h"
#include "pcl/kdtree/kdtree_flann.h"
#include "pcl/kdtree/organized_data.h"
#include "pcl/search/search.h"

namespace pcl
{
Expand Down Expand Up @@ -105,8 +103,8 @@ namespace pcl
typedef boost::shared_ptr< Feature<PointInT, PointOutT> > Ptr;
typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > ConstPtr;

typedef typename pcl::KdTree<PointInT> KdTree;
typedef typename pcl::KdTree<PointInT>::Ptr KdTreePtr;
typedef typename pcl::search::Search<PointInT> KdTree;
typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;

typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,6 @@
#include <pcl/common/io.h>
#include <pcl/io/pcd_io.h>

#include <pcl/kdtree/kdtree.h>
#include <pcl/kdtree/kdtree_flann.h>

#include <pcl/filters/voxel_grid.h>

#include <pcl/features/feature.h>
Expand Down
Loading

0 comments on commit 433c6da

Please sign in to comment.