Skip to content

Commit

Permalink
Fix OpenMP User Error 1001
Browse files Browse the repository at this point in the history
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 PointCloudLibrary#2568

See also PointCloudLibrary#2399
  • Loading branch information
claudiofantacci committed Oct 19, 2018
1 parent aff289e commit c58fb57
Show file tree
Hide file tree
Showing 7 changed files with 47 additions and 34 deletions.
14 changes: 8 additions & 6 deletions features/include/pcl/features/fpfh_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -95,24 +95,26 @@ 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
* <setInputCloud (), setIndices ()> using the surface in setSearchSurface () and the spatial locator in
* setSearchMethod ()
* \param[out] output the resultant point cloud model dataset that contains the FPFH feature estimates
*/
void
void
computeFeature (PointCloudOut &output);

public:
Expand Down
10 changes: 6 additions & 4 deletions features/include/pcl/features/normal_3d_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -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. */
Expand All @@ -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);
};
}
Expand Down
8 changes: 5 additions & 3 deletions features/include/pcl/features/shot_lrf_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,19 +70,21 @@ namespace pcl
typedef boost::shared_ptr<SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT> > Ptr;
typedef boost::shared_ptr<const SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT> > ConstPtr;
/** \brief Constructor */
SHOTLocalReferenceFrameEstimationOMP () : threads_ (0)
SHOTLocalReferenceFrameEstimationOMP ()
{
feature_name_ = "SHOTLocalReferenceFrameEstimationOMP";

setNumberOfThreads(nr_threads);
}

/** \brief Empty destructor */
virtual ~SHOTLocalReferenceFrameEstimationOMP () {}

/** \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:
using Feature<PointInT, PointOutT>::feature_name_;
Expand Down
14 changes: 9 additions & 5 deletions features/include/pcl/features/shot_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,13 +96,16 @@ namespace pcl
typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;

/** \brief Empty constructor. */
SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> (), threads_ (nr_threads)
{ };
SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> ()
{
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:

Expand Down Expand Up @@ -178,15 +181,16 @@ namespace pcl
SHOTColorEstimationOMP (bool describe_shape = true,
bool describe_color = true,
unsigned int nr_threads = 0)
: SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (describe_shape, describe_color), threads_ (nr_threads)
: SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (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:

Expand Down
13 changes: 7 additions & 6 deletions filters/include/pcl/filters/fast_bilateral_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,27 +68,28 @@ namespace pcl
typedef typename Filter<PointT>::PointCloud PointCloud;

public:

typedef boost::shared_ptr< FastBilateralFilterOMP<PointT> > Ptr;
typedef boost::shared_ptr< const FastBilateralFilterOMP<PointT> > 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_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace pcl
using KLDAdaptiveParticleFilterTracker<PointInT, StateT>::calcBoundingBox;

typedef Tracker<PointInT, StateT> BaseClass;

typedef typename Tracker<PointInT, StateT>::PointCloudIn PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
Expand All @@ -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<PointInT, StateT> ()
, 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. */
Expand Down
13 changes: 7 additions & 6 deletions tracking/include/pcl/tracking/particle_filter_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -42,7 +42,7 @@ namespace pcl
using ParticleFilterTracker<PointInT, StateT>::calcBoundingBox;

typedef Tracker<PointInT, StateT> BaseClass;

typedef typename Tracker<PointInT, StateT>::PointCloudIn PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
Expand All @@ -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<PointInT, StateT> ()
, 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_;
Expand Down

0 comments on commit c58fb57

Please sign in to comment.