Skip to content

Commit e96661e

Browse files
committed
Replace more instances of KdTreeFLANN and pcl::search::KdTree
1 parent 3968dd4 commit e96661e

32 files changed

+101
-120
lines changed

examples/features/example_difference_of_normals.cpp

Lines changed: 0 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -67,19 +67,6 @@ int main (int argc, char *argv[])
6767
pcl::fromPCLPointCloud2 (blob, *cloud);
6868
std::cout << "done." << std::endl;
6969

70-
SearchPtr tree;
71-
72-
if (cloud->isOrganized ())
73-
{
74-
tree.reset (new pcl::search::OrganizedNeighbor<PointT> ());
75-
}
76-
else
77-
{
78-
tree.reset (new pcl::search::KdTree<PointT> (false));
79-
}
80-
81-
tree->setInputCloud (cloud);
82-
8370
PointCloud<PointT>::Ptr small_cloud_downsampled;
8471
PointCloud<PointT>::Ptr large_cloud_downsampled;
8572

@@ -110,7 +97,6 @@ int main (int argc, char *argv[])
11097
// Compute normals using both small and large scales at each point
11198
pcl::NormalEstimationOMP<PointT, PointNT> ne;
11299
ne.setInputCloud (cloud);
113-
ne.setSearchMethod (tree);
114100

115101
/**
116102
* NOTE: setting viewpoint is very important, so that we can ensure

filters/include/pcl/filters/impl/convolution_3d.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,7 @@ pcl::filters::Convolution3D<PointInT, PointOutT, KernelT>::initCompute ()
197197
// Initialize the spatial locator
198198
if (!tree_)
199199
{
200-
tree_.reset (pcl::search::autoSelectMethod<PointT>(surface_, false, pcl::search::Purpose::radius_search));
200+
tree_.reset (pcl::search::autoSelectMethod<PointInT>(surface_, false, pcl::search::Purpose::radius_search));
201201
}
202202
else
203203
{

gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@
4444
#include <pcl/common/transforms.h>
4545
#include <pcl/features/normal_3d.h>
4646
#include <pcl/visualization/pcl_visualizer.h>
47+
#include <pcl/search/kdtree.h>
4748
#include <pcl/surface/texture_mapping.h>
4849
#include <pcl/io/vtk_lib_io.h>
4950
#include <pcl/io/ply_io.h>

registration/include/pcl/registration/gicp.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -439,7 +439,7 @@ class GeneralizedIterativeClosestPoint
439439
template <typename PointT>
440440
void
441441
computeCovariances(typename pcl::PointCloud<PointT>::ConstPtr cloud,
442-
const typename pcl::search::KdTree<PointT>::Ptr tree,
442+
const typename pcl::search::Search<PointT>::Ptr tree,
443443
MatricesVector& cloud_covariances);
444444

445445
/** \return trace of mat1 . mat2

registration/include/pcl/registration/impl/gicp.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ template <typename PointT>
7272
void
7373
GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::computeCovariances(
7474
typename pcl::PointCloud<PointT>::ConstPtr cloud,
75-
const typename pcl::search::KdTree<PointT>::Ptr kdtree,
75+
const typename pcl::search::Search<PointT>::Ptr kdtree,
7676
MatricesVector& cloud_covariances)
7777
{
7878
if (k_correspondences_ > static_cast<int>(cloud->size())) {

registration/include/pcl/registration/impl/ia_fpcs.hpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545
#include <pcl/registration/ia_fpcs.h>
4646
#include <pcl/registration/transformation_estimation_3point.h>
4747
#include <pcl/sample_consensus/sac_model_plane.h>
48+
#include <pcl/search/auto.h>
4849

4950
#include <limits>
5051

@@ -58,8 +59,8 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
5859
const float max_dist_sqr = max_dist * max_dist;
5960
const std::size_t s = cloud->size();
6061

61-
pcl::search::KdTree<PointT> tree;
62-
tree.setInputCloud(cloud);
62+
typename pcl::search::Search<PointT>::Ptr tree(
63+
pcl::search::autoSelectMethod<PointT>(cloud, true));
6364

6465
float mean_dist = 0.f;
6566
int num = 0;
@@ -71,7 +72,7 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
7172
firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) \
7273
firstprivate(s, max_dist_sqr) num_threads(nr_threads)
7374
for (int i = 0; i < 1000; i++) {
74-
tree.nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr);
75+
tree->nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr);
7576
if (dists_sqr[1] < max_dist_sqr) {
7677
mean_dist += std::sqrt(dists_sqr[1]);
7778
num++;
@@ -92,8 +93,8 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
9293
const float max_dist_sqr = max_dist * max_dist;
9394
const std::size_t s = indices.size();
9495

95-
pcl::search::KdTree<PointT> tree;
96-
tree.setInputCloud(cloud);
96+
typename pcl::search::Search<PointT>::Ptr tree(
97+
pcl::search::autoSelectMethod<PointT>(cloud, true));
9798

9899
float mean_dist = 0.f;
99100
int num = 0;
@@ -109,7 +110,7 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud<PointT>::ConstPtr& cloud
109110
firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads)
110111
#endif
111112
for (int i = 0; i < 1000; i++) {
112-
tree.nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr);
113+
tree->nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr);
113114
if (dists_sqr[1] < max_dist_sqr) {
114115
mean_dist += std::sqrt(dists_sqr[1]);
115116
num++;

search/include/pcl/search/auto.h

Lines changed: 14 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,20 @@ namespace pcl {
2828
* \param[in] purpose Optional, can be used to give more information about what this search method will be used for, to achieve optimal performance
2929
*/
3030
template<typename PointT>
31-
pcl::search::Search<PointT> * autoSelectMethod(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, bool sorted_results, Purpose purpose = Purpose::undefined);
31+
pcl::search::Search<PointT> * autoSelectMethod(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, bool sorted_results, Purpose purpose = Purpose::undefined)
32+
{
33+
return autoSelectMethod<PointT>(cloud, pcl::IndicesConstPtr(), sorted_results, purpose);
34+
}
35+
36+
/**
37+
* Automatically select the fastest search method for the given point cloud. Make sure to delete the returned object after use!
38+
* \param[in] cloud Point cloud, this function will pass it to the search method via setInputCloud
39+
* \param[in] indices Will be passed to the search method via setInputCloud, together with the point cloud
40+
* \param[in] sorted_results Whether the search method should always return results sorted by distance (may be slower than unsorted)
41+
* \param[in] purpose Optional, can be used to give more information about what this search method will be used for, to achieve optimal performance
42+
*/
43+
template<typename PointT>
44+
pcl::search::Search<PointT> * autoSelectMethod(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, Purpose purpose = Purpose::undefined);
3245
} // namespace search
3346
} // namespace pcl
3447

search/include/pcl/search/impl/auto.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -18,34 +18,34 @@
1818
#include <pcl/search/organized.h>
1919

2020
template<typename PointT>
21-
pcl::search::Search<PointT> * pcl::search::autoSelectMethod(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, bool sorted_results, pcl::search::Purpose purpose) {
21+
pcl::search::Search<PointT> * pcl::search::autoSelectMethod(const typename pcl::PointCloud<PointT>::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, pcl::search::Purpose purpose) {
2222
pcl::search::Search<PointT> * searcher = nullptr;
2323
if (cloud->isOrganized ()) {
2424
searcher = new pcl::search::OrganizedNeighbor<PointT> (sorted_results);
25-
if(searcher->setInputCloud (cloud)) { // may return false if OrganizedNeighbor cannot work with the cloud, then use another search method instead
25+
if(searcher->setInputCloud (cloud, indices)) { // may return false if OrganizedNeighbor cannot work with the cloud, then use another search method instead
2626
return searcher;
2727
}
2828
}
2929
#if PCL_HAS_NANOFLANN
3030
searcher = new pcl::search::KdTreeNanoflann<PointT> (sorted_results, (purpose == pcl::search::Purpose::one_knn_search ? 10 : 20));
31-
if(searcher->setInputCloud (cloud)) {
31+
if(searcher->setInputCloud (cloud, indices)) {
3232
return searcher;
3333
}
3434
#else
3535
pcl::utils::ignore(purpose);
3636
#endif
3737
#if PCL_HAS_FLANN
3838
searcher = new pcl::search::KdTree<PointT> (sorted_results);
39-
if(searcher->setInputCloud (cloud)) {
39+
if(searcher->setInputCloud (cloud, indices)) {
4040
return searcher;
4141
}
4242
#endif
4343
// If nothing else works, use brute force method
4444
searcher = new pcl::search::BruteForce<PointT> (sorted_results);
45-
searcher->setInputCloud (cloud);
45+
searcher->setInputCloud (cloud, indices);
4646
return searcher;
4747
}
4848

49-
#define PCL_INSTANTIATE_AutoSelectMethod(T) template PCL_EXPORTS pcl::search::Search<T> * pcl::search::autoSelectMethod<T>(const typename pcl::PointCloud<T>::ConstPtr& cloud, bool sorted_results, pcl::search::Purpose purpose);
49+
#define PCL_INSTANTIATE_AutoSelectMethod(T) template PCL_EXPORTS pcl::search::Search<T> * pcl::search::autoSelectMethod<T>(const typename pcl::PointCloud<T>::ConstPtr& cloud, const pcl::IndicesConstPtr& indices, bool sorted_results, pcl::search::Purpose purpose);
5050

5151
#endif //#ifndef PCL_SEARCH_AUTO_IMPL_HPP_

segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,7 @@
3838
#define PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
3939

4040
#include <pcl/segmentation/conditional_euclidean_clustering.h>
41-
#include <pcl/search/organized.h> // for OrganizedNeighbor
42-
#include <pcl/search/kdtree.h> // for KdTree
41+
#include <pcl/search/auto.h>
4342

4443
template<typename PointT> void
4544
pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clusters)
@@ -59,12 +58,12 @@ pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clus
5958
// Initialize the search class
6059
if (!searcher_)
6160
{
62-
if (input_->isOrganized ())
63-
searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> (false)); // not requiring sorted results is much faster
64-
else
65-
searcher_.reset (new pcl::search::KdTree<PointT> (false)); // not requiring sorted results is much faster
61+
searcher_.reset (pcl::search::autoSelectMethod<PointT>(input_, indices_, false)); // not requiring sorted results is much faster
62+
}
63+
else
64+
{
65+
searcher_->setInputCloud (input_, indices_);
6666
}
67-
searcher_->setInputCloud (input_, indices_);
6867
// If searcher_ gives sorted results, we can skip the first one because it is the query point itself
6968
const int nn_start_idx = searcher_->getSortedResults () ? 1 : 0;
7069

segmentation/include/pcl/segmentation/impl/extract_clusters.hpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
#define PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_
4040

4141
#include <pcl/segmentation/extract_clusters.h>
42-
#include <pcl/search/organized.h> // for OrganizedNeighbor
42+
#include <pcl/search/auto.h>
4343

4444
//////////////////////////////////////////////////////////////////////////////////////////////
4545
template <typename PointT> void
@@ -234,14 +234,13 @@ pcl::EuclideanClusterExtraction<PointT>::extract (std::vector<PointIndices> &clu
234234
// Initialize the spatial locator
235235
if (!tree_)
236236
{
237-
if (input_->isOrganized ())
238-
tree_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
239-
else
240-
tree_.reset (new pcl::search::KdTree<PointT> (false));
237+
tree_.reset (pcl::search::autoSelectMethod<PointT>(input_, indices_, false));
238+
}
239+
else
240+
{
241+
// Send the input dataset to the spatial locator
242+
tree_->setInputCloud (input_, indices_);
241243
}
242-
243-
// Send the input dataset to the spatial locator
244-
tree_->setInputCloud (input_, indices_);
245244
extractEuclideanClusters (*input_, *indices_, tree_, static_cast<float> (cluster_tolerance_), clusters, min_pts_per_cluster_, max_pts_per_cluster_);
246245

247246
//tree_->setInputCloud (input_);

0 commit comments

Comments
 (0)