From 84933c8291cd654d608017e4cd7fe44c56125322 Mon Sep 17 00:00:00 2001 From: Shrijit Singh Date: Sat, 18 Jul 2020 17:01:27 +0530 Subject: [PATCH 1/3] Merge normal and OMP classes as well cleanup redundant code --- features/include/pcl/features/fpfh.h | 29 ++- features/include/pcl/features/fpfh_omp.h | 87 +-------- features/include/pcl/features/impl/fpfh.hpp | 94 ++++------ .../include/pcl/features/impl/fpfh_omp.hpp | 176 ------------------ features/src/fpfh.cpp | 3 - 5 files changed, 67 insertions(+), 322 deletions(-) delete mode 100644 features/include/pcl/features/impl/fpfh_omp.hpp diff --git a/features/include/pcl/features/fpfh.h b/features/include/pcl/features/fpfh.h index 5d3b64b4170..8dc30e3fa33 100644 --- a/features/include/pcl/features/fpfh.h +++ b/features/include/pcl/features/fpfh.h @@ -93,9 +93,10 @@ namespace pcl using PointCloudOut = typename Feature::PointCloudOut; /** \brief Empty constructor. */ - FPFHEstimation () : + FPFHEstimation (unsigned int nr_threads = -1) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), - d_pi_ (1.0f / (2.0f * static_cast (M_PI))) + d_pi_ (1.0f / (2.0f * static_cast (M_PI))), + threads_(nr_threads) { feature_name_ = "FPFHEstimation"; }; @@ -177,6 +178,21 @@ namespace pcl nr_bins_f3 = nr_bins_f3_; } + /** \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) + */ + void + setNumberOfThreads (unsigned int nr_threads = 0) { + if (nr_threads == 0) + #ifdef _OPENMP + threads_ = omp_get_num_procs(); + #else + threads_ = 1; + #endif + else + threads_ = nr_threads; + } + protected: /** \brief Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud @@ -213,8 +229,15 @@ namespace pcl Eigen::VectorXf fpfh_histogram_; /** \brief Float constant = 1.0 / (2.0 * M_PI) */ - float d_pi_; + float d_pi_; + + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; }; + +template +using FPFHEstimationOMP PCL_DEPRECATED(1, 12, "use FPFHEstimation instead") = FPFHEstimation; + } #ifdef PCL_NO_PRECOMPILE diff --git a/features/include/pcl/features/fpfh_omp.h b/features/include/pcl/features/fpfh_omp.h index fd7e49a339f..96e78633cbc 100644 --- a/features/include/pcl/features/fpfh_omp.h +++ b/features/include/pcl/features/fpfh_omp.h @@ -40,91 +40,8 @@ #pragma once -#include -#include - -namespace pcl -{ - /** \brief FPFHEstimationOMP estimates the Fast Point Feature Histogram (FPFH) descriptor for a given point cloud - * dataset containing points and normals, in parallel, using the OpenMP standard. - * - * \note If you use this code in any academic work, please cite: - * - * - R.B. Rusu, N. Blodow, M. Beetz. - * Fast Point Feature Histograms (FPFH) for 3D Registration. - * In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), - * Kobe, Japan, May 12-17 2009. - * - R.B. Rusu, A. Holzbach, N. Blodow, M. Beetz. - * Fast Geometric Point Labeling using Conditional Random Fields. - * In Proceedings of the 22nd IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), - * St. Louis, MO, USA, October 11-15 2009. - * - * \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 - * (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 - * NaN data on x, y, or z, will have its FPFH feature property set to NaN. - * - * \author Radu B. Rusu - * \ingroup features - */ - template - class FPFHEstimationOMP : public FPFHEstimation - { - public: - using Ptr = shared_ptr >; - using ConstPtr = shared_ptr >; - using Feature::feature_name_; - using Feature::getClassName; - using Feature::indices_; - using Feature::k_; - using Feature::search_parameter_; - using Feature::input_; - using Feature::surface_; - using FeatureFromNormals::normals_; - using FPFHEstimation::hist_f1_; - using FPFHEstimation::hist_f2_; - using FPFHEstimation::hist_f3_; - using FPFHEstimation::weightPointSPFHSignature; - - using PointCloudOut = typename Feature::PointCloudOut; - - /** \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) - { - feature_name_ = "FPFHEstimationOMP"; +PCL_DEPRECATED_HEADER(1, 13, "Use instead.") - 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) - */ - void - setNumberOfThreads (unsigned int nr_threads = 0); - - private: - /** \brief Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by - * 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 - computeFeature (PointCloudOut &output) override; +#include - public: - /** \brief The number of subdivisions for each angular feature interval. */ - int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_; - private: - /** \brief The number of threads the scheduler should use. */ - unsigned int threads_; - }; -} -#ifdef PCL_NO_PRECOMPILE -#include -#endif diff --git a/features/include/pcl/features/impl/fpfh.hpp b/features/include/pcl/features/impl/fpfh.hpp index 209b6d512a6..e9faa256b0e 100644 --- a/features/include/pcl/features/impl/fpfh.hpp +++ b/features/include/pcl/features/impl/fpfh.hpp @@ -186,7 +186,8 @@ pcl::FPFHEstimation::computeSPFHSignatures (std::v std::vector nn_indices (k_); std::vector nn_dists (k_); - std::set spfh_indices; + std::set spfh_indices_set; + std::vector spfh_indices_vec; spfh_hist_lookup.resize (surface_->size ()); // Build a list of (unique) indices for which we will need to compute SPFH signatures @@ -199,26 +200,37 @@ pcl::FPFHEstimation::computeSPFHSignatures (std::v if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0) continue; - spfh_indices.insert (nn_indices.begin (), nn_indices.end ()); + spfh_indices_set.insert (nn_indices.begin (), nn_indices.end ()); } + spfh_indices_vec.resize (spfh_indices_set.size ()); + std::copy (spfh_indices_set.cbegin (), spfh_indices_set.cend (), spfh_indices_vec.begin ()); } else { // Special case: When a feature must be computed at every point, there is no need for a neighborhood search - for (std::size_t idx = 0; idx < indices_->size (); ++idx) - spfh_indices.insert (static_cast (idx)); + spfh_indices_vec.resize (indices_->size ()); + std::iota(spfh_indices_vec.begin (), spfh_indices_vec.end (), + static_cast(0)); } // Initialize the arrays that will store the SPFH signatures - std::size_t data_size = spfh_indices.size (); + const auto data_size = spfh_indices_vec.size (); hist_f1.setZero (data_size, nr_bins_f1_); hist_f2.setZero (data_size, nr_bins_f2_); hist_f3.setZero (data_size, nr_bins_f3_); // Compute SPFH signatures for every point that needs them - std::size_t i = 0; - for (const auto& p_idx: spfh_indices) +#pragma omp parallel for \ + default(none) \ + shared(spfh_hist_lookup, spfh_indices_vec, hist_f1, hist_f2, hist_f3) \ + firstprivate(nn_indices, nn_dists) \ + num_threads(threads_) \ + if (threads_ != -1) + for (std::ptrdiff_t i = 0; i < static_cast (spfh_indices_vec.size ()); ++i) { + // Get the next point index + int p_idx = spfh_indices_vec[i]; + // Find the neighborhood around p_idx if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0) continue; @@ -228,7 +240,6 @@ pcl::FPFHEstimation::computeSPFHSignatures (std::v // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices spfh_hist_lookup[p_idx] = i; - i++; } } @@ -245,59 +256,32 @@ pcl::FPFHEstimation::computeFeature (PointCloudOut computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_); output.is_dense = true; - // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense - if (input_->is_dense) - { - // Iterate over the entire index vector - for (std::size_t idx = 0; idx < indices_->size (); ++idx) - { - if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) - { - for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d) - output[idx].histogram[d] = std::numeric_limits::quiet_NaN (); - - output.is_dense = false; - continue; - } - - // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices - // instead of indices into surface_->points - for (auto &nn_index : nn_indices) - nn_index = spfh_hist_lookup[nn_index]; - - // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... - weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_); - // ...and copy it into the output cloud - std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram); - } - } - else + // Iterate over the entire index vector + for (std::size_t idx = 0; idx < indices_->size (); ++idx) { - // Iterate over the entire index vector - for (std::size_t idx = 0; idx < indices_->size (); ++idx) - { - if (!isFinite ((*input_)[(*indices_)[idx]]) || - this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) - { - for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d) - output[idx].histogram[d] = std::numeric_limits::quiet_NaN (); - - output.is_dense = false; + if (input_->is_dense || isFinite ((*input_)[(*indices_)[idx]])) { + if (this->searchForNeighbors( + (*indices_)[idx], search_parameter_, nn_indices, nn_dists)) { + // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices + // instead of indices into surface_->points + for (auto &nn_index : nn_indices) + nn_index = spfh_hist_lookup[nn_index]; + + // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... + weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_); + + // ...and copy it into the output cloud + std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram); continue; } + } - // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices - // instead of indices into surface_->points - for (auto &nn_index : nn_indices) - nn_index = spfh_hist_lookup[nn_index]; - - // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... - weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_); + for (Eigen::Index d = 0; d < fpfh_histogram_.size(); ++d) + output[idx].histogram[d] = std::numeric_limits::quiet_NaN(); - // ...and copy it into the output cloud - std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram); - } + if (output.is_dense) + output.is_dense = false; } } diff --git a/features/include/pcl/features/impl/fpfh_omp.hpp b/features/include/pcl/features/impl/fpfh_omp.hpp deleted file mode 100644 index 2b72e64df85..00000000000 --- a/features/include/pcl/features/impl/fpfh_omp.hpp +++ /dev/null @@ -1,176 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#pragma once - -#include - -#include // for pcl::isFinite - -#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) -{ - std::vector spfh_indices_vec; - std::vector spfh_hist_lookup (surface_->size ()); - - // Build a list of (unique) indices for which we will need to compute SPFH signatures - // (We need an SPFH signature for every point that is a neighbor of any point in input_[indices_]) - if (surface_ != input_ || - indices_->size () != surface_->size ()) - { - std::vector nn_indices (k_); // \note These resizes are irrelevant for a radiusSearch (). - std::vector nn_dists (k_); - - std::set spfh_indices_set; - for (std::size_t idx = 0; idx < indices_->size (); ++idx) - { - int p_idx = (*indices_)[idx]; - if (!isFinite ((*input_)[p_idx]) || - this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0) - continue; - - spfh_indices_set.insert (nn_indices.begin (), nn_indices.end ()); - } - spfh_indices_vec.resize (spfh_indices_set.size ()); - std::copy (spfh_indices_set.cbegin (), spfh_indices_set.cend (), spfh_indices_vec.begin ()); - } - else - { - // Special case: When a feature must be computed at every point, there is no need for a neighborhood search - spfh_indices_vec.resize (indices_->size ()); - std::iota(spfh_indices_vec.begin (), spfh_indices_vec.end (), - static_cast(0)); - } - - // Initialize the arrays that will store the SPFH signatures - const auto data_size = spfh_indices_vec.size (); - hist_f1_.setZero (data_size, nr_bins_f1_); - hist_f2_.setZero (data_size, nr_bins_f2_); - hist_f3_.setZero (data_size, nr_bins_f3_); - - std::vector nn_indices (k_); // \note These resizes are irrelevant for a radiusSearch (). - std::vector nn_dists (k_); - - // Compute SPFH signatures for every point that needs them - -#pragma omp parallel for \ - default(none) \ - shared(spfh_hist_lookup, spfh_indices_vec) \ - firstprivate(nn_indices, nn_dists) \ - num_threads(threads_) - for (std::ptrdiff_t i = 0; i < static_cast (spfh_indices_vec.size ()); ++i) - { - // Get the next point index - int p_idx = spfh_indices_vec[i]; - - // Find the neighborhood around p_idx - if (!isFinite ((*input_)[p_idx]) || - this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0) - continue; - - // Estimate the SPFH signature around p_idx - this->computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1_, hist_f2_, hist_f3_); - - // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices - spfh_hist_lookup[p_idx] = i; - } - - // Initialize the array that will store the FPFH signature - int nr_bins = nr_bins_f1_ + nr_bins_f2_ + nr_bins_f3_; - - nn_indices.clear(); - nn_dists.clear(); - - // Iterate over the entire index vector -#pragma omp parallel for \ - default(none) \ - shared(nr_bins, output, spfh_hist_lookup) \ - firstprivate(nn_dists, nn_indices) \ - num_threads(threads_) - for (std::ptrdiff_t idx = 0; idx < static_cast (indices_->size ()); ++idx) - { - // Find the indices of point idx's neighbors... - if (!isFinite ((*input_)[(*indices_)[idx]]) || - this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) - { - for (int d = 0; d < nr_bins; ++d) - output[idx].histogram[d] = std::numeric_limits::quiet_NaN (); - - output.is_dense = false; - continue; - } - - - // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices - // instead of indices into surface_->points - for (int &nn_index : nn_indices) - nn_index = spfh_hist_lookup[nn_index]; - - // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ... - Eigen::VectorXf fpfh_histogram = Eigen::VectorXf::Zero (nr_bins); - weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram); - - // ...and copy it into the output cloud - for (int d = 0; d < nr_bins; ++d) - output[idx].histogram[d] = fpfh_histogram[d]; - } - -} - -#define PCL_INSTANTIATE_FPFHEstimationOMP(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimationOMP; - diff --git a/features/src/fpfh.cpp b/features/src/fpfh.cpp index ef8584532ee..7c97872f07a 100644 --- a/features/src/fpfh.cpp +++ b/features/src/fpfh.cpp @@ -37,7 +37,6 @@ */ #include -#include #ifndef PCL_NO_PRECOMPILE #include @@ -45,10 +44,8 @@ // Instantiations of specific point types #ifdef PCL_ONLY_CORE_POINT_TYPES PCL_INSTANTIATE_PRODUCT(FPFHEstimation, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointNormal))((pcl::Normal)(pcl::PointNormal))((pcl::FPFHSignature33))) - PCL_INSTANTIATE_PRODUCT(FPFHEstimationOMP, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointNormal))((pcl::Normal)(pcl::PointNormal))((pcl::FPFHSignature33))) #else PCL_INSTANTIATE_PRODUCT(FPFHEstimation, (PCL_XYZ_POINT_TYPES)(PCL_NORMAL_POINT_TYPES)((pcl::FPFHSignature33))) - PCL_INSTANTIATE_PRODUCT(FPFHEstimationOMP, (PCL_XYZ_POINT_TYPES)(PCL_NORMAL_POINT_TYPES)((pcl::FPFHSignature33))) #endif #endif // PCL_NO_PRECOMPILE From b62ed27fbb342445dc8e87984e8f9eff6365925a Mon Sep 17 00:00:00 2001 From: Shrijit Singh Date: Sat, 18 Jul 2020 17:02:12 +0530 Subject: [PATCH 2/3] Update tests for compatability with merged FPFHEstimation & FPFHEstimationOMP class --- features/CMakeLists.txt | 1 - test/features/test_pfh_estimation.cpp | 41 +++++++-------------------- 2 files changed, 11 insertions(+), 31 deletions(-) diff --git a/features/CMakeLists.txt b/features/CMakeLists.txt index bbc5d5cfc42..827cde01725 100644 --- a/features/CMakeLists.txt +++ b/features/CMakeLists.txt @@ -80,7 +80,6 @@ set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/don.hpp" "include/pcl/${SUBSYS_NAME}/impl/feature.hpp" "include/pcl/${SUBSYS_NAME}/impl/fpfh.hpp" - "include/pcl/${SUBSYS_NAME}/impl/fpfh_omp.hpp" "include/pcl/${SUBSYS_NAME}/impl/gasd.hpp" "include/pcl/${SUBSYS_NAME}/impl/gfpfh.hpp" "include/pcl/${SUBSYS_NAME}/impl/integral_image2D.hpp" diff --git a/test/features/test_pfh_estimation.cpp b/test/features/test_pfh_estimation.cpp index 080d9acc617..d8bcf8fb800 100644 --- a/test/features/test_pfh_estimation.cpp +++ b/test/features/test_pfh_estimation.cpp @@ -46,7 +46,6 @@ #include #include #include -#include #include #include #include @@ -262,46 +261,28 @@ TEST (PCL, PFHEstimation) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// using pcl::FPFHEstimation; -using pcl::FPFHEstimationOMP; using pcl::FPFHSignature33; -// "Placeholder" for the type specialized test fixture -template -struct FPFHTest; - -// Template specialization test for FPFHEstimation -template<> -struct FPFHTest > - : public ::testing::Test +struct FPFHTest + : public ::testing::TestWithParam { FPFHEstimation fpfh; }; -// Template specialization test for FPFHEstimationOMP -template<> -struct FPFHTest > - : public ::testing::Test -{ - // Default Constructor is defined to instantiate 4 threads - FPFHTest > () - : fpfh (4) - {} - - FPFHEstimationOMP fpfh; -}; - -// Types which will be instantiated -using FPFHEstimatorTypes = ::testing::Types - , - FPFHEstimationOMP >; -TYPED_TEST_SUITE (FPFHTest, FPFHEstimatorTypes); +INSTANTIATE_TEST_CASE_P( + FPFHEstimationTests, + FPFHTest, + ::testing::Values( + -1, 4 + )); // This is a copy of the old FPFHEstimation test which will now // be applied to both FPFHEstimation and FPFHEstimationOMP -TYPED_TEST (FPFHTest, Estimation) +TEST_P (FPFHTest, Estimation) { // Create reference - TypeParam& fpfh = this->fpfh; + FPFHEstimation& fpfh = this->fpfh; + fpfh.setNumberOfThreads(GetParam()); fpfh.setInputNormals (cloud); EXPECT_EQ (fpfh.getInputNormals (), cloud); From 4440c4e53aa67df41f2b99ec3aa85f6f3f9c9f70 Mon Sep 17 00:00:00 2001 From: Shrijit Singh Date: Sat, 18 Jul 2020 17:09:32 +0530 Subject: [PATCH 3/3] Switch to SPDX style license --- features/include/pcl/features/fpfh.h | 33 +-------------------- features/include/pcl/features/impl/fpfh.hpp | 33 +-------------------- features/src/fpfh.cpp | 33 ++------------------- 3 files changed, 4 insertions(+), 95 deletions(-) diff --git a/features/include/pcl/features/fpfh.h b/features/include/pcl/features/fpfh.h index 8dc30e3fa33..d914897ab79 100644 --- a/features/include/pcl/features/fpfh.h +++ b/features/include/pcl/features/fpfh.h @@ -1,41 +1,10 @@ /* - * Software License Agreement (BSD License) + * SPDX-License-Identifier: BSD-3-Clause * * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2011, Willow Garage, Inc. * Copyright (c) 2012-, Open Perception, Inc. * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * */ #pragma once diff --git a/features/include/pcl/features/impl/fpfh.hpp b/features/include/pcl/features/impl/fpfh.hpp index e9faa256b0e..c653ffa610d 100644 --- a/features/include/pcl/features/impl/fpfh.hpp +++ b/features/include/pcl/features/impl/fpfh.hpp @@ -1,41 +1,10 @@ /* - * Software License Agreement (BSD License) + * SPDX-License-Identifier: BSD-3-Clause * * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2011, Willow Garage, Inc. * Copyright (c) 2012-, Open Perception, Inc. * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * */ #pragma once diff --git a/features/src/fpfh.cpp b/features/src/fpfh.cpp index 7c97872f07a..9a1a8df3bdb 100644 --- a/features/src/fpfh.cpp +++ b/features/src/fpfh.cpp @@ -1,39 +1,10 @@ /* - * Software License Agreement (BSD License) + * SPDX-License-Identifier: BSD-3-Clause * * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2012, Willow Garage, Inc. + * Copyright (c) 2010-2011, Willow Garage, Inc. * Copyright (c) 2012-, Open Perception, Inc. * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * */ #include