Skip to content

Commit 5a216b8

Browse files
committed
Move num_threads_ to pcl_base.
Set number of threads using omp_get_num_procs in initCompute.
1 parent afafe4f commit 5a216b8

File tree

33 files changed

+36
-85
lines changed

33 files changed

+36
-85
lines changed

benchmarks/filters/radius_outlier_removal.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ BM_RadiusOutlierRemoval(benchmark::State& state, const std::string& file)
1515
ror.setInputCloud(cloud);
1616
ror.setRadiusSearch(0.02);
1717
ror.setMinNeighborsInRadius(14);
18+
ror.setNumberOfThreads(1);
1819

1920
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_voxelized(
2021
new pcl::PointCloud<pcl::PointXYZ>);

common/include/pcl/impl/pcl_base.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,6 +167,15 @@ pcl::PCLBase<PointT>::initCompute ()
167167
for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = i; }
168168
}
169169

170+
// Set the number of threads
171+
#ifdef _OPENMP
172+
num_threads_ = num_threads_ != 0 ? num_threads_ : omp_get_num_procs();
173+
#else
174+
if (num_threads_ != 1) {
175+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
176+
}
177+
#endif
178+
170179
return (true);
171180
}
172181

common/include/pcl/pcl_base.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -155,6 +155,11 @@ namespace pcl
155155
/** \brief If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. */
156156
bool fake_indices_;
157157

158+
/**
159+
* @brief Number of threads used if the algorithm supports parallelization
160+
*/
161+
unsigned int num_threads_{0};
162+
158163
/** \brief This method should get called before starting the actual computation.
159164
*
160165
* Internally, initCompute() does the following:
@@ -233,6 +238,11 @@ namespace pcl
233238
/** \brief If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. */
234239
bool fake_indices_;
235240

241+
/**
242+
* @brief Number of threads used during filtering
243+
*/
244+
unsigned int num_threads_{0};
245+
236246
/** \brief The size of each individual field. */
237247
std::vector<uindex_t> field_sizes_;
238248

common/src/pcl_base.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,15 @@ pcl::PCLBase<pcl::PCLPointCloud2>::initCompute ()
130130
std::iota(indices_->begin () + indices_size, indices_->end (), indices_size);
131131
}
132132

133+
// Set the number of threads
134+
#ifdef _OPENMP
135+
num_threads_ = num_threads_ != 0 ? num_threads_ : omp_get_num_procs();
136+
#else
137+
if (num_threads_ != 1) {
138+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
139+
}
140+
#endif
141+
133142
return (true);
134143
}
135144

features/include/pcl/features/fpfh_omp.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -119,9 +119,6 @@ namespace pcl
119119
public:
120120
/** \brief The number of subdivisions for each angular feature interval. */
121121
int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11};
122-
private:
123-
/** \brief The number of threads the scheduler should use. */
124-
unsigned int num_threads_{1};
125122
};
126123
}
127124

features/include/pcl/features/intensity_gradient.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -117,8 +117,6 @@ namespace pcl
117117
protected:
118118
///intensity field accessor structure
119119
IntensitySelectorT intensity_;
120-
///number of threads to be used
121-
unsigned int num_threads_{1};
122120
};
123121
}
124122

features/include/pcl/features/normal_3d_omp.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -88,9 +88,6 @@ namespace pcl
8888
setNumberOfThreads (unsigned int num_threads = 0);
8989

9090
protected:
91-
/** \brief The number of threads the scheduler should use. */
92-
unsigned int num_threads_{1};
93-
9491
/** \brief Chunk size for (dynamic) scheduling. */
9592
int chunk_size_;
9693
private:

features/include/pcl/features/principal_curvatures.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -111,9 +111,6 @@ namespace pcl
111111
setNumberOfThreads (unsigned int num_threads = 0);
112112

113113
protected:
114-
/** \brief The number of threads the scheduler should use. */
115-
unsigned int num_threads_{1};
116-
117114
/** \brief Chunk size for (dynamic) scheduling. */
118115
int chunk_size_;
119116

features/include/pcl/features/shot_lrf_omp.h

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -103,10 +103,6 @@ namespace pcl
103103
*/
104104
void
105105
computeFeature (PointCloudOut &output) override;
106-
107-
/** \brief The number of threads the scheduler should use. */
108-
unsigned int num_threads_{1};
109-
110106
};
111107
}
112108

features/include/pcl/features/shot_omp.h

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -119,9 +119,6 @@ namespace pcl
119119
/** \brief This method should get called before starting the actual computation. */
120120
bool
121121
initCompute () override;
122-
123-
/** \brief The number of threads the scheduler should use. */
124-
unsigned int num_threads_{1};
125122
};
126123

127124
/** \brief SHOTColorEstimationOMP estimates the Signature of Histograms of OrienTations (SHOT) descriptor for a given point cloud dataset
@@ -204,9 +201,6 @@ namespace pcl
204201
/** \brief This method should get called before starting the actual computation. */
205202
bool
206203
initCompute () override;
207-
208-
/** \brief The number of threads the scheduler should use. */
209-
unsigned int num_threads_{1};
210204
};
211205

212206
}

filters/include/pcl/filters/convolution.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -227,8 +227,6 @@ namespace pcl
227227
/// kernel size - 1
228228
int kernel_width_{};
229229
protected:
230-
/** \brief The number of threads the scheduler should use. */
231-
unsigned int num_threads_{1};
232230

233231
void
234232
makeInfinite (PointOut& p)

filters/include/pcl/filters/convolution_3d.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -281,9 +281,6 @@ namespace pcl
281281
/** \brief The nearest neighbors search radius for each point. */
282282
double search_radius_;
283283

284-
/** \brief number of threads */
285-
unsigned int num_threads_{1};
286-
287284
/** \brief convlving kernel */
288285
KernelT kernel_;
289286
};

filters/include/pcl/filters/fast_bilateral_omp.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -87,11 +87,6 @@ namespace pcl
8787
*/
8888
void
8989
applyFilter (PointCloud &output) override;
90-
91-
protected:
92-
/** \brief The number of threads the scheduler should use. */
93-
unsigned int num_threads_{1};
94-
9590
};
9691
}
9792

filters/include/pcl/filters/pyramid.h

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -64,8 +64,9 @@ namespace pcl
6464
class Pyramid : public PCLBase<PointT>
6565
{
6666
public:
67-
using PointCloudPtr = typename PointCloud<PointT>::Ptr;
68-
using PointCloudConstPtr = typename PointCloud<PointT>::ConstPtr;
67+
using PointCloud = pcl::PointCloud<PointT>;
68+
using PointCloudPtr = typename PointCloud::Ptr;
69+
using PointCloudConstPtr = typename PointCloud::ConstPtr;
6970
using Ptr = shared_ptr< Pyramid<PointT> >;
7071
using ConstPtr = shared_ptr< const Pyramid<PointT> >;
7172

@@ -166,9 +167,6 @@ namespace pcl
166167
Eigen::MatrixXf kernel_;
167168
/// Threshold distance between adjacent points
168169
float threshold_{0.01f};
169-
/// \brief number of threads
170-
unsigned int num_threads_{1};
171-
172170
public:
173171
PCL_MAKE_ALIGNED_OPERATOR_NEW
174172
};

filters/include/pcl/filters/radius_outlier_removal.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -195,11 +195,6 @@ namespace pcl
195195

196196
/** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier. */
197197
int min_pts_radius_{1};
198-
199-
/**
200-
* @brief Number of threads used during filtering
201-
*/
202-
unsigned int num_threads_{1};
203198
};
204199

205200
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////

keypoints/include/pcl/keypoints/harris_2d.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -170,8 +170,6 @@ namespace pcl
170170
bool nonmax_;
171171
/// cornerness computation method
172172
ResponseMethod method_;
173-
/// number of threads to be used
174-
unsigned int num_threads_{1};
175173

176174
private:
177175
Eigen::MatrixXf derivatives_rows_;

keypoints/include/pcl/keypoints/harris_3d.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,6 @@ namespace pcl
183183
bool nonmax_{true};
184184
ResponseMethod method_;
185185
PointCloudNConstPtr normals_;
186-
unsigned int num_threads_{1};
187186
};
188187
}
189188

keypoints/include/pcl/keypoints/harris_6d.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,6 @@ namespace pcl
140140
float threshold_;
141141
bool refine_{true};
142142
bool nonmax_{true};
143-
unsigned int num_threads_{1};
144143
typename pcl::PointCloud<NormalT>::Ptr normals_;
145144
pcl::PointCloud<pcl::IntensityGradient>::Ptr intensity_gradients_;
146145
} ;

keypoints/include/pcl/keypoints/iss_3d.h

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -257,10 +257,6 @@ namespace pcl
257257

258258
/** \brief The decision boundary (angle threshold) that marks points as boundary or regular. (default \f$\pi / 2.0\f$) */
259259
float angle_threshold_;
260-
261-
/** \brief The number of threads that has to be used by the scheduler. */
262-
unsigned int num_threads_{1};
263-
264260
};
265261

266262
}

keypoints/include/pcl/keypoints/susan.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,6 @@ namespace pcl
180180
float intensity_threshold_;
181181
float tolerance_;
182182
PointCloudNConstPtr normals_;
183-
unsigned int num_threads_{1};
184183
bool geometric_validation_;
185184
bool nonmax_;
186185
/// intensity field accessor

keypoints/include/pcl/keypoints/trajkovic_2d.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -175,8 +175,6 @@ namespace pcl
175175
float first_threshold_;
176176
/// second threshold for corner evaluation
177177
float second_threshold_;
178-
/// number of threads to be used
179-
unsigned int num_threads_{1};
180178
/// point cloud response
181179
pcl::PointCloud<float>::Ptr response_;
182180
};

keypoints/include/pcl/keypoints/trajkovic_3d.h

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -214,8 +214,6 @@ namespace pcl
214214
float first_threshold_;
215215
/// second threshold for corner evaluation
216216
float second_threshold_;
217-
/// number of threads to be used
218-
unsigned int num_threads_{1};
219217
/// point cloud normals
220218
NormalsConstPtr normals_;
221219
/// point cloud response

registration/include/pcl/registration/correspondence_estimation.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@ class CorrespondenceEstimationBase : public PCLBase<PointSource> {
6969
using PCLBase<PointSource>::input_;
7070
using PCLBase<PointSource>::indices_;
7171
using PCLBase<PointSource>::setIndices;
72+
using PCLBase<PointSource>::num_threads_;
7273

7374
using KdTree = pcl::search::KdTree<PointTarget>;
7475
using KdTreePtr = typename KdTree::Ptr;
@@ -379,8 +380,6 @@ class CorrespondenceEstimationBase : public PCLBase<PointSource> {
379380
/** \brief A flag which, if set, means the tree operating on the source cloud
380381
* will never be recomputed*/
381382
bool force_no_recompute_reciprocal_{false};
382-
383-
unsigned int num_threads_{1};
384383
};
385384

386385
/** \brief @b CorrespondenceEstimation represents a simple class for

registration/include/pcl/registration/gicp.h

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,7 @@ template <typename PointSource, typename PointTarget, typename Scalar = float>
7575
class GeneralizedIterativeClosestPoint
7676
: public IterativeClosestPoint<PointSource, PointTarget, Scalar> {
7777
public:
78+
using PCLBase<PointSource>::num_threads_;
7879
using IterativeClosestPoint<PointSource, PointTarget, Scalar>::reg_name_;
7980
using IterativeClosestPoint<PointSource, PointTarget, Scalar>::getClassName;
8081
using IterativeClosestPoint<PointSource, PointTarget, Scalar>::indices_;
@@ -141,7 +142,6 @@ class GeneralizedIterativeClosestPoint
141142
max_iterations_ = 200;
142143
transformation_epsilon_ = 5e-4;
143144
corr_dist_threshold_ = 5.;
144-
setNumberOfThreads(0);
145145
rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
146146
const pcl::Indices& indices_src,
147147
const PointCloudTarget& cloud_tgt,
@@ -532,9 +532,6 @@ class GeneralizedIterativeClosestPoint
532532
Eigen::Matrix3d& ddR_dTheta_dTheta,
533533
Eigen::Matrix3d& ddR_dTheta_dPsi,
534534
Eigen::Matrix3d& ddR_dPsi_dPsi) const;
535-
536-
/** \brief The number of threads the scheduler should use. */
537-
unsigned int num_threads_{1};
538535
};
539536
} // namespace pcl
540537

registration/include/pcl/registration/ia_fpcs.h

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -474,11 +474,6 @@ class FPCSInitialAlignment : public Registration<PointSource, PointTarget, Scala
474474
/** \brief Normals of target point cloud. */
475475
NormalsConstPtr target_normals_;
476476

477-
/** \brief Number of threads for parallelization (standard = 1).
478-
* \note Only used if run compiled with OpenMP.
479-
*/
480-
unsigned int num_threads_{1};
481-
482477
/** \brief Estimated overlap between source and target (standard = 0.5). */
483478
float approx_overlap_{0.5f};
484479

sample_consensus/include/pcl/sample_consensus/sac.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -351,7 +351,7 @@ namespace pcl
351351
/** \brief Maximum number of iterations before giving up. */
352352
int max_iterations_;
353353

354-
/** \brief The number of threads the scheduler should use, or a negative number if no parallelization is wanted. */
354+
/** Number of threads used */
355355
unsigned int num_threads_{1};
356356

357357
/** \brief Boost-based random number generator algorithm. */

segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -173,9 +173,6 @@ namespace pcl
173173

174174
/** \brief Exponentially grow window sizes? */
175175
bool exponential_{true};
176-
177-
/** \brief Number of threads to be used. */
178-
unsigned int num_threads_{1};
179176
};
180177
}
181178

segmentation/include/pcl/segmentation/sac_segmentation.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -293,9 +293,6 @@ namespace pcl
293293
/** \brief Maximum number of iterations before giving up (user given parameter). */
294294
int max_iterations_{50};
295295

296-
/** \brief The number of threads the scheduler should use. */
297-
unsigned int num_threads_{1};
298-
299296
/** \brief Desired probability of choosing at least one sample free from outliers (user given parameter). */
300297
double probability_{0.99};
301298

surface/include/pcl/surface/mls.h

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -257,6 +257,7 @@ namespace pcl
257257

258258
using PCLBase<PointInT>::input_;
259259
using PCLBase<PointInT>::indices_;
260+
using PCLBase<PointInT>::num_threads_;
260261
using PCLBase<PointInT>::fake_indices_;
261262
using PCLBase<PointInT>::initCompute;
262263
using PCLBase<PointInT>::deinitCompute;
@@ -563,10 +564,6 @@ namespace pcl
563564
/** \brief Parameter that specifies the projection method to be used. */
564565
MLSResult::ProjectionMethod projection_method_{MLSResult::SIMPLE};
565566

566-
/** \brief The maximum number of threads the scheduler should use. */
567-
unsigned int num_threads_{1};
568-
569-
570567
/** \brief A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling
571568
* \note Used only in the case of VOXEL_GRID_DILATION upsampling
572569
*/

surface/include/pcl/surface/poisson.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -257,7 +257,6 @@ namespace pcl
257257
bool show_residual_{false};
258258
int min_iterations_{8};
259259
float solver_accuracy_{1e-3f};
260-
unsigned int num_threads_{1};
261260

262261
template<int Degree> void
263262
execute (poisson::CoredVectorMeshData &mesh,

tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -85,9 +85,6 @@ class KLDAdaptiveParticleFilterOMPTracker
8585
setNumberOfThreads(unsigned int num_threads = 0);
8686

8787
protected:
88-
/** \brief The number of threads the scheduler should use. */
89-
unsigned int num_threads_{1};
90-
9188
/** \brief weighting phase of particle filter method. calculate the likelihood of all
9289
* of the particles and set the weights.
9390
*/

tracking/include/pcl/tracking/particle_filter_omp.h

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -73,9 +73,6 @@ class ParticleFilterOMPTracker : public ParticleFilterTracker<PointInT, StateT>
7373
setNumberOfThreads(unsigned int num_threads = 0);
7474

7575
protected:
76-
/** \brief The number of threads the scheduler should use. */
77-
unsigned int num_threads_{1};
78-
7976
/** \brief weighting phase of particle filter method. calculate the likelihood of all
8077
* of the particles and set the weights.
8178
*/

0 commit comments

Comments
 (0)