diff --git a/features/include/pcl/features/fpfh_omp.h b/features/include/pcl/features/fpfh_omp.h index 4288691ddc7..5a8d779248a 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); 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/impl/fpfh_omp.hpp b/features/include/pcl/features/impl/fpfh_omp.hpp index b71d2a69b5a..151492b5b0f 100644 --- a/features/include/pcl/features/impl/fpfh_omp.hpp +++ b/features/include/pcl/features/impl/fpfh_omp.hpp @@ -43,6 +43,20 @@ #include +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FPFHEstimationOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + ////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::FPFHEstimationOMP::computeFeature (PointCloudOut &output) diff --git a/features/include/pcl/features/impl/normal_3d_omp.hpp b/features/include/pcl/features/impl/normal_3d_omp.hpp index f48e4d11c0c..cb539b71d9c 100644 --- a/features/include/pcl/features/impl/normal_3d_omp.hpp +++ b/features/include/pcl/features/impl/normal_3d_omp.hpp @@ -43,6 +43,20 @@ #include +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::NormalEstimationOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + /////////////////////////////////////////////////////////////////////////////////////////// template void pcl::NormalEstimationOMP::computeFeature (PointCloudOut &output) diff --git a/features/include/pcl/features/impl/shot_lrf_omp.hpp b/features/include/pcl/features/impl/shot_lrf_omp.hpp index 42a3c9ea5ed..ac0127edc49 100644 --- a/features/include/pcl/features/impl/shot_lrf_omp.hpp +++ b/features/include/pcl/features/impl/shot_lrf_omp.hpp @@ -44,8 +44,22 @@ #include #include -template -void +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTLocalReferenceFrameEstimationOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + +////////////////////////////////////////////////////////////////////////////////////////////// +template void pcl::SHOTLocalReferenceFrameEstimationOMP::computeFeature (PointCloudOut &output) { //check whether used with search radius or search k-neighbors diff --git a/features/include/pcl/features/impl/shot_omp.hpp b/features/include/pcl/features/impl/shot_omp.hpp index 16215c3ab8c..d4aa094ddd0 100644 --- a/features/include/pcl/features/impl/shot_omp.hpp +++ b/features/include/pcl/features/impl/shot_omp.hpp @@ -119,6 +119,20 @@ pcl::SHOTColorEstimationOMP::initCompute return (true); } +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTEstimationOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + ////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::SHOTEstimationOMP::computeFeature (PointCloudOut &output) @@ -189,6 +203,20 @@ pcl::SHOTEstimationOMP::computeFeature ( } } +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::SHOTColorEstimationOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + ////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::SHOTColorEstimationOMP::computeFeature (PointCloudOut &output) diff --git a/features/include/pcl/features/normal_3d_omp.h b/features/include/pcl/features/normal_3d_omp.h index e98f1c5d6ad..66256991407 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); 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..1b6a03582fb 100644 --- a/features/include/pcl/features/shot_lrf_omp.h +++ b/features/include/pcl/features/shot_lrf_omp.h @@ -70,19 +70,21 @@ 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 () {} /** \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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); 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..97b999bee80 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); protected: diff --git a/filters/include/pcl/filters/fast_bilateral_omp.h b/filters/include/pcl/filters/fast_bilateral_omp.h index a93c18491b2..dc9b6194228 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); /** \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/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp b/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp index ee72418401b..a1bdcccf17c 100644 --- a/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp +++ b/filters/include/pcl/filters/impl/fast_bilateral_omp.hpp @@ -45,6 +45,20 @@ #include #include +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::FastBilateralFilterOMP::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + ////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::FastBilateralFilterOMP::applyFilter (PointCloud &output) diff --git a/outofcore/src/outofcore_base_data.cpp b/outofcore/src/outofcore_base_data.cpp index 0b76e3e9a2a..3fb8a23698a 100644 --- a/outofcore/src/outofcore_base_data.cpp +++ b/outofcore/src/outofcore_base_data.cpp @@ -137,6 +137,9 @@ namespace pcl void OutofcoreOctreeBaseMetadata::serializeMetadataToDisk () { + if (LOD_num_points_.empty ()) + return; + // Create JSON object boost::shared_ptr idx (cJSON_CreateObject (), cJSON_Delete); diff --git a/test/common/test_wrappers.cpp b/test/common/test_wrappers.cpp index 2c717237d86..bfc0792ccea 100644 --- a/test/common/test_wrappers.cpp +++ b/test/common/test_wrappers.cpp @@ -89,28 +89,25 @@ TEST (PointCloud, constructor_with_allocation) TEST (PointCloud, constructor_with_allocation_valued) { - PointXYZ nan_point (0.1f, 0.2f, 0.3f); + PointXYZ nan_point (0.1f, 0.2f, 0.3f); PointCloud cloud2 (5, 80, nan_point); EXPECT_EQ (cloud2.width, 5); EXPECT_EQ (cloud2.height, 80); EXPECT_EQ (cloud2.size (), 5*80); - for (PointCloud::const_iterator pit = cloud2.begin (); - pit != cloud2.end (); - ++pit) + for (PointCloud::const_iterator pit = cloud2.begin (); pit != cloud2.end (); ++pit) { EXPECT_NEAR (pit->x, 0.1, 1e-3); EXPECT_NEAR (pit->y, 0.2, 1e-3); EXPECT_NEAR (pit->z, 0.3, 1e-3); } - } TEST (PointCloud, iterators) { - EXPECT_EQ_VECTORS (cloud.begin ()->getVector3fMap (), + EXPECT_EQ_VECTORS (cloud.begin ()->getVector3fMap (), cloud.points.begin ()->getVector3fMap ()); - EXPECT_EQ_VECTORS (cloud.end ()->getVector3fMap (), - cloud.points.end ()->getVector3fMap ()); + EXPECT_EQ_VECTORS ((--cloud.end ())->getVector3fMap (), + (--cloud.points.end ())->getVector3fMap ()); PointCloud::const_iterator pit = cloud.begin (); PointCloud::VectorType::const_iterator pit2 = cloud.points.begin (); for (; pit < cloud.end (); ++pit2, ++pit) diff --git a/test/recognition/test_recognition_cg.cpp b/test/recognition/test_recognition_cg.cpp index 3794b404a0d..1b183a18f83 100644 --- a/test/recognition/test_recognition_cg.cpp +++ b/test/recognition/test_recognition_cg.cpp @@ -130,7 +130,7 @@ TEST (PCL, Hough3DGrouping) clusterer.setSceneRf (scene_rf); clusterer.setModelSceneCorrespondences (model_scene_corrs_); clusterer.setHoughBinSize (0.03); - clusterer.setHoughThreshold (13); + clusterer.setHoughThreshold (10); EXPECT_TRUE (clusterer.recognize (rototranslations)); //Assertions diff --git a/test/sample_consensus/test_sample_consensus.cpp b/test/sample_consensus/test_sample_consensus.cpp index 1b3833adc30..997945d445d 100644 --- a/test/sample_consensus/test_sample_consensus.cpp +++ b/test/sample_consensus/test_sample_consensus.cpp @@ -89,7 +89,12 @@ TEST (SampleConsensus, InfiniteLoop) cloud.points[idx].z = 0.0; } +#if defined(DEBUG) || defined(_DEBUG) + boost::posix_time::time_duration delay (0, 0, 15, 0); +#else boost::posix_time::time_duration delay (0, 0, 1, 0); +#endif + boost::function sac_function; SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere (cloud.makeShared ())); diff --git a/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp b/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp index 0c018e4d8e0..e1fe8630f63 100644 --- a/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp +++ b/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter_omp.hpp @@ -3,6 +3,21 @@ #include +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::KLDAdaptiveParticleFilterOMPTracker::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + +////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::tracking::KLDAdaptiveParticleFilterOMPTracker::weight () { diff --git a/tracking/include/pcl/tracking/impl/particle_filter_omp.hpp b/tracking/include/pcl/tracking/impl/particle_filter_omp.hpp index 092c5d16bdf..bfc100bc462 100644 --- a/tracking/include/pcl/tracking/impl/particle_filter_omp.hpp +++ b/tracking/include/pcl/tracking/impl/particle_filter_omp.hpp @@ -3,6 +3,21 @@ #include +////////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::tracking::ParticleFilterOMPTracker::setNumberOfThreads (unsigned int nr_threads) +{ + if (nr_threads == 0) +#ifdef _OPENMP + threads_ = omp_get_num_procs(); +#else + threads_ = 1; +#endif + else + threads_ = nr_threads; +} + +////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::tracking::ParticleFilterOMPTracker::weight () { 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..45b8e24acc0 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; } + void + setNumberOfThreads (unsigned int nr_threads = 0); 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..4f52c6b74e0 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; } - + void + setNumberOfThreads (unsigned int nr_threads = 0); + protected: /** \brief The number of threads the scheduler should use. */ unsigned int threads_;