Skip to content

Commit b054dd8

Browse files
committed
Make omp naming and functionality consistent.
1 parent c9a1750 commit b054dd8

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

65 files changed

+506
-390
lines changed

features/include/pcl/features/fpfh_omp.h

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -92,20 +92,20 @@ namespace pcl
9292
using PointCloudOut = typename Feature<PointInT, PointOutT>::PointCloudOut;
9393

9494
/** \brief Initialize the scheduler and set the number of threads to use.
95-
* \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
95+
* \param[in] num_threads the number of hardware threads to use (0 sets the value back to automatic)
9696
*/
97-
FPFHEstimationOMP (unsigned int nr_threads = 0)
97+
FPFHEstimationOMP (unsigned int num_threads = 0)
9898
{
9999
feature_name_ = "FPFHEstimationOMP";
100100

101-
setNumberOfThreads(nr_threads);
101+
setNumberOfThreads(num_threads);
102102
}
103103

104104
/** \brief Initialize the scheduler and set the number of threads to use.
105-
* \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
105+
* \param[in] num_threads the number of hardware threads to use (0 sets the value back to automatic)
106106
*/
107107
void
108-
setNumberOfThreads (unsigned int nr_threads = 0);
108+
setNumberOfThreads (unsigned int num_threads = 0);
109109

110110
private:
111111
/** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by
@@ -121,7 +121,7 @@ namespace pcl
121121
int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11};
122122
private:
123123
/** \brief The number of threads the scheduler should use. */
124-
unsigned int threads_;
124+
unsigned int num_threads_{1};
125125
};
126126
}
127127

features/include/pcl/features/impl/fpfh_omp.hpp

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -49,16 +49,15 @@
4949

5050
//////////////////////////////////////////////////////////////////////////////////////////////
5151
template <typename PointInT, typename PointNT, typename PointOutT> void
52-
pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
52+
pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int num_threads)
5353
{
54-
if (nr_threads == 0)
5554
#ifdef _OPENMP
56-
threads_ = omp_get_num_procs();
55+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
5756
#else
58-
threads_ = 1;
57+
if (num_threads_ != 1) {
58+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
59+
}
5960
#endif
60-
else
61-
threads_ = nr_threads;
6261
}
6362

6463
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -112,7 +111,7 @@ pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::computeFeature (PointCloud
112111
default(none) \
113112
shared(spfh_hist_lookup, spfh_indices_vec) \
114113
firstprivate(nn_indices, nn_dists) \
115-
num_threads(threads_)
114+
num_threads(num_threads_)
116115
for (std::ptrdiff_t i = 0; i < static_cast<std::ptrdiff_t> (spfh_indices_vec.size ()); ++i)
117116
{
118117
// Get the next point index
@@ -141,7 +140,7 @@ pcl::FPFHEstimationOMP<PointInT, PointNT, PointOutT>::computeFeature (PointCloud
141140
default(none) \
142141
shared(nr_bins, output, spfh_hist_lookup) \
143142
firstprivate(nn_dists, nn_indices) \
144-
num_threads(threads_)
143+
num_threads(num_threads_)
145144
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
146145
{
147146
// Find the indices of point idx's neighbors...

features/include/pcl/features/impl/intensity_gradient.hpp

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -149,21 +149,14 @@ pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelector
149149
std::vector<float> nn_dists (k_);
150150
output.is_dense = true;
151151

152-
#ifdef _OPENMP
153-
if (threads_ == 0) {
154-
threads_ = omp_get_num_procs();
155-
PCL_DEBUG ("[pcl::IntensityGradientEstimation::computeFeature] Setting number of threads to %u.\n", threads_);
156-
}
157-
#endif // _OPENMP
158-
159152
// If the data is dense, we don't need to check for NaN
160153
if (surface_->is_dense)
161154
{
162155
#pragma omp parallel for \
163156
default(none) \
164157
shared(output) \
165158
firstprivate(nn_indices, nn_dists) \
166-
num_threads(threads_)
159+
num_threads(num_threads_)
167160
// Iterating over the entire index vector
168161
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
169162
{
@@ -203,7 +196,7 @@ pcl::IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelector
203196
default(none) \
204197
shared(output) \
205198
firstprivate(nn_indices, nn_dists) \
206-
num_threads(threads_)
199+
num_threads(num_threads_)
207200
// Iterating over the entire index vector
208201
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
209202
{

features/include/pcl/features/impl/normal_3d_omp.hpp

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -45,19 +45,15 @@
4545

4646
///////////////////////////////////////////////////////////////////////////////////////////
4747
template <typename PointInT, typename PointOutT> void
48-
pcl::NormalEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
48+
pcl::NormalEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int num_threads)
4949
{
5050
#ifdef _OPENMP
51-
if (nr_threads == 0)
52-
threads_ = omp_get_num_procs();
53-
else
54-
threads_ = nr_threads;
55-
PCL_DEBUG ("[pcl::NormalEstimationOMP::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
51+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
5652
#else
57-
threads_ = 1;
58-
if (nr_threads != 1)
59-
PCL_WARN ("[pcl::NormalEstimationOMP::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
60-
#endif // _OPENMP
53+
if (num_threads_ != 1) {
54+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
55+
}
56+
#endif
6157
}
6258

6359
///////////////////////////////////////////////////////////////////////////////////////////
@@ -77,7 +73,7 @@ pcl::NormalEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &ou
7773
default(none) \
7874
shared(output) \
7975
firstprivate(nn_indices, nn_dists) \
80-
num_threads(threads_) \
76+
num_threads(num_threads_) \
8177
schedule(dynamic, chunk_size_)
8278
// Iterating over the entire index vector
8379
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
@@ -107,7 +103,7 @@ pcl::NormalEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &ou
107103
default(none) \
108104
shared(output) \
109105
firstprivate(nn_indices, nn_dists) \
110-
num_threads(threads_) \
106+
num_threads(num_threads_) \
111107
schedule(dynamic, chunk_size_)
112108
// Iterating over the entire index vector
113109
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)

features/include/pcl/features/impl/principal_curvatures.hpp

Lines changed: 8 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -47,19 +47,15 @@
4747

4848
///////////////////////////////////////////////////////////////////////////////////////////
4949
template <typename PointInT, typename PointNT, typename PointOutT> void
50-
pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
50+
pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::setNumberOfThreads (unsigned int num_threads)
5151
{
5252
#ifdef _OPENMP
53-
if (nr_threads == 0)
54-
threads_ = omp_get_num_procs();
55-
else
56-
threads_ = nr_threads;
57-
PCL_DEBUG ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
53+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
5854
#else
59-
threads_ = 1;
60-
if (nr_threads != 1)
61-
PCL_WARN ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
62-
#endif // _OPENMP
55+
if (num_threads_ != 1) {
56+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
57+
}
58+
#endif
6359
}
6460

6561
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -142,7 +138,7 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature
142138
default(none) \
143139
shared(output) \
144140
firstprivate(nn_indices, nn_dists) \
145-
num_threads(threads_) \
141+
num_threads(num_threads_) \
146142
schedule(dynamic, chunk_size_)
147143
// Iterating over the entire index vector
148144
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
@@ -167,7 +163,7 @@ pcl::PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT>::computeFeature
167163
default(none) \
168164
shared(output) \
169165
firstprivate(nn_indices, nn_dists) \
170-
num_threads(threads_) \
166+
num_threads(num_threads_) \
171167
schedule(dynamic, chunk_size_)
172168
// Iterating over the entire index vector
173169
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)

features/include/pcl/features/impl/shot_lrf_omp.hpp

Lines changed: 6 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -45,16 +45,15 @@
4545

4646
//////////////////////////////////////////////////////////////////////////////////////////////
4747
template<typename PointInT, typename PointOutT> void
48-
pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int nr_threads)
48+
pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::setNumberOfThreads (unsigned int num_threads)
4949
{
50-
if (nr_threads == 0)
5150
#ifdef _OPENMP
52-
threads_ = omp_get_num_procs();
51+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
5352
#else
54-
threads_ = 1;
53+
if (num_threads_ != 1) {
54+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
55+
}
5556
#endif
56-
else
57-
threads_ = nr_threads;
5857
}
5958

6059
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -74,7 +73,7 @@ pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeature (
7473
#pragma omp parallel for \
7574
default(none) \
7675
shared(output) \
77-
num_threads(threads_) \
76+
num_threads(num_threads_) \
7877
schedule(dynamic, 64)
7978
for (std::ptrdiff_t i = 0; i < static_cast<std::ptrdiff_t> (indices_->size ()); ++i)
8079
{

features/include/pcl/features/impl/shot_omp.hpp

Lines changed: 14 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute ()
6969
lrf_estimator->setRadiusSearch ((lrf_radius_ > 0 ? lrf_radius_ : search_radius_));
7070
lrf_estimator->setInputCloud (input_);
7171
lrf_estimator->setIndices (indices_);
72-
lrf_estimator->setNumberOfThreads(threads_);
72+
lrf_estimator->setNumberOfThreads(num_threads_);
7373

7474
if (!fake_surface_)
7575
lrf_estimator->setSearchSurface(surface_);
@@ -107,7 +107,7 @@ pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute
107107
lrf_estimator->setRadiusSearch ((lrf_radius_ > 0 ? lrf_radius_ : search_radius_));
108108
lrf_estimator->setInputCloud (input_);
109109
lrf_estimator->setIndices (indices_);
110-
lrf_estimator->setNumberOfThreads(threads_);
110+
lrf_estimator->setNumberOfThreads(num_threads_);
111111

112112
if (!fake_surface_)
113113
lrf_estimator->setSearchSurface(surface_);
@@ -123,16 +123,15 @@ pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::initCompute
123123

124124
//////////////////////////////////////////////////////////////////////////////////////////////
125125
template<typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
126-
pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int nr_threads)
126+
pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int num_threads)
127127
{
128-
if (nr_threads == 0)
129128
#ifdef _OPENMP
130-
threads_ = omp_get_num_procs();
129+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
131130
#else
132-
threads_ = 1;
131+
if (num_threads_ != 1) {
132+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
133+
}
133134
#endif
134-
else
135-
threads_ = nr_threads;
136135
}
137136

138137
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -153,7 +152,7 @@ pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (
153152
#pragma omp parallel for \
154153
default(none) \
155154
shared(output) \
156-
num_threads(threads_)
155+
num_threads(num_threads_)
157156
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
158157
{
159158

@@ -206,16 +205,15 @@ pcl::SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeature (
206205

207206
//////////////////////////////////////////////////////////////////////////////////////////////
208207
template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT> void
209-
pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int nr_threads)
208+
pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::setNumberOfThreads (unsigned int num_threads)
210209
{
211-
if (nr_threads == 0)
212210
#ifdef _OPENMP
213-
threads_ = omp_get_num_procs();
211+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
214212
#else
215-
threads_ = 1;
213+
if (num_threads_ != 1) {
214+
PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n");
215+
}
216216
#endif
217-
else
218-
threads_ = nr_threads;
219217
}
220218

221219
//////////////////////////////////////////////////////////////////////////////////////////////
@@ -240,7 +238,7 @@ pcl::SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT>::computeFeat
240238
#pragma omp parallel for \
241239
default(none) \
242240
shared(output) \
243-
num_threads(threads_)
241+
num_threads(num_threads_)
244242
for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
245243
{
246244
Eigen::VectorXf shot;

features/include/pcl/features/intensity_gradient.h

Lines changed: 14 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -75,10 +75,20 @@ namespace pcl
7575
}
7676

7777
/** \brief Initialize the scheduler and set the number of threads to use.
78-
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
78+
* \param num_threads the number of hardware threads to use (0 sets the value back to automatic)
7979
*/
8080
inline void
81-
setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
81+
setNumberOfThreads(unsigned int num_threads = 0)
82+
{
83+
#ifdef _OPENMP
84+
num_threads_ = num_threads != 0 ? num_threads : omp_get_num_procs();
85+
#else
86+
if (num_threads_ != 1) {
87+
PCL_WARN(
88+
"OpenMP is not available. Keeping number of threads unchanged at 1\n");
89+
}
90+
#endif
91+
}
8292

8393
protected:
8494
/** \brief Estimate the intensity gradients for a set of points given in <setInputCloud (), setIndices ()> using
@@ -107,8 +117,8 @@ namespace pcl
107117
protected:
108118
///intensity field accessor structure
109119
IntensitySelectorT intensity_;
110-
///number of threads to be used, default 0 (auto)
111-
unsigned int threads_{0};
120+
///number of threads to be used
121+
unsigned int num_threads_{1};
112122
};
113123
}
114124

features/include/pcl/features/normal_3d_omp.h

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -71,25 +71,25 @@ namespace pcl
7171

7272
public:
7373
/** \brief Initialize the scheduler and set the number of threads to use.
74-
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
74+
* \param num_threads the number of hardware threads to use (0 sets the value back to automatic)
7575
* \param chunk_size PCL will use dynamic scheduling with this chunk size. Setting it too low will lead to more parallelization overhead. Setting it too high will lead to a worse balancing between the threads.
7676
*/
77-
NormalEstimationOMP (unsigned int nr_threads = 0, int chunk_size = 256): chunk_size_(chunk_size)
77+
NormalEstimationOMP (unsigned int num_threads = 0, int chunk_size = 256): chunk_size_(chunk_size)
7878
{
7979
feature_name_ = "NormalEstimationOMP";
8080

81-
setNumberOfThreads(nr_threads);
81+
setNumberOfThreads(num_threads);
8282
}
8383

8484
/** \brief Initialize the scheduler and set the number of threads to use.
85-
* \param nr_threads the number of hardware threads to use (0 sets the value back to automatic)
85+
* \param num_threads the number of hardware threads to use (0 sets the value back to automatic)
8686
*/
8787
void
88-
setNumberOfThreads (unsigned int nr_threads = 0);
88+
setNumberOfThreads (unsigned int num_threads = 0);
8989

9090
protected:
9191
/** \brief The number of threads the scheduler should use. */
92-
unsigned int threads_;
92+
unsigned int num_threads_{1};
9393

9494
/** \brief Chunk size for (dynamic) scheduling. */
9595
int chunk_size_;

0 commit comments

Comments
 (0)