diff --git a/examples/features/example_difference_of_normals.cpp b/examples/features/example_difference_of_normals.cpp index 4c16c4e5f45..e8a13301f90 100644 --- a/examples/features/example_difference_of_normals.cpp +++ b/examples/features/example_difference_of_normals.cpp @@ -67,19 +67,6 @@ int main (int argc, char *argv[]) pcl::fromPCLPointCloud2 (blob, *cloud); std::cout << "done." << std::endl; - SearchPtr tree; - - if (cloud->isOrganized ()) - { - tree.reset (new pcl::search::OrganizedNeighbor ()); - } - else - { - tree.reset (new pcl::search::KdTree (false)); - } - - tree->setInputCloud (cloud); - PointCloud::Ptr small_cloud_downsampled; PointCloud::Ptr large_cloud_downsampled; @@ -110,7 +97,6 @@ int main (int argc, char *argv[]) // Compute normals using both small and large scales at each point pcl::NormalEstimationOMP ne; ne.setInputCloud (cloud); - ne.setSearchMethod (tree); /** * NOTE: setting viewpoint is very important, so that we can ensure diff --git a/filters/include/pcl/filters/impl/convolution_3d.hpp b/filters/include/pcl/filters/impl/convolution_3d.hpp index 009ff4bdce2..caa96bc188f 100644 --- a/filters/include/pcl/filters/impl/convolution_3d.hpp +++ b/filters/include/pcl/filters/impl/convolution_3d.hpp @@ -197,7 +197,7 @@ pcl::filters::Convolution3D::initCompute () // Initialize the spatial locator if (!tree_) { - tree_.reset (pcl::search::autoSelectMethod(surface_, false, pcl::search::Purpose::radius_search)); + tree_.reset (pcl::search::autoSelectMethod(surface_, false, pcl::search::Purpose::radius_search)); } else { diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index 8a9f6faae23..1910f2e2f77 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include #include diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 99a9288250e..b8d2d8c0578 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -439,7 +439,7 @@ class GeneralizedIterativeClosestPoint template void computeCovariances(typename pcl::PointCloud::ConstPtr cloud, - const typename pcl::search::KdTree::Ptr tree, + const typename pcl::search::Search::Ptr tree, MatricesVector& cloud_covariances); /** \return trace of mat1 . mat2 diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index 78490b66370..1971bde5117 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -72,7 +72,7 @@ template void GeneralizedIterativeClosestPoint::computeCovariances( typename pcl::PointCloud::ConstPtr cloud, - const typename pcl::search::KdTree::Ptr kdtree, + const typename pcl::search::Search::Ptr kdtree, MatricesVector& cloud_covariances) { if (k_correspondences_ > static_cast(cloud->size())) { diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index 31533621a82..395a7f102e7 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -45,6 +45,7 @@ #include #include #include +#include #include @@ -58,8 +59,8 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud::ConstPtr& cloud const float max_dist_sqr = max_dist * max_dist; const std::size_t s = cloud->size(); - pcl::search::KdTree tree; - tree.setInputCloud(cloud); + typename pcl::search::Search::Ptr tree(pcl::search::autoSelectMethod( + cloud, true, pcl::search::Purpose::many_knn_search)); float mean_dist = 0.f; int num = 0; @@ -71,7 +72,7 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud::ConstPtr& cloud firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) \ firstprivate(s, max_dist_sqr) num_threads(nr_threads) for (int i = 0; i < 1000; i++) { - tree.nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr); + tree->nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr); if (dists_sqr[1] < max_dist_sqr) { mean_dist += std::sqrt(dists_sqr[1]); num++; @@ -92,8 +93,8 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud::ConstPtr& cloud const float max_dist_sqr = max_dist * max_dist; const std::size_t s = indices.size(); - pcl::search::KdTree tree; - tree.setInputCloud(cloud); + typename pcl::search::Search::Ptr tree(pcl::search::autoSelectMethod( + cloud, true, pcl::search::Purpose::many_knn_search)); float mean_dist = 0.f; int num = 0; @@ -109,7 +110,7 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud::ConstPtr& cloud firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads) #endif for (int i = 0; i < 1000; i++) { - tree.nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr); + tree->nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr); if (dists_sqr[1] < max_dist_sqr) { mean_dist += std::sqrt(dists_sqr[1]); num++; diff --git a/search/include/pcl/search/auto.h b/search/include/pcl/search/auto.h index 605177557c4..6cb9f679e1e 100644 --- a/search/include/pcl/search/auto.h +++ b/search/include/pcl/search/auto.h @@ -28,7 +28,20 @@ namespace pcl { * \param[in] purpose Optional, can be used to give more information about what this search method will be used for, to achieve optimal performance */ template - pcl::search::Search * autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, bool sorted_results, Purpose purpose = Purpose::undefined); + pcl::search::Search * autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, bool sorted_results, Purpose purpose = Purpose::undefined) + { + return autoSelectMethod(cloud, pcl::IndicesConstPtr(), sorted_results, purpose); + } + + /** + * Automatically select the fastest search method for the given point cloud. Make sure to delete the returned object after use! + * \param[in] cloud Point cloud, this function will pass it to the search method via setInputCloud + * \param[in] indices Will be passed to the search method via setInputCloud, together with the point cloud + * \param[in] sorted_results Whether the search method should always return results sorted by distance (may be slower than unsorted) + * \param[in] purpose Optional, can be used to give more information about what this search method will be used for, to achieve optimal performance + */ + template + pcl::search::Search * autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, Purpose purpose = Purpose::undefined); } // namespace search } // namespace pcl diff --git a/search/include/pcl/search/impl/auto.hpp b/search/include/pcl/search/impl/auto.hpp index 96cb3733ee1..62ef2313060 100644 --- a/search/include/pcl/search/impl/auto.hpp +++ b/search/include/pcl/search/impl/auto.hpp @@ -18,17 +18,17 @@ #include template -pcl::search::Search * pcl::search::autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, bool sorted_results, pcl::search::Purpose purpose) { +pcl::search::Search * pcl::search::autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, pcl::search::Purpose purpose) { pcl::search::Search * searcher = nullptr; if (cloud->isOrganized ()) { searcher = new pcl::search::OrganizedNeighbor (sorted_results); - if(searcher->setInputCloud (cloud)) { // may return false if OrganizedNeighbor cannot work with the cloud, then use another search method instead + if(searcher->setInputCloud (cloud, indices)) { // may return false if OrganizedNeighbor cannot work with the cloud, then use another search method instead return searcher; } } #if PCL_HAS_NANOFLANN searcher = new pcl::search::KdTreeNanoflann (sorted_results, (purpose == pcl::search::Purpose::one_knn_search ? 10 : 20)); - if(searcher->setInputCloud (cloud)) { + if(searcher->setInputCloud (cloud, indices)) { return searcher; } #else @@ -36,16 +36,16 @@ pcl::search::Search * pcl::search::autoSelectMethod(const typename pcl:: #endif #if PCL_HAS_FLANN searcher = new pcl::search::KdTree (sorted_results); - if(searcher->setInputCloud (cloud)) { + if(searcher->setInputCloud (cloud, indices)) { return searcher; } #endif // If nothing else works, use brute force method searcher = new pcl::search::BruteForce (sorted_results); - searcher->setInputCloud (cloud); + searcher->setInputCloud (cloud, indices); return searcher; } -#define PCL_INSTANTIATE_AutoSelectMethod(T) template PCL_EXPORTS pcl::search::Search * pcl::search::autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, bool sorted_results, pcl::search::Purpose purpose); +#define PCL_INSTANTIATE_AutoSelectMethod(T) template PCL_EXPORTS pcl::search::Search * pcl::search::autoSelectMethod(const typename pcl::PointCloud::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, pcl::search::Purpose purpose); #endif //#ifndef PCL_SEARCH_AUTO_IMPL_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp b/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp index 5eef5e59919..7dd4f2f2b44 100644 --- a/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp @@ -38,8 +38,7 @@ #define PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_ #include -#include // for OrganizedNeighbor -#include // for KdTree +#include template void pcl::ConditionalEuclideanClustering::segment (pcl::IndicesClusters &clusters) @@ -59,12 +58,12 @@ pcl::ConditionalEuclideanClustering::segment (pcl::IndicesClusters &clus // Initialize the search class if (!searcher_) { - if (input_->isOrganized ()) - searcher_.reset (new pcl::search::OrganizedNeighbor (false)); // not requiring sorted results is much faster - else - searcher_.reset (new pcl::search::KdTree (false)); // not requiring sorted results is much faster + searcher_.reset (pcl::search::autoSelectMethod(input_, indices_, false, pcl::search::Purpose::radius_search)); // not requiring sorted results is much faster + } + else + { + searcher_->setInputCloud (input_, indices_); } - searcher_->setInputCloud (input_, indices_); // If searcher_ gives sorted results, we can skip the first one because it is the query point itself const int nn_start_idx = searcher_->getSortedResults () ? 1 : 0; diff --git a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp index 8c1fb79aa1e..1920baf4906 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp @@ -39,7 +39,7 @@ #define PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ #include -#include // for OrganizedNeighbor +#include ////////////////////////////////////////////////////////////////////////////////////////////// template void @@ -234,14 +234,13 @@ pcl::EuclideanClusterExtraction::extract (std::vector &clu // Initialize the spatial locator if (!tree_) { - if (input_->isOrganized ()) - tree_.reset (new pcl::search::OrganizedNeighbor ()); - else - tree_.reset (new pcl::search::KdTree (false)); + tree_.reset (pcl::search::autoSelectMethod(input_, indices_, false, pcl::search::Purpose::radius_search)); + } + else + { + // Send the input dataset to the spatial locator + tree_->setInputCloud (input_, indices_); } - - // Send the input dataset to the spatial locator - tree_->setInputCloud (input_, indices_); extractEuclideanClusters (*input_, *indices_, tree_, static_cast (cluster_tolerance_), clusters, min_pts_per_cluster_, max_pts_per_cluster_); //tree_->setInputCloud (input_); diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index 64364911886..3d6fafd9ee1 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -42,7 +42,7 @@ #include // for boykov_kolmogorov_max_flow #include #include -#include +#include #include ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -290,7 +290,13 @@ pcl::MinCutSegmentation::buildGraph () return (false); if (!search_) - search_.reset (new pcl::search::KdTree); + { + search_.reset (pcl::search::autoSelectMethod(input_, indices_, true, pcl::search::Purpose::many_knn_search)); + } + else + { + search_->setInputCloud (input_, indices_); + } graph_.reset (new mGraph); @@ -325,7 +331,6 @@ pcl::MinCutSegmentation::buildGraph () pcl::Indices neighbours; std::vector distances; - search_->setInputCloud (input_, indices_); for (std::size_t i_point = 0; i_point < number_of_indices; i_point++) { index_t point_index = (*indices_)[i_point]; diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index 862af012807..06e056f2e57 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -46,7 +46,7 @@ #include // for pcl::isFinite #include // for PCL_ERROR #include -#include +#include #include #include @@ -303,18 +303,22 @@ pcl::RegionGrowing::prepareForSegmentation () if (neighbour_number_ == 0) return (false); - // if user didn't set search method - if (!search_) - search_.reset (new pcl::search::KdTree); - if (indices_) { if (indices_->empty ()) PCL_ERROR ("[pcl::RegionGrowing::prepareForSegmentation] Empty given indices!\n"); - search_->setInputCloud (input_, indices_); + if (!search_) + search_.reset (pcl::search::autoSelectMethod(input_, indices_, true, pcl::search::Purpose::many_knn_search)); + else + search_->setInputCloud (input_, indices_); } else - search_->setInputCloud (input_); + { + if (!search_) + search_.reset (pcl::search::autoSelectMethod(input_, true, pcl::search::Purpose::many_knn_search)); + else + search_->setInputCloud (input_); + } return (true); } diff --git a/surface/include/pcl/surface/gp3.h b/surface/include/pcl/surface/gp3.h index 9a3cdbbd3f2..98d91fd8d16 100644 --- a/surface/include/pcl/surface/gp3.h +++ b/surface/include/pcl/surface/gp3.h @@ -42,8 +42,6 @@ // PCL includes #include -#include - #include #include // for cross @@ -138,9 +136,6 @@ namespace pcl using MeshConstruction::input_; using MeshConstruction::indices_; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - using PointCloudIn = pcl::PointCloud; using PointCloudInPtr = typename PointCloudIn::Ptr; using PointCloudInConstPtr = typename PointCloudIn::ConstPtr; diff --git a/surface/include/pcl/surface/grid_projection.h b/surface/include/pcl/surface/grid_projection.h index f49f8b82cca..c037ca5c0fe 100644 --- a/surface/include/pcl/surface/grid_projection.h +++ b/surface/include/pcl/surface/grid_projection.h @@ -83,9 +83,6 @@ namespace pcl using PointCloudPtr = typename pcl::PointCloud::Ptr; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - /** \brief Data leaf. */ struct Leaf { diff --git a/surface/include/pcl/surface/impl/concave_hull.hpp b/surface/include/pcl/surface/impl/concave_hull.hpp index d769a656018..ea032ef4a71 100644 --- a/surface/include/pcl/surface/impl/concave_hull.hpp +++ b/surface/include/pcl/surface/impl/concave_hull.hpp @@ -566,8 +566,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: if (keep_information_) { // build a tree with the original points - pcl::KdTreeFLANN tree (true); - tree.setInputCloud (input_, indices_); + typename pcl::search::Search::Ptr tree(pcl::search::autoSelectMethod(input_, indices_, false, pcl::search::Purpose::one_knn_search)); pcl::Indices neighbor; std::vector distances; @@ -581,7 +580,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: for (const auto& point: alpha_shape) { - tree.nearestKSearch (point, 1, neighbor, distances); + tree->nearestKSearch (point, 1, neighbor, distances); hull_indices_.indices.push_back (neighbor[0]); } diff --git a/surface/include/pcl/surface/impl/reconstruction.hpp b/surface/include/pcl/surface/impl/reconstruction.hpp index 3b5e6ea2761..8f6d95197af 100644 --- a/surface/include/pcl/surface/impl/reconstruction.hpp +++ b/surface/include/pcl/surface/impl/reconstruction.hpp @@ -41,8 +41,7 @@ #define PCL_SURFACE_RECONSTRUCTION_IMPL_H_ #include // for pcl::toPCLPointCloud2 -#include // for KdTree -#include // for OrganizedNeighbor +#include namespace pcl @@ -67,14 +66,13 @@ SurfaceReconstruction::reconstruct (pcl::PolygonMesh &output) { if (!tree_) { - if (input_->isOrganized ()) - tree_.reset (new pcl::search::OrganizedNeighbor ()); - else - tree_.reset (new pcl::search::KdTree (false)); + tree_.reset (pcl::search::autoSelectMethod(input_, indices_, false)); + } + else + { + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); } - - // Send the surface dataset to the spatial locator - tree_->setInputCloud (input_, indices_); } // Set up the output dataset @@ -108,14 +106,13 @@ SurfaceReconstruction::reconstruct (pcl::PointCloud &points, { if (!tree_) { - if (input_->isOrganized ()) - tree_.reset (new pcl::search::OrganizedNeighbor ()); - else - tree_.reset (new pcl::search::KdTree (false)); + tree_.reset (pcl::search::autoSelectMethod(input_, indices_, false)); + } + else + { + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); } - - // Send the surface dataset to the spatial locator - tree_->setInputCloud (input_, indices_); } // Set up the output dataset @@ -147,14 +144,13 @@ MeshConstruction::reconstruct (pcl::PolygonMesh &output) { if (!tree_) { - if (input_->isOrganized ()) - tree_.reset (new pcl::search::OrganizedNeighbor ()); - else - tree_.reset (new pcl::search::KdTree (false)); + tree_.reset (pcl::search::autoSelectMethod(input_, indices_, false)); + } + else + { + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); } - - // Send the surface dataset to the spatial locator - tree_->setInputCloud (input_, indices_); } // Set up the output dataset @@ -182,14 +178,13 @@ MeshConstruction::reconstruct (std::vector &polygons) { if (!tree_) { - if (input_->isOrganized ()) - tree_.reset (new pcl::search::OrganizedNeighbor ()); - else - tree_.reset (new pcl::search::KdTree (false)); + tree_.reset(pcl::search::autoSelectMethod(input_, indices_, false)); + } + else + { + // Send the surface dataset to the spatial locator + tree_->setInputCloud (input_, indices_); } - - // Send the surface dataset to the spatial locator - tree_->setInputCloud (input_, indices_); } // Set up the output dataset diff --git a/surface/include/pcl/surface/impl/texture_mapping.hpp b/surface/include/pcl/surface/impl/texture_mapping.hpp index 95ebc342f44..1cd8d6269d6 100644 --- a/surface/include/pcl/surface/impl/texture_mapping.hpp +++ b/surface/include/pcl/surface/impl/texture_mapping.hpp @@ -39,6 +39,7 @@ #define PCL_SURFACE_IMPL_TEXTURE_MAPPING_HPP_ #include +#include #include #include diff --git a/surface/include/pcl/surface/marching_cubes.h b/surface/include/pcl/surface/marching_cubes.h index c09c0aafa50..57a32f16a2e 100644 --- a/surface/include/pcl/surface/marching_cubes.h +++ b/surface/include/pcl/surface/marching_cubes.h @@ -372,9 +372,6 @@ namespace pcl using PointCloudPtr = typename pcl::PointCloud::Ptr; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - /** \brief Constructor. */ MarchingCubes (const float percentage_extend_grid = 0.0f, const float iso_level = 0.0f) : diff --git a/surface/include/pcl/surface/marching_cubes_hoppe.h b/surface/include/pcl/surface/marching_cubes_hoppe.h index 7f66bdd960a..6b7745a534d 100644 --- a/surface/include/pcl/surface/marching_cubes_hoppe.h +++ b/surface/include/pcl/surface/marching_cubes_hoppe.h @@ -68,9 +68,6 @@ namespace pcl using PointCloudPtr = typename pcl::PointCloud::Ptr; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - /** \brief Constructor. */ MarchingCubesHoppe (const float dist_ignore = -1.0f, diff --git a/surface/include/pcl/surface/marching_cubes_rbf.h b/surface/include/pcl/surface/marching_cubes_rbf.h index 8acaed9b8cc..f19e5e30644 100644 --- a/surface/include/pcl/surface/marching_cubes_rbf.h +++ b/surface/include/pcl/surface/marching_cubes_rbf.h @@ -72,9 +72,6 @@ namespace pcl using PointCloudPtr = typename pcl::PointCloud::Ptr; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - /** \brief Constructor. */ MarchingCubesRBF (const float off_surface_epsilon = 0.1f, diff --git a/surface/include/pcl/surface/poisson.h b/surface/include/pcl/surface/poisson.h index 9fca5b4b343..77ba2327ead 100644 --- a/surface/include/pcl/surface/poisson.h +++ b/surface/include/pcl/surface/poisson.h @@ -69,9 +69,6 @@ namespace pcl using PointCloudPtr = typename pcl::PointCloud::Ptr; - using KdTree = pcl::KdTree; - using KdTreePtr = typename KdTree::Ptr; - /** \brief Constructor that sets all the parameters to working default values. */ Poisson (); diff --git a/test/surface/test_concave_hull.cpp b/test/surface/test_concave_hull.cpp index 3f863d71625..31a88b0429a 100644 --- a/test/surface/test_concave_hull.cpp +++ b/test/surface/test_concave_hull.cpp @@ -45,6 +45,7 @@ #include #include #include // for SACMODEL_PLANE +#include #include diff --git a/test/surface/test_convex_hull.cpp b/test/surface/test_convex_hull.cpp index 0ad3b8e9644..f814cb89ae8 100644 --- a/test/surface/test_convex_hull.cpp +++ b/test/surface/test_convex_hull.cpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include #include // for SACMODEL_PLANE diff --git a/test/surface/test_gp3.cpp b/test/surface/test_gp3.cpp index d7eed86d891..c647dd00342 100644 --- a/test/surface/test_gp3.cpp +++ b/test/surface/test_gp3.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include diff --git a/test/surface/test_grid_projection.cpp b/test/surface/test_grid_projection.cpp index 97c1deb5ca4..5cdef266fe3 100644 --- a/test/surface/test_grid_projection.cpp +++ b/test/surface/test_grid_projection.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include using namespace pcl; diff --git a/test/surface/test_marching_cubes.cpp b/test/surface/test_marching_cubes.cpp index ab093eaf83c..54491d649f5 100644 --- a/test/surface/test_marching_cubes.cpp +++ b/test/surface/test_marching_cubes.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include diff --git a/test/surface/test_organized_fast_mesh.cpp b/test/surface/test_organized_fast_mesh.cpp index b66ce2068c4..298081ea4fc 100644 --- a/test/surface/test_organized_fast_mesh.cpp +++ b/test/surface/test_organized_fast_mesh.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include using namespace pcl; diff --git a/test/surface/test_poisson.cpp b/test/surface/test_poisson.cpp index b6a0ec1bf10..01d75f67d57 100644 --- a/test/surface/test_poisson.cpp +++ b/test/surface/test_poisson.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include diff --git a/tools/compute_cloud_error.cpp b/tools/compute_cloud_error.cpp index 6b8b25a5283..6c60ac64ee3 100644 --- a/tools/compute_cloud_error.cpp +++ b/tools/compute_cloud_error.cpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include using namespace pcl; @@ -112,8 +112,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &cloud_source, const pcl::PCLPointC { // print_highlight (stderr, "Computing using the nearest neighbor correspondence heuristic.\n"); - KdTreeFLANN::Ptr tree (new KdTreeFLANN ()); - tree->setInputCloud (xyz_target); + pcl::search::Search::Ptr tree(pcl::search::autoSelectMethod(xyz_target, false, pcl::search::Purpose::one_knn_search)); for (std::size_t point_i = 0; point_i < xyz_source->size (); ++ point_i) { @@ -144,8 +143,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &cloud_source, const pcl::PCLPointC PointCloud::Ptr normals_target (new PointCloud ()); fromPCLPointCloud2 (*cloud_target, *normals_target); - KdTreeFLANN::Ptr tree (new KdTreeFLANN ()); - tree->setInputCloud (xyz_target); + pcl::search::Search::Ptr tree(pcl::search::autoSelectMethod(xyz_target, false, pcl::search::Purpose::one_knn_search)); for (std::size_t point_i = 0; point_i < xyz_source->size (); ++ point_i) { diff --git a/tools/fpfh_estimation.cpp b/tools/fpfh_estimation.cpp index 248487aadb1..ab9f7f41162 100644 --- a/tools/fpfh_estimation.cpp +++ b/tools/fpfh_estimation.cpp @@ -43,7 +43,6 @@ #include #include #include -#include // for KdTree using namespace pcl; using namespace pcl::io; @@ -104,7 +103,6 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output FPFHEstimation ne; ne.setInputCloud (xyznormals); ne.setInputNormals (xyznormals); - ne.setSearchMethod (search::KdTree::Ptr (new search::KdTree)); ne.setKSearch (k); ne.setRadiusSearch (radius); diff --git a/tools/gp3_surface.cpp b/tools/gp3_surface.cpp index 421aad041af..d280bc12e4d 100644 --- a/tools/gp3_surface.cpp +++ b/tools/gp3_surface.cpp @@ -97,7 +97,6 @@ compute (const PointCloud::Ptr &input, pcl::PolygonMesh &output, cloud->is_dense = true; GreedyProjectionTriangulation gpt; - gpt.setSearchMethod (pcl::search::KdTree::Ptr (new pcl::search::KdTree)); gpt.setInputCloud (cloud); gpt.setSearchRadius (radius); gpt.setMu (mu); diff --git a/tools/mls_smoothing.cpp b/tools/mls_smoothing.cpp index 1a95bdd178e..436824f86e1 100644 --- a/tools/mls_smoothing.cpp +++ b/tools/mls_smoothing.cpp @@ -42,7 +42,6 @@ #include #include #include -#include // for KdTree using namespace pcl; using namespace pcl::io; @@ -122,9 +121,6 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, mls.setUpsamplingStepSize (0.015); mls.setDilationIterations (2); mls.setDilationVoxelSize (0.01f); - - search::KdTree::Ptr tree (new search::KdTree ()); - mls.setSearchMethod (tree); mls.setComputeNormals (true); PCL_INFO ("Computing smoothed surface and normals with search_radius %f , sqr_gaussian_param %f, polynomial order %d\n",