From 518d9969cc17dc730d670e34fbbca8a6b261f8cc Mon Sep 17 00:00:00 2001 From: Claudio Fantacci Date: Fri, 19 Oct 2018 13:35:55 +0200 Subject: [PATCH] Fix OpenMP User Error 1001 The number of thread passed to OpenMP must be greater than 0. The default for OpenMP classes is 0. With this commit, by setting 0, the number of threads is set to the number of cores detected on the machine. Closes #2568 See also https://github.com/PointCloudLibrary/pcl/issues/2399 --- features/include/pcl/features/fpfh_omp.h | 14 ++++++++------ features/include/pcl/features/normal_3d_omp.h | 10 ++++++---- features/include/pcl/features/shot_lrf_omp.h | 8 +++++--- features/include/pcl/features/shot_omp.h | 14 +++++++++----- filters/include/pcl/filters/fast_bilateral_omp.h | 13 +++++++------ .../tracking/kld_adaptive_particle_filter_omp.h | 9 +++++---- .../include/pcl/tracking/particle_filter_omp.h | 13 +++++++------ 7 files changed, 47 insertions(+), 34 deletions(-) diff --git a/features/include/pcl/features/fpfh_omp.h b/features/include/pcl/features/fpfh_omp.h index 4288691ddc7..6782148f567 100644 --- a/features/include/pcl/features/fpfh_omp.h +++ b/features/include/pcl/features/fpfh_omp.h @@ -60,9 +60,9 @@ namespace pcl * In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), * St. Louis, MO, USA, October 11-15 2009. * - * \attention + * \attention * The convention for FPFH features is: - * - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN + * - if a query point's nearest neighbors cannot be estimated, the FPFH feature will be set to NaN * (not a number) * - it is impossible to estimate a FPFH descriptor for a point that * doesn't have finite 3D coordinates. Therefore, any point that contains @@ -95,16 +95,18 @@ namespace pcl /** \brief Initialize the scheduler and set the number of threads to use. * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), threads_ (nr_threads) + FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11) { feature_name_ = "FPFHEstimationOMP"; + + setNumberOfThreads(nr_threads); } /** \brief Initialize the scheduler and set the number of threads to use. * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } private: /** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by @@ -112,7 +114,7 @@ namespace pcl * setSearchMethod () * \param[out] output the resultant point cloud model dataset that contains the FPFH feature estimates */ - void + void computeFeature (PointCloudOut &output); public: diff --git a/features/include/pcl/features/normal_3d_omp.h b/features/include/pcl/features/normal_3d_omp.h index e98f1c5d6ad..a3a501a7f50 100644 --- a/features/include/pcl/features/normal_3d_omp.h +++ b/features/include/pcl/features/normal_3d_omp.h @@ -74,16 +74,18 @@ namespace pcl /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - NormalEstimationOMP (unsigned int nr_threads = 0) : threads_ (nr_threads) + NormalEstimationOMP (unsigned int nr_threads = 0) { feature_name_ = "NormalEstimationOMP"; + + setNumberOfThreads(nr_threads); } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } protected: /** \brief The number of threads the scheduler should use. */ @@ -94,7 +96,7 @@ namespace pcl * setSearchSurface () and the spatial locator in setSearchMethod () * \param output the resultant point cloud model dataset that contains surface normals and curvatures */ - void + void computeFeature (PointCloudOut &output); }; } diff --git a/features/include/pcl/features/shot_lrf_omp.h b/features/include/pcl/features/shot_lrf_omp.h index 958b8b7df77..834123e534a 100644 --- a/features/include/pcl/features/shot_lrf_omp.h +++ b/features/include/pcl/features/shot_lrf_omp.h @@ -70,11 +70,13 @@ namespace pcl typedef boost::shared_ptr > Ptr; typedef boost::shared_ptr > ConstPtr; /** \brief Constructor */ - SHOTLocalReferenceFrameEstimationOMP () : threads_ (0) + SHOTLocalReferenceFrameEstimationOMP () { feature_name_ = "SHOTLocalReferenceFrameEstimationOMP"; + + setNumberOfThreads(0); } - + /** \brief Empty destructor */ virtual ~SHOTLocalReferenceFrameEstimationOMP () {} @@ -82,7 +84,7 @@ namespace pcl * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } protected: using Feature::feature_name_; diff --git a/features/include/pcl/features/shot_omp.h b/features/include/pcl/features/shot_omp.h index 7fc34b476d8..73a7cf5c43c 100644 --- a/features/include/pcl/features/shot_omp.h +++ b/features/include/pcl/features/shot_omp.h @@ -96,13 +96,16 @@ namespace pcl typedef typename Feature::PointCloudIn PointCloudIn; /** \brief Empty constructor. */ - SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation (), threads_ (nr_threads) - { }; + SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation () + { + setNumberOfThreads(nr_threads); + }; + /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } protected: @@ -178,15 +181,16 @@ namespace pcl SHOTColorEstimationOMP (bool describe_shape = true, bool describe_color = true, unsigned int nr_threads = 0) - : SHOTColorEstimation (describe_shape, describe_color), threads_ (nr_threads) + : SHOTColorEstimation (describe_shape, describe_color) { + setNumberOfThreads(nr_threads); } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } protected: diff --git a/filters/include/pcl/filters/fast_bilateral_omp.h b/filters/include/pcl/filters/fast_bilateral_omp.h index a93c18491b2..e732b1c10d4 100644 --- a/filters/include/pcl/filters/fast_bilateral_omp.h +++ b/filters/include/pcl/filters/fast_bilateral_omp.h @@ -68,27 +68,28 @@ namespace pcl typedef typename Filter::PointCloud PointCloud; public: - + typedef boost::shared_ptr< FastBilateralFilterOMP > Ptr; typedef boost::shared_ptr< const FastBilateralFilterOMP > ConstPtr; /** \brief Empty constructor. */ FastBilateralFilterOMP (unsigned int nr_threads = 0) - : threads_ (nr_threads) - { } + { + setNumberOfThreads(nr_threads); + } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + inline void + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } /** \brief Filter the input data and store the results into output. * \param[out] output the resultant point cloud */ void applyFilter (PointCloud &output); - + protected: /** \brief The number of threads the scheduler should use. */ unsigned int threads_; diff --git a/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h b/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h index 64559adf5cc..f1c88e29c3e 100644 --- a/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h +++ b/tracking/include/pcl/tracking/kld_adaptive_particle_filter_omp.h @@ -46,7 +46,7 @@ namespace pcl using KLDAdaptiveParticleFilterTracker::calcBoundingBox; typedef Tracker BaseClass; - + typedef typename Tracker::PointCloudIn PointCloudIn; typedef typename PointCloudIn::Ptr PointCloudInPtr; typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; @@ -65,19 +65,20 @@ namespace pcl /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) - */ + */ KLDAdaptiveParticleFilterOMPTracker (unsigned int nr_threads = 0) : KLDAdaptiveParticleFilterTracker () - , threads_ (nr_threads) { tracker_name_ = "KLDAdaptiveParticleFilterOMPTracker"; + + setNumberOfThreads(nr_threads); } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } protected: /** \brief The number of threads the scheduler should use. */ diff --git a/tracking/include/pcl/tracking/particle_filter_omp.h b/tracking/include/pcl/tracking/particle_filter_omp.h index 208815ed40c..531444a6e66 100644 --- a/tracking/include/pcl/tracking/particle_filter_omp.h +++ b/tracking/include/pcl/tracking/particle_filter_omp.h @@ -10,7 +10,7 @@ namespace pcl namespace tracking { /** \brief @b ParticleFilterOMPTracker tracks the PointCloud which is given by - setReferenceCloud within the measured PointCloud using particle filter method + setReferenceCloud within the measured PointCloud using particle filter method in parallel, using the OpenMP standard. * \author Ryohei Ueda * \ingroup tracking @@ -42,7 +42,7 @@ namespace pcl using ParticleFilterTracker::calcBoundingBox; typedef Tracker BaseClass; - + typedef typename Tracker::PointCloudIn PointCloudIn; typedef typename PointCloudIn::Ptr PointCloudInPtr; typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr; @@ -61,20 +61,21 @@ namespace pcl /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) - */ + */ ParticleFilterOMPTracker (unsigned int nr_threads = 0) : ParticleFilterTracker () - , threads_ (nr_threads) { tracker_name_ = "ParticleFilterOMPTracker"; + + setNumberOfThreads(nr_threads); } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ inline void - setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; } - + setNumberOfThreads (unsigned int nr_threads = 0) { nr_threads == 0 ? threads_ = omp_get_num_procs() : threads_ = nr_threads; } + protected: /** \brief The number of threads the scheduler should use. */ unsigned int threads_;