From d65df2ec07bf5018334a6c50cf920a43fb6c95e5 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Sat, 25 Apr 2020 10:31:04 +0000 Subject: [PATCH 001/123] add tests for CropHull applied suggestion from @kunaltyagi delete unused (knowingly falling) tests CropHull test refactor: callback -> SetUp/TearDown & vector of data CropHull test refactor. using TYPED_TEST_SUITE --- test/filters/CMakeLists.txt | 8 +- test/filters/test_crop_hull.cpp | 297 ++++++++++++++++++++++++++++++++ 2 files changed, 304 insertions(+), 1 deletion(-) create mode 100644 test/filters/test_crop_hull.cpp diff --git a/test/filters/CMakeLists.txt b/test/filters/CMakeLists.txt index df60939a849..c618bd4bb65 100644 --- a/test/filters/CMakeLists.txt +++ b/test/filters/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME tests_filters) set(SUBSYS_DESC "Point cloud library filters module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS filters) -set(OPT_DEPS io features segmentation) +set(OPT_DEPS io features segmentation surface) set(DEFAULT ON) set(build TRUE) @@ -37,6 +37,12 @@ PCL_ADD_TEST(filters_convolution test_convolution FILES test_convolution.cpp LINK_WITH pcl_gtest pcl_filters) +if (BUILD_surface AND QHULL_FOUND) + PCL_ADD_TEST(filters_crop_hull test_crop_hull + FILES test_crop_hull.cpp + LINK_WITH pcl_gtest pcl_surface pcl_filters) +endif() + if(BUILD_io) PCL_ADD_TEST(filters_bilateral test_filters_bilateral FILES test_bilateral.cpp diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp new file mode 100644 index 00000000000..2c91095629c --- /dev/null +++ b/test/filters/test_crop_hull.cpp @@ -0,0 +1,297 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * 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: test_filters.cpp 7683 2012-10-23 02:49:03Z rusu $ + * + */ + +#include +#include + +#include + +#include +#include +#include +#include + + +namespace +{ + bool randomBool() + { + static std::default_random_engine gen; + static std::uniform_int_distribution<> int_distr(0, 1); + return int_distr(gen); + } + + struct TestData + { + TestData(pcl::Indices const & insideIndices, pcl::PointCloud::ConstPtr inputCloud) + : inputCloud(inputCloud), + insideMask(inputCloud->size(), false), + insideIndices(insideIndices), + insideCloud(new pcl::PointCloud), + outsideCloud(new pcl::PointCloud) + { + pcl::copyPointCloud(*inputCloud, insideIndices, *insideCloud); + for (pcl::index_t idx : insideIndices) { + insideMask[idx] = true; + } + for (size_t i = 0; i < inputCloud->size(); ++i) { + if (!insideMask[i]) { + outsideIndices.push_back(i); + } + } + pcl::copyPointCloud(*inputCloud, outsideIndices, *outsideCloud); + } + + pcl::PointCloud::ConstPtr inputCloud; + std::vector insideMask; + pcl::Indices insideIndices, outsideIndices; + pcl::PointCloud::Ptr insideCloud, outsideCloud; + }; + + + std::vector + createTestDataSuite( + std::function insidePointGenerator, + std::function outsidePointGenerator) + { + std::vector testDataSuite; + size_t const chunkSize = 1000; + pcl::PointCloud::Ptr insideCloud(new pcl::PointCloud); + pcl::PointCloud::Ptr outsideCloud(new pcl::PointCloud); + pcl::PointCloud::Ptr mixedCloud(new pcl::PointCloud); + pcl::Indices insideIndicesForInsideCloud; + pcl::Indices insideIndicesForOutsideCloud; // empty indices, cause outsideCloud don't contains any inside point + pcl::Indices insideIndicesForMixedCloud; + for (size_t i = 0; i < chunkSize; ++i) + { + insideIndicesForInsideCloud.push_back(i); + insideCloud->push_back(insidePointGenerator()); + outsideCloud->push_back(outsidePointGenerator()); + if (randomBool()) { + insideIndicesForMixedCloud.push_back(i); + mixedCloud->push_back(insidePointGenerator()); + } + else { + mixedCloud->push_back(outsidePointGenerator()); + } + } + testDataSuite.emplace_back(std::move(insideIndicesForInsideCloud), insideCloud); + testDataSuite.emplace_back(std::move(insideIndicesForOutsideCloud), outsideCloud); + testDataSuite.emplace_back(std::move(insideIndicesForMixedCloud), mixedCloud); + return testDataSuite; + } + + + template + class PCLCropHullTestFixture : public ::testing::Test + { + public: + PCLCropHullTestFixture() + : gen(12345u), + rd(0.0f, 1.0f) + { + baseOffsetList.emplace_back(0, 0, 0); + baseOffsetList.emplace_back(5, 1, 10); + baseOffsetList.emplace_back(1, 5, 10); + baseOffsetList.emplace_back(1, 10, 5); + baseOffsetList.emplace_back(10, 1, 5); + baseOffsetList.emplace_back(10, 5, 1); + } + protected: + + void SetUp() override + { + data.clear(); + pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); + for (pcl::PointXYZ const & baseOffset : baseOffsetList) + { + pcl::copyPointCloud(*CropHullTestTraits::getInputCloud(), *inputCloud); + for (pcl::PointXYZ & p : *inputCloud) { + p.getVector3fMap() += baseOffset.getVector3fMap(); + } + auto insidePointGenerator = [this, &baseOffset] () { + pcl::PointXYZ p(rd(gen), rd(gen), rd(gen)); + p.getVector3fMap() += baseOffset.getVector3fMap(); + return p; + }; + auto outsidePointGenerator = [this, &baseOffset] () { + pcl::PointXYZ p(rd(gen) + 2., rd(gen) + 2., rd(gen) + 2.); + p.getVector3fMap() += baseOffset.getVector3fMap(); + return p; + }; + pcl::CropHull cropHullFilter = createDefaultCropHull(inputCloud); + std::vector testDataSuite = createTestDataSuite(insidePointGenerator, outsidePointGenerator); + data.emplace_back(cropHullFilter, testDataSuite); + } + } + + std::vector, std::vector>> data; + + private: + pcl::CropHull createDefaultCropHull (pcl::PointCloud::ConstPtr inputCloud) const + { + //pcl::CropHull cropHullFilter(true); + pcl::CropHull cropHullFilter; + pcl::ConvexHull convexHull; + convexHull.setDimension(3); + convexHull.setInputCloud(inputCloud); + pcl::PointCloud::Ptr hullCloudPtr(new pcl::PointCloud); + std::vector hullPolygons; + convexHull.reconstruct(*hullCloudPtr, hullPolygons); + cropHullFilter.setHullIndices(hullPolygons); + cropHullFilter.setHullCloud(hullCloudPtr); + cropHullFilter.setDim(CropHullTestTraits::getDim()); + return cropHullFilter; + } + + mutable std::mt19937 gen; + mutable std::uniform_real_distribution rd; + pcl::PointCloud baseOffsetList; + }; + + + struct CropHullTestTraits2d + { + static pcl::PointCloud::ConstPtr getInputCloud() + { + static pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); + if (inputCloud->empty()) { + for (const float i: {0.f, 1.f}) + for (const float j: {0.f, 1.f}) + for (const float k: {0.f, -0.1f}) + inputCloud->emplace_back(i, j, k); + } + return inputCloud; + } + static int getDim() { + return 2; + } + }; + + + struct CropHullTestTraits3d + { + static pcl::PointCloud::ConstPtr getInputCloud() + { + static pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); + if (inputCloud->empty()) { + for (const float i: {0.f, 1.f}) + for (const float j: {0.f, 1.f}) + for (const float k: {0.f, 1.f}) + inputCloud->emplace_back(i, j, k); + } + return inputCloud; + } + static int getDim() { + return 3; + } + }; +} +using CropHullTestTypes = ::testing::Types; +TYPED_TEST_SUITE(PCLCropHullTestFixture, CropHullTestTypes); + + +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +// since test input cloud has same distribution for all dimensions, this test also check problem from issue #3960 // +TYPED_TEST (PCLCropHullTestFixture, simple_test) +{ + for (auto & entry : this->data) + { + auto & cropHullFilter = entry.first; + for (TestData const & testData : entry.second) + { + cropHullFilter.setInputCloud(testData.inputCloud); + pcl::Indices filteredIndices; + cropHullFilter.filter(filteredIndices); + pcl::test::EXPECT_EQ_VECTORS(testData.insideIndices, filteredIndices); + } + } +} + + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +// this test will pass only for 2d case // +using PCLCropHullTestFixture2d = PCLCropHullTestFixture; +TEST_F (PCLCropHullTestFixture2d, test_crop_inside) +{ + for (auto & entry : this->data) + { + auto & cropHullFilter = entry.first; + for (TestData const & testData : entry.second) + { + cropHullFilter.setInputCloud(testData.inputCloud); + cropHullFilter.setCropOutside(false); + pcl::Indices filteredIndices; + cropHullFilter.filter(filteredIndices); + pcl::test::EXPECT_EQ_VECTORS(testData.outsideIndices, filteredIndices); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +TYPED_TEST (PCLCropHullTestFixture, test_cloud_filtering) +{ + for (auto & entry : this->data) + { + auto & cropHullFilter = entry.first; + for (TestData const & testData : entry.second) + { + cropHullFilter.setInputCloud(testData.inputCloud); + pcl::PointCloud filteredCloud; + cropHullFilter.filter(filteredCloud); + ASSERT_EQ (testData.insideCloud->size(), filteredCloud.size()); + for (pcl::index_t i = 0; i < testData.insideCloud->size(); ++i) + { + EXPECT_XYZ_NEAR(testData.insideCloud->at(i), filteredCloud[i], 1e-5); + } + } + } +} + + + +/* ---[ */ +int +main (int argc, char** argv) +{ + // Testing + testing::InitGoogleTest (&argc, argv); + return (RUN_ALL_TESTS ()); +} +/* ]--- */ From 01f83ff9a27f23eaba556cf677b7b5fbe188daf4 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Sat, 25 Apr 2020 10:34:54 +0000 Subject: [PATCH 002/123] fixup bug from issue 3960 --- filters/include/pcl/filters/impl/crop_hull.hpp | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/filters/include/pcl/filters/impl/crop_hull.hpp b/filters/include/pcl/filters/impl/crop_hull.hpp index 2a784c107bf..cdceb0ac899 100644 --- a/filters/include/pcl/filters/impl/crop_hull.hpp +++ b/filters/include/pcl/filters/impl/crop_hull.hpp @@ -104,16 +104,19 @@ pcl::CropHull::getHullCloudRange () -std::numeric_limits::max (), -std::numeric_limits::max () ); - for (std::size_t index = 0; index < indices_->size (); index++) + for (pcl::Vertices const & poly : hull_polygons_) { - Eigen::Vector3f pt = (*input_)[(*indices_)[index]].getVector3fMap (); - for (int i = 0; i < 3; i++) + for (std::uint32_t const & idx : poly.vertices) { - if (pt[i] < cloud_min[i]) cloud_min[i] = pt[i]; - if (pt[i] > cloud_max[i]) cloud_max[i] = pt[i]; + Eigen::Vector3f pt = hull_cloud_->points[idx].getVector3fMap (); + for (int i = 0; i < 3; i++) + { + if (pt[i] < cloud_min[i]) cloud_min[i] = pt[i]; + if (pt[i] > cloud_max[i]) cloud_max[i] = pt[i]; + } } } - + return (cloud_max - cloud_min); } From 3254e525895bd49bcabfffc1564142f4ae92b573 Mon Sep 17 00:00:00 2001 From: DaniilSNikulin <31708320+DaniilSNikulin@users.noreply.github.com> Date: Thu, 7 May 2020 19:43:38 +0300 Subject: [PATCH 003/123] Update filters/include/pcl/filters/impl/crop_hull.hpp MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Sérgio Agostinho --- filters/include/pcl/filters/impl/crop_hull.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/filters/include/pcl/filters/impl/crop_hull.hpp b/filters/include/pcl/filters/impl/crop_hull.hpp index cdceb0ac899..12e68c88ea8 100644 --- a/filters/include/pcl/filters/impl/crop_hull.hpp +++ b/filters/include/pcl/filters/impl/crop_hull.hpp @@ -108,7 +108,7 @@ pcl::CropHull::getHullCloudRange () { for (std::uint32_t const & idx : poly.vertices) { - Eigen::Vector3f pt = hull_cloud_->points[idx].getVector3fMap (); + Eigen::Vector3f pt = (*hull_cloud_)[idx].getVector3fMap (); for (int i = 0; i < 3; i++) { if (pt[i] < cloud_min[i]) cloud_min[i] = pt[i]; From 3241e7aea1a76e33ecb55dffbe98f4573beaa3a0 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Thu, 7 May 2020 18:00:37 +0000 Subject: [PATCH 004/123] CropHull test refactor according pcl style guide --- test/filters/test_crop_hull.cpp | 390 +++++++++++++++++--------------- 1 file changed, 209 insertions(+), 181 deletions(-) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 2c91095629c..41206497775 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -37,11 +37,11 @@ * */ +#include + #include #include -#include - #include #include #include @@ -50,179 +50,206 @@ namespace { - bool randomBool() - { - static std::default_random_engine gen; - static std::uniform_int_distribution<> int_distr(0, 1); - return int_distr(gen); - } - struct TestData +bool +getRandomBool () +{ + static std::default_random_engine gen; + static std::uniform_int_distribution<> int_distr(0, 1); + return int_distr(gen); +} + +struct TestData +{ + TestData(pcl::Indices const & insideIndices, pcl::PointCloud::ConstPtr input_cloud) + : input_cloud_(input_cloud), + inside_mask_(input_cloud_->size(), false), + inside_indices_(insideIndices), + inside_cloud_(new pcl::PointCloud), + outside_cloud_(new pcl::PointCloud) { - TestData(pcl::Indices const & insideIndices, pcl::PointCloud::ConstPtr inputCloud) - : inputCloud(inputCloud), - insideMask(inputCloud->size(), false), - insideIndices(insideIndices), - insideCloud(new pcl::PointCloud), - outsideCloud(new pcl::PointCloud) - { - pcl::copyPointCloud(*inputCloud, insideIndices, *insideCloud); - for (pcl::index_t idx : insideIndices) { - insideMask[idx] = true; - } - for (size_t i = 0; i < inputCloud->size(); ++i) { - if (!insideMask[i]) { - outsideIndices.push_back(i); - } + pcl::copyPointCloud(*input_cloud_, inside_indices_, *inside_cloud_); + for (pcl::index_t idx : inside_indices_) { + inside_mask_[idx] = true; + } + for (size_t i = 0; i < input_cloud_->size(); ++i) { + if (!inside_mask_[i]) { + outside_indices_.push_back(i); } - pcl::copyPointCloud(*inputCloud, outsideIndices, *outsideCloud); } + pcl::copyPointCloud(*input_cloud_, outside_indices_, *outside_cloud_); + } - pcl::PointCloud::ConstPtr inputCloud; - std::vector insideMask; - pcl::Indices insideIndices, outsideIndices; - pcl::PointCloud::Ptr insideCloud, outsideCloud; - }; + pcl::PointCloud::ConstPtr input_cloud_; + std::vector inside_mask_; + pcl::Indices inside_indices_, outside_indices_; + pcl::PointCloud::Ptr inside_cloud_, outside_cloud_; +}; - std::vector - createTestDataSuite( - std::function insidePointGenerator, - std::function outsidePointGenerator) +std::vector +createTestDataSuite( + std::function inside_point_generator, + std::function outside_point_generator) +{ + std::vector test_data_suite; + size_t const chunk_size = 1000; + pcl::PointCloud::Ptr inside_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr outside_cloud(new pcl::PointCloud); + pcl::PointCloud::Ptr mixed_cloud(new pcl::PointCloud); + pcl::Indices inside_indices_for_inside_cloud; + pcl::Indices inside_indices_for_outside_cloud; // empty indices, cause outside_cloud don't contains any inside point + pcl::Indices inside_indices_for_mixed_cloud; + for (size_t i = 0; i < chunk_size; ++i) { - std::vector testDataSuite; - size_t const chunkSize = 1000; - pcl::PointCloud::Ptr insideCloud(new pcl::PointCloud); - pcl::PointCloud::Ptr outsideCloud(new pcl::PointCloud); - pcl::PointCloud::Ptr mixedCloud(new pcl::PointCloud); - pcl::Indices insideIndicesForInsideCloud; - pcl::Indices insideIndicesForOutsideCloud; // empty indices, cause outsideCloud don't contains any inside point - pcl::Indices insideIndicesForMixedCloud; - for (size_t i = 0; i < chunkSize; ++i) - { - insideIndicesForInsideCloud.push_back(i); - insideCloud->push_back(insidePointGenerator()); - outsideCloud->push_back(outsidePointGenerator()); - if (randomBool()) { - insideIndicesForMixedCloud.push_back(i); - mixedCloud->push_back(insidePointGenerator()); - } - else { - mixedCloud->push_back(outsidePointGenerator()); - } + inside_indices_for_inside_cloud.push_back(i); + inside_cloud->push_back(inside_point_generator()); + outside_cloud->push_back(outside_point_generator()); + if (getRandomBool()) { + inside_indices_for_mixed_cloud.push_back(i); + mixed_cloud->push_back(inside_point_generator()); + } + else { + mixed_cloud->push_back(outside_point_generator()); } - testDataSuite.emplace_back(std::move(insideIndicesForInsideCloud), insideCloud); - testDataSuite.emplace_back(std::move(insideIndicesForOutsideCloud), outsideCloud); - testDataSuite.emplace_back(std::move(insideIndicesForMixedCloud), mixedCloud); - return testDataSuite; } + test_data_suite.emplace_back(std::move(inside_indices_for_inside_cloud), inside_cloud); + test_data_suite.emplace_back(std::move(inside_indices_for_outside_cloud), outside_cloud); + test_data_suite.emplace_back(std::move(inside_indices_for_mixed_cloud), mixed_cloud); + return test_data_suite; +} - template - class PCLCropHullTestFixture : public ::testing::Test - { - public: - PCLCropHullTestFixture() - : gen(12345u), - rd(0.0f, 1.0f) - { - baseOffsetList.emplace_back(0, 0, 0); - baseOffsetList.emplace_back(5, 1, 10); - baseOffsetList.emplace_back(1, 5, 10); - baseOffsetList.emplace_back(1, 10, 5); - baseOffsetList.emplace_back(10, 1, 5); - baseOffsetList.emplace_back(10, 5, 1); - } - protected: +template +class PCLCropHullTestFixture : public ::testing::Test +{ + public: + PCLCropHullTestFixture() + : gen_(12345u), + rd_(0.0f, 1.0f) + { + baseOffsetList_.emplace_back(0, 0, 0); + baseOffsetList_.emplace_back(5, 1, 10); + baseOffsetList_.emplace_back(1, 5, 10); + baseOffsetList_.emplace_back(1, 10, 5); + baseOffsetList_.emplace_back(10, 1, 5); + baseOffsetList_.emplace_back(10, 5, 1); + } + protected: - void SetUp() override + void + SetUp () override + { + data_.clear(); + pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); + for (pcl::PointXYZ const & baseOffset : baseOffsetList_) { - data.clear(); - pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); - for (pcl::PointXYZ const & baseOffset : baseOffsetList) - { - pcl::copyPointCloud(*CropHullTestTraits::getInputCloud(), *inputCloud); - for (pcl::PointXYZ & p : *inputCloud) { - p.getVector3fMap() += baseOffset.getVector3fMap(); - } - auto insidePointGenerator = [this, &baseOffset] () { - pcl::PointXYZ p(rd(gen), rd(gen), rd(gen)); - p.getVector3fMap() += baseOffset.getVector3fMap(); - return p; - }; - auto outsidePointGenerator = [this, &baseOffset] () { - pcl::PointXYZ p(rd(gen) + 2., rd(gen) + 2., rd(gen) + 2.); - p.getVector3fMap() += baseOffset.getVector3fMap(); - return p; - }; - pcl::CropHull cropHullFilter = createDefaultCropHull(inputCloud); - std::vector testDataSuite = createTestDataSuite(insidePointGenerator, outsidePointGenerator); - data.emplace_back(cropHullFilter, testDataSuite); + pcl::copyPointCloud(*CropHullTestTraits::getInputCloud(), *input_cloud); + for (pcl::PointXYZ & p : *input_cloud) { + p.getVector3fMap() += baseOffset.getVector3fMap(); } + auto inside_point_generator = [this, &baseOffset] () { + pcl::PointXYZ p(rd_(gen_), rd_(gen_), rd_(gen_)); + p.getVector3fMap() += baseOffset.getVector3fMap(); + return p; + }; + auto outside_point_generator = [this, &baseOffset] () { + pcl::PointXYZ p(rd_(gen_) + 2., rd_(gen_) + 2., rd_(gen_) + 2.); + p.getVector3fMap() += baseOffset.getVector3fMap(); + return p; + }; + pcl::CropHull crop_hull_filter = createDefaultCropHull(input_cloud); + std::vector test_data_suite = createTestDataSuite(inside_point_generator, outside_point_generator); + data_.emplace_back(crop_hull_filter, test_data_suite); } + } - std::vector, std::vector>> data; + std::vector, std::vector>> data_; - private: - pcl::CropHull createDefaultCropHull (pcl::PointCloud::ConstPtr inputCloud) const - { - //pcl::CropHull cropHullFilter(true); - pcl::CropHull cropHullFilter; - pcl::ConvexHull convexHull; - convexHull.setDimension(3); - convexHull.setInputCloud(inputCloud); - pcl::PointCloud::Ptr hullCloudPtr(new pcl::PointCloud); - std::vector hullPolygons; - convexHull.reconstruct(*hullCloudPtr, hullPolygons); - cropHullFilter.setHullIndices(hullPolygons); - cropHullFilter.setHullCloud(hullCloudPtr); - cropHullFilter.setDim(CropHullTestTraits::getDim()); - return cropHullFilter; - } + private: + pcl::CropHull + createDefaultCropHull (pcl::PointCloud::ConstPtr input_cloud) const + { + //pcl::CropHull crop_hull_filter(true); + pcl::CropHull crop_hull_filter; + pcl::ConvexHull convex_hull; + convex_hull.setDimension(3); + convex_hull.setInputCloud(input_cloud); + pcl::PointCloud::Ptr hull_cloud_ptr(new pcl::PointCloud); + std::vector hull_polygons; + convex_hull.reconstruct(*hull_cloud_ptr, hull_polygons); + crop_hull_filter.setHullIndices(hull_polygons); + crop_hull_filter.setHullCloud(hull_cloud_ptr); + crop_hull_filter.setDim(CropHullTestTraits::getDim()); + return crop_hull_filter; + } - mutable std::mt19937 gen; - mutable std::uniform_real_distribution rd; - pcl::PointCloud baseOffsetList; - }; + mutable std::mt19937 gen_; + mutable std::uniform_real_distribution rd_; + pcl::PointCloud baseOffsetList_; +}; - struct CropHullTestTraits2d - { - static pcl::PointCloud::ConstPtr getInputCloud() - { - static pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); - if (inputCloud->empty()) { - for (const float i: {0.f, 1.f}) - for (const float j: {0.f, 1.f}) - for (const float k: {0.f, -0.1f}) - inputCloud->emplace_back(i, j, k); - } - return inputCloud; - } - static int getDim() { - return 2; - } - }; +struct CropHullTestTraits2d +{ + static pcl::PointCloud::ConstPtr + getInputCloud(); + static int + getDim(); +}; - struct CropHullTestTraits3d - { - static pcl::PointCloud::ConstPtr getInputCloud() - { - static pcl::PointCloud::Ptr inputCloud (new pcl::PointCloud); - if (inputCloud->empty()) { - for (const float i: {0.f, 1.f}) - for (const float j: {0.f, 1.f}) - for (const float k: {0.f, 1.f}) - inputCloud->emplace_back(i, j, k); - } - return inputCloud; - } - static int getDim() { - return 3; - } - }; + +struct CropHullTestTraits3d +{ + static pcl::PointCloud::ConstPtr + getInputCloud(); + + static int + getDim(); +}; + + +pcl::PointCloud::ConstPtr +CropHullTestTraits2d::getInputCloud () +{ + static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); + if (input_cloud->empty()) { + for (const float i: {0.f, 1.f}) + for (const float j: {0.f, 1.f}) + for (const float k: {0.f, -0.1f}) + input_cloud->emplace_back(i, j, k); + } + return input_cloud; +} + +int +CropHullTestTraits2d::getDim () +{ + return 2; +} + + +pcl::PointCloud::ConstPtr +CropHullTestTraits3d::getInputCloud () +{ + static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); + if (input_cloud->empty()) { + for (const float i: {0.f, 1.f}) + for (const float j: {0.f, 1.f}) + for (const float k: {0.f, 1.f}) + input_cloud->emplace_back(i, j, k); + } + return input_cloud; } + +int +CropHullTestTraits3d::getDim () +{ + return 3; +} + +} // end of anonymous namespace using CropHullTestTypes = ::testing::Types; TYPED_TEST_SUITE(PCLCropHullTestFixture, CropHullTestTypes); @@ -231,55 +258,56 @@ TYPED_TEST_SUITE(PCLCropHullTestFixture, CropHullTestTypes); // since test input cloud has same distribution for all dimensions, this test also check problem from issue #3960 // TYPED_TEST (PCLCropHullTestFixture, simple_test) { - for (auto & entry : this->data) + for (auto & entry : this->data_) { - auto & cropHullFilter = entry.first; - for (TestData const & testData : entry.second) + auto & crop_hull_filter = entry.first; + for (TestData const & test_data : entry.second) { - cropHullFilter.setInputCloud(testData.inputCloud); - pcl::Indices filteredIndices; - cropHullFilter.filter(filteredIndices); - pcl::test::EXPECT_EQ_VECTORS(testData.insideIndices, filteredIndices); + crop_hull_filter.setInputCloud(test_data.input_cloud_); + pcl::Indices filtered_indices; + crop_hull_filter.filter(filtered_indices); + pcl::test::EXPECT_EQ_VECTORS(test_data.inside_indices_, filtered_indices); } } } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -// this test will pass only for 2d case // -using PCLCropHullTestFixture2d = PCLCropHullTestFixture; -TEST_F (PCLCropHullTestFixture2d, test_crop_inside) +TYPED_TEST (PCLCropHullTestFixture, test_cloud_filtering) { - for (auto & entry : this->data) + for (auto & entry : this->data_) { - auto & cropHullFilter = entry.first; - for (TestData const & testData : entry.second) + auto & crop_hull_filter = entry.first; + for (TestData const & test_data : entry.second) { - cropHullFilter.setInputCloud(testData.inputCloud); - cropHullFilter.setCropOutside(false); - pcl::Indices filteredIndices; - cropHullFilter.filter(filteredIndices); - pcl::test::EXPECT_EQ_VECTORS(testData.outsideIndices, filteredIndices); + crop_hull_filter.setInputCloud(test_data.input_cloud_); + pcl::PointCloud filteredCloud; + crop_hull_filter.filter(filteredCloud); + ASSERT_EQ (test_data.inside_cloud_->size(), filteredCloud.size()); + for (pcl::index_t i = 0; i < test_data.inside_cloud_->size(); ++i) + { + EXPECT_XYZ_NEAR(test_data.inside_cloud_->at(i), filteredCloud[i], 1e-5); + } } } } + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TYPED_TEST (PCLCropHullTestFixture, test_cloud_filtering) +// this test will pass only for 2d case // +using PCLCropHullTestFixture2d = PCLCropHullTestFixture; +TEST_F (PCLCropHullTestFixture2d, test_crop_inside) { - for (auto & entry : this->data) + for (auto & entry : this->data_) { - auto & cropHullFilter = entry.first; - for (TestData const & testData : entry.second) + auto & crop_hull_filter = entry.first; + for (TestData const & test_data : entry.second) { - cropHullFilter.setInputCloud(testData.inputCloud); - pcl::PointCloud filteredCloud; - cropHullFilter.filter(filteredCloud); - ASSERT_EQ (testData.insideCloud->size(), filteredCloud.size()); - for (pcl::index_t i = 0; i < testData.insideCloud->size(); ++i) - { - EXPECT_XYZ_NEAR(testData.insideCloud->at(i), filteredCloud[i], 1e-5); - } + crop_hull_filter.setInputCloud(test_data.input_cloud_); + crop_hull_filter.setCropOutside(false); + pcl::Indices filtered_indices; + crop_hull_filter.filter(filtered_indices); + pcl::test::EXPECT_EQ_VECTORS(test_data.outside_indices_, filtered_indices); } } } From 8eaabfb8ef24b5ed5a5ae7f44ef7878a9fc43f1f Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Sat, 25 Apr 2020 10:31:04 +0000 Subject: [PATCH 005/123] add tests for CropHull applied suggestion from @kunaltyagi delete unused (knowingly falling) tests CropHull test refactor: callback -> SetUp/TearDown & vector of data CropHull test refactor. using TYPED_TEST_SUITE --- test/filters/CMakeLists.txt | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/test/filters/CMakeLists.txt b/test/filters/CMakeLists.txt index c618bd4bb65..ed427dec9db 100644 --- a/test/filters/CMakeLists.txt +++ b/test/filters/CMakeLists.txt @@ -33,15 +33,14 @@ PCL_ADD_TEST(filters_uniform_sampling test_uniform_sampling FILES test_uniform_sampling.cpp LINK_WITH pcl_gtest pcl_common pcl_filters) + PCL_ADD_TEST(filters_convolution test_convolution FILES test_convolution.cpp LINK_WITH pcl_gtest pcl_filters) -if (BUILD_surface AND QHULL_FOUND) - PCL_ADD_TEST(filters_crop_hull test_crop_hull - FILES test_crop_hull.cpp - LINK_WITH pcl_gtest pcl_surface pcl_filters) -endif() +PCL_ADD_TEST(filters_crop_hull test_crop_hull + FILES test_crop_hull.cpp + LINK_WITH pcl_gtest pcl_filters) if(BUILD_io) PCL_ADD_TEST(filters_bilateral test_filters_bilateral From 082eede2a64ad6f32a4bdd64866a588dd2689475 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Mon, 27 Jul 2020 16:52:15 +0000 Subject: [PATCH 006/123] delete [surface] module from dependecies for tests --- .../include/pcl/filters/impl/crop_hull.hpp | 7 +- test/filters/CMakeLists.txt | 7 +- test/filters/test_crop_hull.cpp | 106 ++++++++++-------- 3 files changed, 62 insertions(+), 58 deletions(-) diff --git a/filters/include/pcl/filters/impl/crop_hull.hpp b/filters/include/pcl/filters/impl/crop_hull.hpp index 12e68c88ea8..7b913ba6bf0 100644 --- a/filters/include/pcl/filters/impl/crop_hull.hpp +++ b/filters/include/pcl/filters/impl/crop_hull.hpp @@ -109,11 +109,8 @@ pcl::CropHull::getHullCloudRange () for (std::uint32_t const & idx : poly.vertices) { Eigen::Vector3f pt = (*hull_cloud_)[idx].getVector3fMap (); - for (int i = 0; i < 3; i++) - { - if (pt[i] < cloud_min[i]) cloud_min[i] = pt[i]; - if (pt[i] > cloud_max[i]) cloud_max[i] = pt[i]; - } + cloud_min = cloud_min.cwiseMin(pt); + cloud_max = cloud_max.cwiseMax(pt); } } diff --git a/test/filters/CMakeLists.txt b/test/filters/CMakeLists.txt index ed427dec9db..1cbb324938b 100644 --- a/test/filters/CMakeLists.txt +++ b/test/filters/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME tests_filters) set(SUBSYS_DESC "Point cloud library filters module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS filters) -set(OPT_DEPS io features segmentation surface) +set(OPT_DEPS io features segmentation) set(DEFAULT ON) set(build TRUE) @@ -33,10 +33,9 @@ PCL_ADD_TEST(filters_uniform_sampling test_uniform_sampling FILES test_uniform_sampling.cpp LINK_WITH pcl_gtest pcl_common pcl_filters) - PCL_ADD_TEST(filters_convolution test_convolution - FILES test_convolution.cpp - LINK_WITH pcl_gtest pcl_filters) + FILES test_convolution.cpp + LINK_WITH pcl_gtest pcl_filters) PCL_ADD_TEST(filters_crop_hull test_crop_hull FILES test_crop_hull.cpp diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 41206497775..774c7a26581 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -1,49 +1,19 @@ /* - * Software License Agreement (BSD License) + * SPDX-License-Identifier: BSD-3-Clause * - * Point Cloud Library (PCL) - www.pointclouds.org - * 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: test_filters.cpp 7683 2012-10-23 02:49:03Z rusu $ + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. * */ #include +#include #include #include #include -#include #include #include @@ -144,7 +114,7 @@ class PCLCropHullTestFixture : public ::testing::Test pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); for (pcl::PointXYZ const & baseOffset : baseOffsetList_) { - pcl::copyPointCloud(*CropHullTestTraits::getInputCloud(), *input_cloud); + pcl::copyPointCloud(*CropHullTestTraits::getHullCloud(), *input_cloud); for (pcl::PointXYZ & p : *input_cloud) { p.getVector3fMap() += baseOffset.getVector3fMap(); } @@ -154,7 +124,9 @@ class PCLCropHullTestFixture : public ::testing::Test return p; }; auto outside_point_generator = [this, &baseOffset] () { - pcl::PointXYZ p(rd_(gen_) + 2., rd_(gen_) + 2., rd_(gen_) + 2.); + std::array pt; + std::generate(pt.begin(), pt.end(), [this] {return rd_(gen_) + 2. * (getRandomBool() ? -1. : 1.);}); + pcl::PointXYZ p(pt[0], pt[1], pt[2]); p.getVector3fMap() += baseOffset.getVector3fMap(); return p; }; @@ -172,14 +144,8 @@ class PCLCropHullTestFixture : public ::testing::Test { //pcl::CropHull crop_hull_filter(true); pcl::CropHull crop_hull_filter; - pcl::ConvexHull convex_hull; - convex_hull.setDimension(3); - convex_hull.setInputCloud(input_cloud); - pcl::PointCloud::Ptr hull_cloud_ptr(new pcl::PointCloud); - std::vector hull_polygons; - convex_hull.reconstruct(*hull_cloud_ptr, hull_polygons); - crop_hull_filter.setHullIndices(hull_polygons); - crop_hull_filter.setHullCloud(hull_cloud_ptr); + crop_hull_filter.setHullCloud(input_cloud->makeShared()); + crop_hull_filter.setHullIndices(CropHullTestTraits::getHullPolygons()); crop_hull_filter.setDim(CropHullTestTraits::getDim()); return crop_hull_filter; } @@ -193,7 +159,10 @@ class PCLCropHullTestFixture : public ::testing::Test struct CropHullTestTraits2d { static pcl::PointCloud::ConstPtr - getInputCloud(); + getHullCloud(); + + static std::vector + getHullPolygons(); static int getDim(); @@ -203,15 +172,34 @@ struct CropHullTestTraits2d struct CropHullTestTraits3d { static pcl::PointCloud::ConstPtr - getInputCloud(); + getHullCloud(); + + static std::vector + getHullPolygons(); static int getDim(); }; +static std::vector> cube_elements = { + {0, 2, 1}, // l + {1, 2, 3}, // l + {3, 2, 6}, // f + {6, 2, 4}, // bt + {4, 2, 0}, // bt + {3, 7, 1}, // t + {1, 7, 5}, // t + {5, 7, 4}, // r + {4, 7, 6}, // r + {6, 7, 3}, // f + {5, 1, 4}, // back + {4, 1, 0} // back +}; + + pcl::PointCloud::ConstPtr -CropHullTestTraits2d::getInputCloud () +CropHullTestTraits2d::getHullCloud () { static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); if (input_cloud->empty()) { @@ -223,6 +211,16 @@ CropHullTestTraits2d::getInputCloud () return input_cloud; } +std::vector +CropHullTestTraits2d::getHullPolygons () +{ + std::vector polygons(12); + for (size_t i = 0; i < 12; ++i) { + polygons[i].vertices = cube_elements[i]; + } + return polygons; +} + int CropHullTestTraits2d::getDim () { @@ -231,7 +229,7 @@ CropHullTestTraits2d::getDim () pcl::PointCloud::ConstPtr -CropHullTestTraits3d::getInputCloud () +CropHullTestTraits3d::getHullCloud () { static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); if (input_cloud->empty()) { @@ -243,6 +241,16 @@ CropHullTestTraits3d::getInputCloud () return input_cloud; } +std::vector +CropHullTestTraits3d::getHullPolygons () +{ + std::vector polygons(12); + for (size_t i = 0; i < 12; ++i) { + polygons[i].vertices = cube_elements[i]; + } + return polygons; +} + int CropHullTestTraits3d::getDim () { From d6644d71d1cde12d0f7baafd2cc3687a168ca58b Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Tue, 28 Jul 2020 11:52:52 +0000 Subject: [PATCH 007/123] delete implicit comparison pcl::index_t and std::size_t --- test/filters/test_crop_hull.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 774c7a26581..1d818cb1fd4 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -292,7 +292,8 @@ TYPED_TEST (PCLCropHullTestFixture, test_cloud_filtering) pcl::PointCloud filteredCloud; crop_hull_filter.filter(filteredCloud); ASSERT_EQ (test_data.inside_cloud_->size(), filteredCloud.size()); - for (pcl::index_t i = 0; i < test_data.inside_cloud_->size(); ++i) + pcl::index_t cloud_size = test_data.inside_cloud_->size(); + for (pcl::index_t i = 0; i < cloud_size; ++i) { EXPECT_XYZ_NEAR(test_data.inside_cloud_->at(i), filteredCloud[i], 1e-5); } From b0661d65e45269e9072b1aa6571040933f87fe36 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Tue, 28 Jul 2020 14:05:34 +0000 Subject: [PATCH 008/123] add explicit include header --- test/filters/test_crop_hull.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 1d818cb1fd4..94fe9effbbe 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -9,6 +9,7 @@ #include #include +#include #include #include From ddee39af6ecd8c45a5f74d27187c188b10edbb4e Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Mon, 10 Aug 2020 13:54:13 +0000 Subject: [PATCH 009/123] create multiple seeds for random point generator --- test/filters/test_crop_hull.cpp | 87 ++++++++++++++++++++++++--------- 1 file changed, 64 insertions(+), 23 deletions(-) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 94fe9effbbe..0b534f1e59a 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -22,13 +23,6 @@ namespace { -bool -getRandomBool () -{ - static std::default_random_engine gen; - static std::uniform_int_distribution<> int_distr(0, 1); - return int_distr(gen); -} struct TestData { @@ -76,7 +70,7 @@ createTestDataSuite( inside_indices_for_inside_cloud.push_back(i); inside_cloud->push_back(inside_point_generator()); outside_cloud->push_back(outside_point_generator()); - if (getRandomBool()) { + if (i % 2) { inside_indices_for_mixed_cloud.push_back(i); mixed_cloud->push_back(inside_point_generator()); } @@ -91,13 +85,14 @@ createTestDataSuite( } -template +template class PCLCropHullTestFixture : public ::testing::Test { public: + using CropHullTestTraits = typename std::tuple_element<0, TupleType>::type; + using RandomGeneratorType = typename std::tuple_element<1, TupleType>::type; + PCLCropHullTestFixture() - : gen_(12345u), - rd_(0.0f, 1.0f) { baseOffsetList_.emplace_back(0, 0, 0); baseOffsetList_.emplace_back(5, 1, 10); @@ -120,13 +115,17 @@ class PCLCropHullTestFixture : public ::testing::Test p.getVector3fMap() += baseOffset.getVector3fMap(); } auto inside_point_generator = [this, &baseOffset] () { - pcl::PointXYZ p(rd_(gen_), rd_(gen_), rd_(gen_)); + pcl::PointXYZ p(rg_(), rg_(), rg_()); p.getVector3fMap() += baseOffset.getVector3fMap(); return p; }; auto outside_point_generator = [this, &baseOffset] () { std::array pt; - std::generate(pt.begin(), pt.end(), [this] {return rd_(gen_) + 2. * (getRandomBool() ? -1. : 1.);}); + std::generate(pt.begin(), pt.end(), + [this] { + float v = rg_(); + return v + std::copysign(0.51, v); + }); pcl::PointXYZ p(pt[0], pt[1], pt[2]); p.getVector3fMap() += baseOffset.getVector3fMap(); return p; @@ -151,8 +150,7 @@ class PCLCropHullTestFixture : public ::testing::Test return crop_hull_filter; } - mutable std::mt19937 gen_; - mutable std::uniform_real_distribution rd_; + RandomGeneratorType rg_; pcl::PointCloud baseOffsetList_; }; @@ -183,6 +181,23 @@ struct CropHullTestTraits3d }; +template struct RandomGenerator +{ + public: + RandomGenerator() + : gen_(seed), rd_(-0.5f, 0.5f) + {} + + float operator()() { + return rd_(gen_); + } + + private: + std::mt19937 gen_; + std::uniform_real_distribution rd_; +}; + + static std::vector> cube_elements = { {0, 2, 1}, // l {1, 2, 3}, // l @@ -204,8 +219,8 @@ CropHullTestTraits2d::getHullCloud () { static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); if (input_cloud->empty()) { - for (const float i: {0.f, 1.f}) - for (const float j: {0.f, 1.f}) + for (const float i: {-0.5f, 0.5f}) + for (const float j: {-0.5f, .5f}) for (const float k: {0.f, -0.1f}) input_cloud->emplace_back(i, j, k); } @@ -234,9 +249,9 @@ CropHullTestTraits3d::getHullCloud () { static pcl::PointCloud::Ptr input_cloud (new pcl::PointCloud); if (input_cloud->empty()) { - for (const float i: {0.f, 1.f}) - for (const float j: {0.f, 1.f}) - for (const float k: {0.f, 1.f}) + for (const float i: {-0.5f, 0.5f}) + for (const float j: {-0.5f, 0.5f}) + for (const float k: {-0.5f, 0.5f}) input_cloud->emplace_back(i, j, k); } return input_cloud; @@ -259,7 +274,24 @@ CropHullTestTraits3d::getDim () } } // end of anonymous namespace -using CropHullTestTypes = ::testing::Types; +using CropHullTestTraits2dList = std::tuple< + std::tuple>, + std::tuple>, + std::tuple> + >; +using CropHullTestTraits3dList = std::tuple< + std::tuple>, + std::tuple>, + std::tuple> + >; +using CropHullTestTypes = ::testing::Types< + std::tuple_element<0, CropHullTestTraits2dList>::type, + std::tuple_element<1, CropHullTestTraits2dList>::type, + std::tuple_element<2, CropHullTestTraits2dList>::type, + std::tuple_element<0, CropHullTestTraits3dList>::type, + std::tuple_element<1, CropHullTestTraits3dList>::type, + std::tuple_element<2, CropHullTestTraits3dList>::type + >; TYPED_TEST_SUITE(PCLCropHullTestFixture, CropHullTestTypes); @@ -305,8 +337,17 @@ TYPED_TEST (PCLCropHullTestFixture, test_cloud_filtering) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // this test will pass only for 2d case // -using PCLCropHullTestFixture2d = PCLCropHullTestFixture; -TEST_F (PCLCropHullTestFixture2d, test_crop_inside) +template +struct PCLCropHullTestFixture2dCrutch : PCLCropHullTestFixture +{}; +using CropHullTestTraits2dTypes = ::testing::Types< + std::tuple_element<0, CropHullTestTraits2dList>::type, + std::tuple_element<1, CropHullTestTraits2dList>::type, + std::tuple_element<2, CropHullTestTraits2dList>::type + >; +TYPED_TEST_SUITE(PCLCropHullTestFixture2dCrutch, CropHullTestTraits2dTypes); + +TYPED_TEST (PCLCropHullTestFixture2dCrutch, test_crop_inside) { for (auto & entry : this->data_) { From 803ce8ef970d78eb84e01f68af58205dc9f8db8f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 6 Feb 2021 17:29:41 +0100 Subject: [PATCH 010/123] Add pcl log stream macros PCL_INFO_STREAM, PCL_ERROR_STREAM, and more. Similar to ROS_INFO_STREAM etc --- common/include/pcl/console/print.h | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/common/include/pcl/console/print.h b/common/include/pcl/console/print.h index 59617714fe3..d4e94f31d98 100644 --- a/common/include/pcl/console/print.h +++ b/common/include/pcl/console/print.h @@ -43,6 +43,18 @@ #include #include +// Use e.g. like this: +// PCL_INFO_STREAM("Info: this is a point: " << pcl::PointXYZ(1.0, 2.0, 3.0) << std::endl); +// PCL_ERROR_STREAM("Error: an Eigen vector: " << std::endl << Eigen::Vector3f(1.0, 2.0, 3.0) << std::endl); +#define PCL_LOG_STREAM(LEVEL, STREAM, CSTR, ATTR, FG, ARGS) if(pcl::console::isVerbosityLevelEnabled(pcl::console::LEVEL)) { fflush(stdout); pcl::console::change_text_color(CSTR, pcl::console::ATTR, pcl::console::FG); STREAM << ARGS; pcl::console::reset_text_color(CSTR); } +#define PCL_ALWAYS_STREAM(ARGS) PCL_LOG_STREAM(L_ALWAYS, std::cout, stdout, TT_RESET, TT_WHITE, ARGS) +#define PCL_ERROR_STREAM(ARGS) PCL_LOG_STREAM(L_ERROR, std::cerr, stderr, TT_BRIGHT, TT_RED, ARGS) +#define PCL_WARN_STREAM(ARGS) PCL_LOG_STREAM(L_WARN, std::cerr, stderr, TT_BRIGHT, TT_YELLOW, ARGS) +#define PCL_INFO_STREAM(ARGS) PCL_LOG_STREAM(L_INFO, std::cout, stdout, TT_RESET, TT_WHITE, ARGS) +#define PCL_DEBUG_STREAM(ARGS) PCL_LOG_STREAM(L_DEBUG, std::cout, stdout, TT_RESET, TT_GREEN, ARGS) +#define PCL_VERBOSE_STREAM(ARGS) PCL_LOG_STREAM(L_VERBOSE, std::cout, stdout, TT_RESET, TT_WHITE, ARGS) + + #define PCL_ALWAYS(...) pcl::console::print (pcl::console::L_ALWAYS, __VA_ARGS__) #define PCL_ERROR(...) pcl::console::print (pcl::console::L_ERROR, __VA_ARGS__) #define PCL_WARN(...) pcl::console::print (pcl::console::L_WARN, __VA_ARGS__) From 2225fab79bac23d2c1ecfb65b3f30e96fbb86153 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 10 Mar 2021 15:45:23 +0100 Subject: [PATCH 011/123] Improve test_octree_compression - Add additional test that encodes+decodes the same cloud multiple times - Add pcd file as argument so that test OctreeDeCompressionFile actually runs - Run tests for smaller clouds (MAX_XYZ=1.0) in addition to the larger clouds (MAX_XYZ=1024.0) - Make tests stricter: require exact dimensions unless voxel grid downsampling is enabled - Improve some formatting --- test/io/CMakeLists.txt | 3 +- test/io/test_octree_compression.cpp | 246 ++++++++++++++++++---------- 2 files changed, 164 insertions(+), 85 deletions(-) diff --git a/test/io/CMakeLists.txt b/test/io/CMakeLists.txt index 4443fb9b649..303ce71159a 100644 --- a/test/io/CMakeLists.txt +++ b/test/io/CMakeLists.txt @@ -52,4 +52,5 @@ PCL_ADD_TEST(buffers test_buffers PCL_ADD_TEST(io_octree_compression test_octree_compression FILES test_octree_compression.cpp - LINK_WITH pcl_gtest pcl_common pcl_io pcl_octree) + LINK_WITH pcl_gtest pcl_common pcl_io pcl_octree + ARGUMENTS "${PCL_SOURCE_DIR}/test/milk_color.pcd") diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 3eb4beb633b..73d0736ff84 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -48,102 +48,182 @@ int total_runs = 0; char* pcd_file; #define MAX_POINTS 10000.0 -#define MAX_XYZ 1024.0 #define MAX_COLOR 255 -#define NUMBER_OF_TEST_RUNS 2 +#define NUMBER_OF_TEST_RUNS 3 TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) { srand(static_cast (time(NULL))); + for (const double MAX_XYZ : {1.0, 1024.0}) { // Small clouds, large clouds + // iterate over all pre-defined compression profiles + for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; + compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { + // instantiate point cloud compression encoder/decoder + pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression pointcloud_decoder; + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); + // iterate over runs + for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) + { + try + { + int point_count; + do { // empty point cloud hangs decoder + point_count = MAX_POINTS * rand() / RAND_MAX; + } while (point_count < 1); + // create shared pointcloud instances + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + // assign input point clouds to octree + // create random point cloud + for (int point = 0; point < point_count; point++) + { + // generate a random point + pcl::PointXYZRGBA new_point; + new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), + new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); + // OctreePointCloudPointVector can store all points.. + cloud->push_back(new_point); + } + EXPECT_EQ(cloud->height, 1); + +// std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; + std::stringstream compressed_data; + pointcloud_encoder.encodePointCloud(cloud, compressed_data); + pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; + } + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; + } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; + } + catch (std::exception& e) + { + std::cout << e.what() << std::endl; + } + } // runs + } // compression profiles + } // small clouds, large clouds +} // TEST +TEST (PCL, OctreeDeCompressionRandomPointXYZ) +{ + srand(static_cast (time(NULL))); + for (const double MAX_XYZ : {1.0, 1024.0}) { // Small clouds, large clouds // iterate over all pre-defined compression profiles - for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; - compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { - // instantiate point cloud compression encoder/decoder - pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); - pcl::io::OctreePointCloudCompression pointcloud_decoder; - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); - // iterate over runs - for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) + for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; + compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { - try + // instantiate point cloud compression encoder/decoder + pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression pointcloud_decoder; + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); + // loop over runs + for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - int point_count = MAX_POINTS * rand() / RAND_MAX; - if (point_count < 1) - { // empty point cloud hangs decoder - total_runs--; - continue; - } + int point_count; + do { // empty point cloud hangs decoder + point_count = MAX_POINTS * rand() / RAND_MAX; + } while (point_count < 1); // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); // assign input point clouds to octree // create random point cloud for (int point = 0; point < point_count; point++) { - // gereate a random point - pcl::PointXYZRGBA new_point; - new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), - new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); - // OctreePointCloudPointVector can store all points.. + // generate a random point + pcl::PointXYZ new_point(static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX)); cloud->push_back(new_point); } - -// std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; + EXPECT_EQ(cloud->height, 1); + // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; std::stringstream compressed_data; - pointcloud_encoder.encodePointCloud(cloud, compressed_data); - pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - EXPECT_GT((int)cloud_out->width, 0) << "decoded PointCloud width <= 0"; - EXPECT_GT((int)cloud_out->height, 0) << " decoded PointCloud height <= 0 "; - } - catch (std::exception& e) - { - std::cout << e.what() << std::endl; - } - } // runs - } // compression profiles + try + { // decodePointCloud() throws exceptions on errors + pointcloud_encoder.encodePointCloud(cloud, compressed_data); + pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; + } + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; + } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; + } + catch (std::exception& e) + { + std::cout << e.what() << std::endl; + } + } // runs + } // compression profiles + } // small clouds, large clouds } // TEST -TEST (PCL, OctreeDeCompressionRandomPointXYZ) +TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) { + // Generate a random cloud. Put it into the encoder several times and make + // sure that the decoded cloud has correct width and height each time. + const double MAX_XYZ = 1.0; srand(static_cast (time(NULL))); - // iterate over all pre-defined compression profiles for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; - compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) - { + compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { // instantiate point cloud compression encoder/decoder - pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); - pcl::io::OctreePointCloudCompression pointcloud_decoder; - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); - // loop over runs + pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression pointcloud_decoder; + + int point_count; + do { // empty point cloud hangs decoder + point_count = MAX_POINTS * rand() / RAND_MAX; + } while (point_count < 1); + // create shared pointcloud instances + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + // assign input point clouds to octree + // create random point cloud + for (int point = 0; point < point_count; point++) + { + // generate a random point + pcl::PointXYZRGBA new_point; + new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), + new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); + // OctreePointCloudPointVector can store all points.. + cloud->push_back(new_point); + } + EXPECT_EQ(cloud->height, 1); + + // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - int point_count = MAX_POINTS * rand() / RAND_MAX; - // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - // assign input point clouds to octree - // create random point cloud - for (int point = 0; point < point_count; point++) - { - // generate a random point - pcl::PointXYZ new_point(static_cast (MAX_XYZ * rand() / RAND_MAX), - static_cast (MAX_XYZ * rand() / RAND_MAX), - static_cast (MAX_XYZ * rand() / RAND_MAX)); - cloud->push_back(new_point); - } -// std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; - std::stringstream compressed_data; try - { // decodePointCloud() throws exceptions on errors + { +// std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; + std::stringstream compressed_data; + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); pointcloud_encoder.encodePointCloud(cloud, compressed_data); pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - EXPECT_GT((int)cloud_out->width, 0) << "decoded PointCloud width <= 0"; - EXPECT_GT((int)cloud_out->height, 0) << " decoded PointCloud height <= 0 "; + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; + } + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; + } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; } catch (std::exception& e) { @@ -159,36 +239,34 @@ TEST(PCL, OctreeDeCompressionFile) // load point cloud from file, when present if (pcd_file == NULL) return; - int rv = pcl::io::loadPCDFile(pcd_file, *input_cloud_ptr); - float voxel_sizes[] = { 0.1, 0.01 }; + int rv = pcl::io::loadPCDFile(pcd_file, *input_cloud_ptr); + float voxel_sizes[] = { 0.1, 0.01 }; - EXPECT_EQ(rv, 0) << " loadPCDFile " << pcd_file; - EXPECT_GT((int) input_cloud_ptr->width , 0) << "invalid point cloud width from " << pcd_file; - EXPECT_GT((int) input_cloud_ptr->height, 0) << "invalid point cloud height from " << pcd_file; + EXPECT_EQ(rv, 0) << " loadPCDFile " << pcd_file; + EXPECT_GT(input_cloud_ptr->width , 0) << "invalid point cloud width from " << pcd_file; + EXPECT_GT(input_cloud_ptr->height, 0) << "invalid point cloud height from " << pcd_file; - // iterate over compression profiles - for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; - compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { + // iterate over compression profiles + for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; + compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { // instantiate point cloud compression encoder/decoder - pcl::io::OctreePointCloudCompression* PointCloudEncoder = new pcl::io::OctreePointCloudCompression((pcl::io::compression_Profiles_e) compression_profile, false); - pcl::io::OctreePointCloudCompression* PointCloudDecoder = new pcl::io::OctreePointCloudCompression(); + pcl::io::OctreePointCloudCompression PointCloudEncoder((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression PointCloudDecoder; // iterate over various voxel sizes for (std::size_t i = 0; i < sizeof(voxel_sizes)/sizeof(voxel_sizes[0]); i++) { pcl::octree::OctreePointCloud octree(voxel_sizes[i]); - pcl::PointCloud::Ptr octree_out(new pcl::PointCloud()); + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); octree.setInputCloud((*input_cloud_ptr).makeShared()); octree.addPointsFromInputCloud(); std::stringstream compressedData; - PointCloudEncoder->encodePointCloud(octree.getInputCloud(), compressedData); - PointCloudDecoder->decodePointCloud(compressedData, octree_out); - EXPECT_GT((int)octree_out->width, 0) << "decoded PointCloud width <= 0"; - EXPECT_GT((int)octree_out->height, 0) << " decoded PointCloud height <= 0 "; + PointCloudEncoder.encodePointCloud(octree.getInputCloud(), compressedData); + PointCloudDecoder.decodePointCloud(compressedData, cloud_out); + EXPECT_GT(cloud_out->width, 0) << "decoded PointCloud width <= 0"; + EXPECT_GT(cloud_out->height, 0) << " decoded PointCloud height <= 0 "; total_runs++; } - delete PointCloudDecoder; - delete PointCloudEncoder; } } From 793d190afd443c81c0a9b384c425a6ed83d2a618 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 12 Mar 2021 17:05:19 +0100 Subject: [PATCH 012/123] OctreePointCloudCompression: delete unused class member --- io/include/pcl/compression/octree_pointcloud_compression.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/io/include/pcl/compression/octree_pointcloud_compression.h b/io/include/pcl/compression/octree_pointcloud_compression.h index d251d35e7b6..8548daac363 100644 --- a/io/include/pcl/compression/octree_pointcloud_compression.h +++ b/io/include/pcl/compression/octree_pointcloud_compression.h @@ -252,9 +252,6 @@ namespace pcl /** \brief Vector for storing binary tree structure */ std::vector binary_tree_data_vector_; - /** \brief Iterator on binary tree structure vector */ - std::vector binary_color_tree_vector_; - /** \brief Vector for storing points per voxel information */ std::vector point_count_data_vector_; From 72b9a9bcc5a0fe8a763a00e61e4c8d9713bcd37a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 12 Mar 2021 17:06:45 +0100 Subject: [PATCH 013/123] Octree2BufBase: compute bit pattern only when needed --- .../pcl/octree/impl/octree2buf_base.hpp | 22 ++++++++----------- 1 file changed, 9 insertions(+), 13 deletions(-) diff --git a/octree/include/pcl/octree/impl/octree2buf_base.hpp b/octree/include/pcl/octree/impl/octree2buf_base.hpp index edaea812171..e1d46260b0c 100644 --- a/octree/include/pcl/octree/impl/octree2buf_base.hpp +++ b/octree/include/pcl/octree/impl/octree2buf_base.hpp @@ -559,21 +559,17 @@ Octree2BufBase::serializeTreeRecursive( bool do_XOR_encoding_arg, bool new_leafs_filter_arg) { - // bit pattern - char branch_bit_pattern_curr_buffer; - char branch_bit_pattern_prev_buffer; - char node_XOR_bit_pattern; - - // occupancy bit patterns of branch node (current and previous octree buffer) - branch_bit_pattern_curr_buffer = getBranchBitPattern(*branch_arg, buffer_selector_); - branch_bit_pattern_prev_buffer = getBranchBitPattern(*branch_arg, !buffer_selector_); - - // XOR of current and previous occupancy bit patterns - node_XOR_bit_pattern = - branch_bit_pattern_curr_buffer ^ branch_bit_pattern_prev_buffer; - if (binary_tree_out_arg) { + // occupancy bit patterns of branch node (current octree buffer) + const char branch_bit_pattern_curr_buffer = + getBranchBitPattern(*branch_arg, buffer_selector_); if (do_XOR_encoding_arg) { + // occupancy bit patterns of branch node (previous octree buffer) + const char branch_bit_pattern_prev_buffer = + getBranchBitPattern(*branch_arg, !buffer_selector_); + // XOR of current and previous occupancy bit patterns + const char node_XOR_bit_pattern = + branch_bit_pattern_curr_buffer ^ branch_bit_pattern_prev_buffer; // write XOR bit pattern to output vector binary_tree_out_arg->push_back(node_XOR_bit_pattern); } From bcc9eccfb015462dc0dc2d917988f68deb33ce92 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 12 Mar 2021 17:07:08 +0100 Subject: [PATCH 014/123] Octree2BufBase: clear leaf contents when copying from previous buffer The createLeafRecursive function reuses leaf nodes from the previous buffer if possible. Before this commit, the contents of the leaf were not cleared, so if the leaf e.g. contains point indices, they are practically copied from the previous to the current octree. --- octree/include/pcl/octree/impl/octree2buf_base.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/octree/include/pcl/octree/impl/octree2buf_base.hpp b/octree/include/pcl/octree/impl/octree2buf_base.hpp index e1d46260b0c..61f7f70f2d0 100644 --- a/octree/include/pcl/octree/impl/octree2buf_base.hpp +++ b/octree/include/pcl/octree/impl/octree2buf_base.hpp @@ -431,6 +431,7 @@ Octree2BufBase::createLeafRecursive( OctreeNode* child_node = branch_arg->getChildPtr(!buffer_selector_, child_idx); if (child_node->getNodeType() == LEAF_NODE) { child_leaf = static_cast(child_node); + child_leaf->getContainer() = LeafContainer(); // Clear contents of leaf branch_arg->setChildPtr(buffer_selector_, child_idx, child_node); } else { From 6ddb59d1e15f0e5d664880a4b97a5b078e993d1f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 13 Mar 2021 11:09:34 +0100 Subject: [PATCH 015/123] Add deprecation for incorrectly installed headers - Problem: some headers are currently installed twice - Add deprecation/redirection headers - Install these headers instead of one set of the "full" headers (so deprecation headers+full headers instead of full headers twice) - If user includes the wrong header (wrong path), it still works, but they get the deprecation notice --- recognition/CMakeLists.txt | 32 +++++++++---------- .../include/pcl/recognition/auxiliary.h | 2 ++ recognition/include/pcl/recognition/bvh.h | 2 ++ .../include/pcl/recognition/hypothesis.h | 2 ++ .../pcl/recognition/impl/line_rgbd.hpp | 2 ++ .../pcl/recognition/impl/simple_octree.hpp | 2 ++ .../pcl/recognition/impl/voxel_structure.hpp | 2 ++ .../include/pcl/recognition/line_rgbd.h | 2 ++ .../include/pcl/recognition/model_library.h | 2 ++ .../include/pcl/recognition/obj_rec_ransac.h | 2 ++ .../include/pcl/recognition/orr_graph.h | 2 ++ .../include/pcl/recognition/orr_octree.h | 2 ++ .../pcl/recognition/orr_octree_zprojection.h | 2 ++ .../pcl/recognition/rigid_transform_space.h | 2 ++ .../include/pcl/recognition/simple_octree.h | 2 ++ .../include/pcl/recognition/trimmed_icp.h | 2 ++ .../include/pcl/recognition/voxel_structure.h | 2 ++ 17 files changed, 48 insertions(+), 16 deletions(-) create mode 100644 recognition/include/pcl/recognition/auxiliary.h create mode 100644 recognition/include/pcl/recognition/bvh.h create mode 100644 recognition/include/pcl/recognition/hypothesis.h create mode 100644 recognition/include/pcl/recognition/impl/line_rgbd.hpp create mode 100644 recognition/include/pcl/recognition/impl/simple_octree.hpp create mode 100644 recognition/include/pcl/recognition/impl/voxel_structure.hpp create mode 100644 recognition/include/pcl/recognition/line_rgbd.h create mode 100644 recognition/include/pcl/recognition/model_library.h create mode 100644 recognition/include/pcl/recognition/obj_rec_ransac.h create mode 100644 recognition/include/pcl/recognition/orr_graph.h create mode 100644 recognition/include/pcl/recognition/orr_octree.h create mode 100644 recognition/include/pcl/recognition/orr_octree_zprojection.h create mode 100644 recognition/include/pcl/recognition/rigid_transform_space.h create mode 100644 recognition/include/pcl/recognition/simple_octree.h create mode 100644 recognition/include/pcl/recognition/trimmed_icp.h create mode 100644 recognition/include/pcl/recognition/voxel_structure.h diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 54d357e6f8d..7e9386e7cd9 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -38,20 +38,20 @@ set(incs "include/pcl/${SUBSYS_NAME}/dense_quantized_multi_mod_template.h" "include/pcl/${SUBSYS_NAME}/sparse_quantized_multi_mod_template.h" "include/pcl/${SUBSYS_NAME}/surface_normal_modality.h" - "include/pcl/${SUBSYS_NAME}/linemod/line_rgbd.h" + "include/pcl/${SUBSYS_NAME}/line_rgbd.h" "include/pcl/${SUBSYS_NAME}/implicit_shape_model.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/auxiliary.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/hypothesis.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/model_library.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/rigid_transform_space.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/obj_rec_ransac.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/orr_graph.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/orr_octree_zprojection.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/trimmed_icp.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/orr_octree.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/simple_octree.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/voxel_structure.h" - "include/pcl/${SUBSYS_NAME}/ransac_based/bvh.h" + "include/pcl/${SUBSYS_NAME}/auxiliary.h" + "include/pcl/${SUBSYS_NAME}/hypothesis.h" + "include/pcl/${SUBSYS_NAME}/model_library.h" + "include/pcl/${SUBSYS_NAME}/rigid_transform_space.h" + "include/pcl/${SUBSYS_NAME}/obj_rec_ransac.h" + "include/pcl/${SUBSYS_NAME}/orr_graph.h" + "include/pcl/${SUBSYS_NAME}/orr_octree_zprojection.h" + "include/pcl/${SUBSYS_NAME}/trimmed_icp.h" + "include/pcl/${SUBSYS_NAME}/orr_octree.h" + "include/pcl/${SUBSYS_NAME}/simple_octree.h" + "include/pcl/${SUBSYS_NAME}/voxel_structure.h" + "include/pcl/${SUBSYS_NAME}/bvh.h" ) set(ransac_based_incs @@ -91,9 +91,9 @@ set(cg_incs ) set(impl_incs - "include/pcl/${SUBSYS_NAME}/impl/linemod/line_rgbd.hpp" - "include/pcl/${SUBSYS_NAME}/impl/ransac_based/simple_octree.hpp" - "include/pcl/${SUBSYS_NAME}/impl/ransac_based/voxel_structure.hpp" + "include/pcl/${SUBSYS_NAME}/impl/line_rgbd.hpp" + "include/pcl/${SUBSYS_NAME}/impl/simple_octree.hpp" + "include/pcl/${SUBSYS_NAME}/impl/voxel_structure.hpp" "include/pcl/${SUBSYS_NAME}/impl/implicit_shape_model.hpp" ) diff --git a/recognition/include/pcl/recognition/auxiliary.h b/recognition/include/pcl/recognition/auxiliary.h new file mode 100644 index 00000000000..0e364add08e --- /dev/null +++ b/recognition/include/pcl/recognition/auxiliary.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/bvh.h b/recognition/include/pcl/recognition/bvh.h new file mode 100644 index 00000000000..12374a202c6 --- /dev/null +++ b/recognition/include/pcl/recognition/bvh.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/hypothesis.h b/recognition/include/pcl/recognition/hypothesis.h new file mode 100644 index 00000000000..ad8f5b642df --- /dev/null +++ b/recognition/include/pcl/recognition/hypothesis.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/impl/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/line_rgbd.hpp new file mode 100644 index 00000000000..53d67119496 --- /dev/null +++ b/recognition/include/pcl/recognition/impl/line_rgbd.hpp @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/impl/simple_octree.hpp b/recognition/include/pcl/recognition/impl/simple_octree.hpp new file mode 100644 index 00000000000..0c8c0ccb3d0 --- /dev/null +++ b/recognition/include/pcl/recognition/impl/simple_octree.hpp @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/impl/voxel_structure.hpp b/recognition/include/pcl/recognition/impl/voxel_structure.hpp new file mode 100644 index 00000000000..44697e8e358 --- /dev/null +++ b/recognition/include/pcl/recognition/impl/voxel_structure.hpp @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/line_rgbd.h b/recognition/include/pcl/recognition/line_rgbd.h new file mode 100644 index 00000000000..5d526ad3984 --- /dev/null +++ b/recognition/include/pcl/recognition/line_rgbd.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/model_library.h b/recognition/include/pcl/recognition/model_library.h new file mode 100644 index 00000000000..4b4ee3345bd --- /dev/null +++ b/recognition/include/pcl/recognition/model_library.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/obj_rec_ransac.h b/recognition/include/pcl/recognition/obj_rec_ransac.h new file mode 100644 index 00000000000..52b96362eb5 --- /dev/null +++ b/recognition/include/pcl/recognition/obj_rec_ransac.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/orr_graph.h b/recognition/include/pcl/recognition/orr_graph.h new file mode 100644 index 00000000000..a43e35c9558 --- /dev/null +++ b/recognition/include/pcl/recognition/orr_graph.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/orr_octree.h b/recognition/include/pcl/recognition/orr_octree.h new file mode 100644 index 00000000000..b0f43fc2f27 --- /dev/null +++ b/recognition/include/pcl/recognition/orr_octree.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/orr_octree_zprojection.h b/recognition/include/pcl/recognition/orr_octree_zprojection.h new file mode 100644 index 00000000000..536f8a53f49 --- /dev/null +++ b/recognition/include/pcl/recognition/orr_octree_zprojection.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/rigid_transform_space.h b/recognition/include/pcl/recognition/rigid_transform_space.h new file mode 100644 index 00000000000..2cc30436bad --- /dev/null +++ b/recognition/include/pcl/recognition/rigid_transform_space.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/simple_octree.h b/recognition/include/pcl/recognition/simple_octree.h new file mode 100644 index 00000000000..aa47e0d885d --- /dev/null +++ b/recognition/include/pcl/recognition/simple_octree.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/trimmed_icp.h b/recognition/include/pcl/recognition/trimmed_icp.h new file mode 100644 index 00000000000..cabf17ba777 --- /dev/null +++ b/recognition/include/pcl/recognition/trimmed_icp.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/voxel_structure.h b/recognition/include/pcl/recognition/voxel_structure.h new file mode 100644 index 00000000000..a78e541ca7d --- /dev/null +++ b/recognition/include/pcl/recognition/voxel_structure.h @@ -0,0 +1,2 @@ +#include +PCL_DEPRECATED_HEADER(1, 15, "Please use instead") From ca6fdd10b0213d6f8223bec378c128014db189b3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 20 Mar 2021 20:04:11 +0100 Subject: [PATCH 016/123] Remove try-catch in test_octree_compression --- test/io/test_octree_compression.cpp | 119 ++++++++++++---------------- 1 file changed, 49 insertions(+), 70 deletions(-) diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 73d0736ff84..ca65c61dd22 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -65,49 +65,42 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - try + int point_count; + do { // empty point cloud hangs decoder + point_count = MAX_POINTS * rand() / RAND_MAX; + } while (point_count < 1); + // create shared pointcloud instances + pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + // assign input point clouds to octree + // create random point cloud + for (int point = 0; point < point_count; point++) { - int point_count; - do { // empty point cloud hangs decoder - point_count = MAX_POINTS * rand() / RAND_MAX; - } while (point_count < 1); - // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - // assign input point clouds to octree - // create random point cloud - for (int point = 0; point < point_count; point++) - { - // generate a random point - pcl::PointXYZRGBA new_point; - new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), - new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); - // OctreePointCloudPointVector can store all points.. - cloud->push_back(new_point); - } - EXPECT_EQ(cloud->height, 1); + // generate a random point + pcl::PointXYZRGBA new_point; + new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), + new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); + new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); + new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); + // OctreePointCloudPointVector can store all points.. + cloud->push_back(new_point); + } + EXPECT_EQ(cloud->height, 1); // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; - std::stringstream compressed_data; - pointcloud_encoder.encodePointCloud(cloud, compressed_data); - pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { - EXPECT_GT(cloud_out->width, 0); - EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; - } - else { - EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; - } - EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; + std::stringstream compressed_data; + pointcloud_encoder.encodePointCloud(cloud, compressed_data); + pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; } - catch (std::exception& e) - { - std::cout << e.what() << std::endl; + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; } // runs } // compression profiles } // small clouds, large clouds @@ -147,23 +140,16 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZ) EXPECT_EQ(cloud->height, 1); // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; std::stringstream compressed_data; - try - { // decodePointCloud() throws exceptions on errors - pointcloud_encoder.encodePointCloud(cloud, compressed_data); - pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { - EXPECT_GT(cloud_out->width, 0); - EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; - } - else { - EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; - } - EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; + pointcloud_encoder.encodePointCloud(cloud, compressed_data); + pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; } - catch (std::exception& e) - { - std::cout << e.what() << std::endl; + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; } // runs } // compression profiles } // small clouds, large clouds @@ -209,26 +195,19 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - try - { // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; - std::stringstream compressed_data; - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); - pointcloud_encoder.encodePointCloud(cloud, compressed_data); - pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { - EXPECT_GT(cloud_out->width, 0); - EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; - } - else { - EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; - } - EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; + std::stringstream compressed_data; + pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); + pointcloud_encoder.encodePointCloud(cloud, compressed_data); + pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); + if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { + EXPECT_GT(cloud_out->width, 0); + EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; } - catch (std::exception& e) - { - std::cout << e.what() << std::endl; + else { + EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; } + EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; } // runs } // compression profiles } // TEST From 2932286548b2e79f7b2ec0fcbf78f25de6df9ed3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 18 Mar 2021 15:15:23 +0100 Subject: [PATCH 017/123] Tracking: pyramidal klt: switch keypoints_status_ from PointIndices to int vector It has nothing to do with indices, the elements of the vector are not and should not be used as indices. Furthermore, the status can be negative (-1, -2). This commit also deprecates a getter-function with a PointIndices return type and adds a replacement. --- apps/src/openni_klt.cpp | 6 +++--- .../pcl/tracking/impl/pyramidal_klt.hpp | 6 +++--- tracking/include/pcl/tracking/pyramidal_klt.h | 18 +++++++++++++++++- 3 files changed, 23 insertions(+), 7 deletions(-) diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index ff17a983fe8..e0adcdcb551 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -251,14 +251,14 @@ class OpenNIViewer { if (tracker_->getInitialized() && cloud_) { if (points_mutex_.try_lock()) { keypoints_ = tracker_->getTrackedPoints(); - points_status_ = tracker_->getPointsToTrackStatus(); + points_status_ = tracker_->getStatusOfPointsToTrack(); points_mutex_.unlock(); } std::vector markers; markers.reserve(keypoints_->size() * 2); for (std::size_t i = 0; i < keypoints_->size(); ++i) { - if (points_status_->indices[i] < 0) + if ((*points_status_)[i] < 0) continue; const pcl::PointUV& uv = (*keypoints_)[i]; markers.push_back(uv.u); @@ -295,7 +295,7 @@ class OpenNIViewer { typename pcl::tracking::PyramidalKLTTracker::Ptr tracker_; pcl::PointCloud::ConstPtr keypoints_; pcl::PointIndicesConstPtr points_; - pcl::PointIndicesConstPtr points_status_; + pcl::shared_ptr> points_status_; int counter_; }; diff --git a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp index dc9bd1474dc..ebee0a184e4 100644 --- a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp +++ b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp @@ -69,8 +69,8 @@ PyramidalKLTTracker::setPointsToTrack( keypoints_ = p; } - keypoints_status_.reset(new pcl::PointIndices); - keypoints_status_->indices.resize(keypoints_->size(), 0); + keypoints_status_.reset(new std::vector); + keypoints_status_->resize(keypoints_->size(), 0); } /////////////////////////////////////////////////////////////////////////////////////////////// @@ -723,7 +723,7 @@ PyramidalKLTTracker::computeTracking() ref_ = input_; ref_pyramid_ = pyramid; keypoints_ = keypoints; - keypoints_status_->indices = status; + *keypoints_status_ = status; } } // namespace tracking diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index bdc0e812835..6f8436163e3 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -260,8 +260,24 @@ class PyramidalKLTTracker : public Tracker { * Status == -1 --> point is out of bond; * Status == -2 --> optical flow can not be computed for this point. */ + PCL_DEPRECATED(1, 15, "use getStatusOfPointsToTrack instead") inline pcl::PointIndicesConstPtr getPointsToTrackStatus() const + { + pcl::PointIndicesPtr res(new pcl::PointIndices); + res->indices.insert( + res->indices.end(), keypoints_status_->begin(), keypoints_status_->end()); + return (res); + } + + /** \return the status of points to track. + * Status == 0 --> points successfully tracked; + * Status < 0 --> point is lost; + * Status == -1 --> point is out of bond; + * Status == -2 --> optical flow can not be computed for this point. + */ + inline pcl::shared_ptr> + getStatusOfPointsToTrack() const { return (keypoints_status_); } @@ -398,7 +414,7 @@ class PyramidalKLTTracker : public Tracker { /** \brief detected keypoints 2D coordinates */ pcl::PointCloud::ConstPtr keypoints_; /** \brief status of keypoints of t-1 at t */ - pcl::PointIndicesPtr keypoints_status_; + pcl::shared_ptr> keypoints_status_; /** \brief number of points to detect */ std::size_t keypoints_nbr_; /** \brief tracking width */ From eda5305d2c749f0d655745ac45dc9cc1eeb851a3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 26 Mar 2021 17:22:28 +0100 Subject: [PATCH 018/123] Improve documentation, fix warnings Fix doxygen warnings such as: - Illegal command @param as part of a \a command - The following parameter [...] is not documented Fix rst warnings such as: - duplicate label - duplicate citation - malformed table - could not lex literal_block as "cmake" --- common/include/pcl/common/common.h | 1 + common/include/pcl/point_cloud.h | 4 ++++ doc/advanced/content/c_cache.rst | 8 ++++---- doc/tutorials/content/function_filter.rst | 4 ++-- doc/tutorials/content/how_features_work.rst | 8 ++++---- .../content/random_sample_consensus.rst | 6 +++--- gpu/octree/include/pcl/gpu/octree/octree.hpp | 2 +- ...spondence_estimation_organized_projection.h | 14 ++++++++++---- registration/include/pcl/registration/gicp.h | 13 +++++++------ .../registration/transformation_estimation.h | 4 ++-- .../transformation_estimation_2D.h | 13 +++++++------ .../transformation_estimation_3point.h | 4 ++-- .../transformation_estimation_dq.h | 14 ++++++++------ ...transformation_estimation_dual_quaternion.h | 14 ++++++++------ .../transformation_estimation_lm.h | 14 ++++++++------ ...nsformation_estimation_point_to_plane_lls.h | 14 ++++++++------ ...on_estimation_point_to_plane_lls_weighted.h | 14 ++++++++------ ...mation_estimation_point_to_plane_weighted.h | 17 ++++++++++------- .../transformation_estimation_svd.h | 14 ++++++++------ ...n_estimation_symmetric_point_to_plane_lls.h | 14 ++++++++------ .../segmentation/extract_labeled_clusters.h | 18 +++++++++++------- 21 files changed, 124 insertions(+), 90 deletions(-) diff --git a/common/include/pcl/common/common.h b/common/include/pcl/common/common.h index 97a41df5a95..f21f096881d 100644 --- a/common/include/pcl/common/common.h +++ b/common/include/pcl/common/common.h @@ -60,6 +60,7 @@ namespace pcl /** \brief Compute the smallest angle between two 3D vectors in radians (default) or degree. * \param v1 the first 3D vector (represented as a \a Eigen::Vector4f) * \param v2 the second 3D vector (represented as a \a Eigen::Vector4f) + * \param in_degree determine if angle should be in radians or degrees * \return the angle between v1 and v2 in radians or degrees * \note Handles rounding error for parallel and anti-parallel vectors * \ingroup common diff --git a/common/include/pcl/point_cloud.h b/common/include/pcl/point_cloud.h index 11d856f0eec..4a6cad3315a 100644 --- a/common/include/pcl/point_cloud.h +++ b/common/include/pcl/point_cloud.h @@ -536,6 +536,7 @@ namespace pcl * \note This breaks the organized structure of the cloud by setting the height to * 1! * \param[in] count new size of the point cloud + * \param[in] value value each point of the cloud should have */ inline void assign(index_t count, const PointT& value) @@ -549,6 +550,7 @@ namespace pcl * \brief Replaces the points with `new_width * new_height` copies of `value` * \param[in] new_width new width of the point cloud * \param[in] new_height new height of the point cloud + * \param[in] value value each point of the cloud should have */ inline void assign(index_t new_width, index_t new_height, const PointT& value) @@ -580,6 +582,7 @@ namespace pcl * `*this` * \note This calculates the height based on size and width provided. This means * the assignment happens even if the size is not perfectly divisible by width + * \param[in] first, last the range from which the points are copied * \param[in] new_width new width of the point cloud */ template @@ -616,6 +619,7 @@ namespace pcl * \brief Replaces the points with the elements from the initializer list `ilist` * \note This calculates the height based on size and width provided. This means * the assignment happens even if the size is not perfectly divisible by width + * \param[in] ilist initializer list from which the points are copied * \param[in] new_width new width of the point cloud */ void diff --git a/doc/advanced/content/c_cache.rst b/doc/advanced/content/c_cache.rst index 21da47ba24d..8d2826cce37 100644 --- a/doc/advanced/content/c_cache.rst +++ b/doc/advanced/content/c_cache.rst @@ -35,14 +35,14 @@ Install ``colorgcc`` on an Ubuntu system with :: To enable colorgcc, perform the following steps: -.. code-block:: cmake +.. code-block:: shell cp /etc/colorgcc/colorgccrc $HOME/.colorgccrc * edit the $HOME/.colorgccrc file, search for the following lines: -.. code-block:: cmake +.. code-block:: text g++: /usr/bin/g++ gcc: /usr/bin/gcc @@ -54,7 +54,7 @@ To enable colorgcc, perform the following steps: and replace them with: -.. code-block:: cmake +.. code-block:: text g++: ccache /usr/bin/g++ gcc: ccache /usr/bin/gcc @@ -66,7 +66,7 @@ and replace them with: * create a $HOME/bin or $HOME/sbin directory, and create the following softlinks in it -.. code-block:: cmake +.. code-block:: shell ln -s /usr/bin/colorgcc c++ ln -s /usr/bin/colorgcc cc diff --git a/doc/tutorials/content/function_filter.rst b/doc/tutorials/content/function_filter.rst index f346934b477..59ed23355c2 100644 --- a/doc/tutorials/content/function_filter.rst +++ b/doc/tutorials/content/function_filter.rst @@ -1,4 +1,4 @@ -.. _conditional_removal: +.. _function_filter: Removing outliers using a custom non-destructive condition ---------------------------------------------------------- @@ -7,7 +7,7 @@ This document demonstrates how to use the FunctionFilter class to remove points and faster appraoch compared to ConditionalRemoval filter or a `custom Condition class `_. .. note:: -Advanced users can use the FunctorFilter class that can provide a small but measurable speedup when used with a `lambda `_. + Advanced users can use the FunctorFilter class that can provide a small but measurable speedup when used with a `lambda `_. The code -------- diff --git a/doc/tutorials/content/how_features_work.rst b/doc/tutorials/content/how_features_work.rst index 0989543ef35..8eef3a32d66 100644 --- a/doc/tutorials/content/how_features_work.rst +++ b/doc/tutorials/content/how_features_work.rst @@ -54,13 +54,13 @@ the table below for a reference on each of the terms used. +=============+================================================+ | Foo | a class named `Foo` | +-------------+------------------------------------------------+ -| FooPtr | a shared pointer to a class `Foo`, | +| FooPtr | a shared pointer to a class `Foo`, | | | | -| | e.g., `shared_ptr` | +| | e.g., `shared_ptr` | +-------------+------------------------------------------------+ -| FooConstPtr | a const shared pointer to a class `Foo`, | +| FooConstPtr | a const shared pointer to a class `Foo`, | | | | -| | e.g., `const shared_ptr` | +| | e.g., `const shared_ptr` | +-------------+------------------------------------------------+ How to pass the input diff --git a/doc/tutorials/content/random_sample_consensus.rst b/doc/tutorials/content/random_sample_consensus.rst index d627f8b2cd6..ed5dad498ae 100644 --- a/doc/tutorials/content/random_sample_consensus.rst +++ b/doc/tutorials/content/random_sample_consensus.rst @@ -10,7 +10,7 @@ Theoretical Primer The abbreviation of "RANdom SAmple Consensus" is RANSAC, and it is an iterative method that is used to estimate parameters of a mathematical model from a set of data containing outliers. This algorithm was published by Fischler and Bolles in 1981. The RANSAC algorithm assumes that all of the data we are looking at is comprised of both inliers and outliers. Inliers can be explained by a model with a particular set of parameter values, while outliers do not fit that model in any circumstance. Another necessary assumption is that a procedure which can optimally estimate the parameters of the chosen model from the data is available. -From [Wikipedia]_: +From [WikipediaRANSAC]_: *The input to the RANSAC algorithm is a set of observed data values, a parameterized model which can explain or be fitted to the observations, and some confidence parameters.* @@ -38,7 +38,7 @@ From [Wikipedia]_: :align: right :height: 200px -The pictures to the left and right (From [Wikipedia]_) show a simple application of the RANSAC algorithm on a 2-dimensional set of data. The image on our left is a visual representation of a data set containing both inliers and outliers. The image on our right shows all of the outliers in red, and shows inliers in blue. The blue line is the result of the work done by RANSAC. In this case the model that we are trying to fit to the data is a line, and it looks like it's a fairly good fit to our data. +The pictures to the left and right (From [WikipediaRANSAC]_) show a simple application of the RANSAC algorithm on a 2-dimensional set of data. The image on our left is a visual representation of a data set containing both inliers and outliers. The image on our right shows all of the outliers in red, and shows inliers in blue. The blue line is the result of the work done by RANSAC. In this case the model that we are trying to fit to the data is a line, and it looks like it's a fairly good fit to our data. The code -------- @@ -123,4 +123,4 @@ It will show you the result of applying RandomSampleConsensus to this data set w :align: center :height: 400px -.. [Wikipedia] http://en.wikipedia.org/wiki/RANSAC +.. [WikipediaRANSAC] http://en.wikipedia.org/wiki/RANSAC diff --git a/gpu/octree/include/pcl/gpu/octree/octree.hpp b/gpu/octree/include/pcl/gpu/octree/octree.hpp index 64cfb378839..a5e2c734f3a 100644 --- a/gpu/octree/include/pcl/gpu/octree/octree.hpp +++ b/gpu/octree/include/pcl/gpu/octree/octree.hpp @@ -150,7 +150,7 @@ namespace pcl /** \brief Batch approximate nearest search on GPU * \param[in] queries array of centers * \param[out] result array of results ( one index for each query ) - * \param[out] sqr_distances corresponding square distances to results from query point + * \param[out] sqr_distance corresponding square distances to results from query point */ void approxNearestSearch(const Queries& queries, NeighborIndices& result, ResultSqrDists& sqr_distance) const; diff --git a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h index 4f351fe1e49..97bf14ab188 100644 --- a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h +++ b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h @@ -187,15 +187,21 @@ class CorrespondenceEstimationOrganizedProjection } /** \brief Computes the correspondences, applying a maximum Euclidean distance - * threshold. \param correspondences \param[in] max_distance Euclidean distance - * threshold above which correspondences will be rejected + * threshold. + * \param[out] correspondences the found correspondences (index of query point, index + * of target point, distance) + * \param[in] max_distance Euclidean distance threshold above which correspondences + * will be rejected */ void determineCorrespondences(Correspondences& correspondences, double max_distance); /** \brief Computes the correspondences, applying a maximum Euclidean distance - * threshold. \param correspondences \param[in] max_distance Euclidean distance - * threshold above which correspondences will be rejected + * threshold. + * \param[out] correspondences the found correspondences (index of query and target + * point, distance) + * \param[in] max_distance Euclidean distance threshold above which correspondences + * will be rejected */ void determineReciprocalCorrespondences(Correspondences& correspondences, diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index d39c8d16892..c26688197c1 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -186,10 +186,11 @@ class GeneralizedIterativeClosestPoint /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using an iterative non-linear Levenberg-Marquardt approach. \param[in] * cloud_src the source point cloud dataset \param[in] indices_src the vector of - * indices describing the points of interest in \a cloud_src \param[in] cloud_tgt the - * target point cloud dataset \param[in] indices_tgt the vector of indices describing - * the correspondences of the interest points from \a indices_src \param[out] - * transformation_matrix the resultant transformation matrix + * indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing + * the correspondences of the interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ void estimateRigidTransformationBFGS(const PointCloudSource& cloud_src, @@ -275,7 +276,7 @@ class GeneralizedIterativeClosestPoint } /** \brief Set the minimal translation gradient threshold for early optimization stop - * \param[in] translation gradient threshold in meters + * \param[in] tolerance translation gradient threshold in meters */ void setTranslationGradientTolerance(double tolerance) @@ -293,7 +294,7 @@ class GeneralizedIterativeClosestPoint } /** \brief Set the minimal rotation gradient threshold for early optimization stop - * \param[in] rotation gradient threshold in radians + * \param[in] tolerance rotation gradient threshold in radians */ void setRotationGradientTolerance(double tolerance) diff --git a/registration/include/pcl/registration/transformation_estimation.h b/registration/include/pcl/registration/transformation_estimation.h index c07ae01af85..d77c8931b34 100644 --- a/registration/include/pcl/registration/transformation_estimation.h +++ b/registration/include/pcl/registration/transformation_estimation.h @@ -93,8 +93,8 @@ class TransformationEstimation { * indices_src the vector of indices describing the points of interest in \a cloud_src * \param[in] cloud_tgt the target point cloud dataset * \param[in] indices_tgt the vector of indices describing the correspondences of the - * interest points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ virtual void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_2D.h b/registration/include/pcl/registration/transformation_estimation_2D.h index 6729f60be5c..6772f87298d 100644 --- a/registration/include/pcl/registration/transformation_estimation_2D.h +++ b/registration/include/pcl/registration/transformation_estimation_2D.h @@ -80,9 +80,9 @@ class TransformationEstimation2D /** \brief Estimate a rigid transformation between a source and a target point cloud * in 2D. \param[in] cloud_src the source point cloud dataset \param[in] indices_src - * the vector of indices describing the points of interest in \a cloud_src \param[in] - * cloud_tgt the target point cloud dataset \param[out] transformation_matrix the - * resultant transformation matrix + * the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -92,9 +92,10 @@ class TransformationEstimation2D /** \brief Estimate a rigid transformation between a source and a target point cloud * in 2D. \param[in] cloud_src the source point cloud dataset \param[in] indices_src - * the vector of indices describing the points of interest in \a cloud_src \param[in] - * cloud_tgt the target point cloud dataset \param[in] indices_tgt the vector of - * indices describing the correspondences of the interest points from \a indices_src + * the vector of indices describing the points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src * \param[out] transformation_matrix the resultant transformation matrix */ virtual void diff --git a/registration/include/pcl/registration/transformation_estimation_3point.h b/registration/include/pcl/registration/transformation_estimation_3point.h index 8ee7ab0aae9..2441fd93a8d 100644 --- a/registration/include/pcl/registration/transformation_estimation_3point.h +++ b/registration/include/pcl/registration/transformation_estimation_3point.h @@ -100,8 +100,8 @@ class TransformationEstimation3Point * indices_src the vector of indices describing the points of interest in \a cloud_src * \param[in] cloud_tgt the target point cloud dataset * \param[in] indices_tgt the vector of indices describing the correspondences of the - * interest points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_dq.h b/registration/include/pcl/registration/transformation_estimation_dq.h index 4c7512c0b62..955fcfa24a8 100644 --- a/registration/include/pcl/registration/transformation_estimation_dq.h +++ b/registration/include/pcl/registration/transformation_estimation_dq.h @@ -83,8 +83,9 @@ class TransformationEstimationDQ /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using dual quaternion optimization \param[in] cloud_src the source * point cloud dataset \param[in] indices_src the vector of indices describing the - * points of interest in \a cloud_src \param[in] cloud_tgt the target point cloud - * dataset \param[out] transformation_matrix the resultant transformation matrix + * points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -95,10 +96,11 @@ class TransformationEstimationDQ /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using dual quaternion optimization \param[in] cloud_src the source * point cloud dataset \param[in] indices_src the vector of indices describing the - * points of interest in \a cloud_src \param[in] cloud_tgt the target point cloud - * dataset \param[in] indices_tgt the vector of indices describing the correspondences - * of the interest points from \a indices_src \param[out] transformation_matrix the - * resultant transformation matrix + * points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h b/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h index e52937af88d..2b154120228 100644 --- a/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h +++ b/registration/include/pcl/registration/transformation_estimation_dual_quaternion.h @@ -80,8 +80,9 @@ class TransformationEstimationDualQuaternion /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using dual quaternion optimization \param[in] cloud_src the source * point cloud dataset \param[in] indices_src the vector of indices describing the - * points of interest in \a cloud_src \param[in] cloud_tgt the target point cloud - * dataset \param[out] transformation_matrix the resultant transformation matrix + * points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -92,10 +93,11 @@ class TransformationEstimationDualQuaternion /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using dual quaternion optimization \param[in] cloud_src the source * point cloud dataset \param[in] indices_src the vector of indices describing the - * points of interest in \a cloud_src \param[in] cloud_tgt the target point cloud - * dataset \param[in] indices_tgt the vector of indices describing the correspondences - * of the interest points from \a indices_src \param[out] transformation_matrix the - * resultant transformation matrix + * points of interest in \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_lm.h b/registration/include/pcl/registration/transformation_estimation_lm.h index 2680f6460bd..b2a0e185273 100644 --- a/registration/include/pcl/registration/transformation_estimation_lm.h +++ b/registration/include/pcl/registration/transformation_estimation_lm.h @@ -119,8 +119,9 @@ class TransformationEstimationLM /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using LM. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -131,10 +132,11 @@ class TransformationEstimationLM /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using LM. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h index c41ec430000..a1f6bdbd14f 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls.h @@ -87,8 +87,9 @@ class TransformationEstimationPointToPlaneLLS /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -99,10 +100,11 @@ class TransformationEstimationPointToPlaneLLS /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h index f04415b2caa..645b0d45cde 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_lls_weighted.h @@ -90,8 +90,9 @@ class TransformationEstimationPointToPlaneLLSWeighted /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -102,10 +103,11 @@ class TransformationEstimationPointToPlaneLLSWeighted /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h index 03a360736f7..4ebf6a9b33c 100644 --- a/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h +++ b/registration/include/pcl/registration/transformation_estimation_point_to_plane_weighted.h @@ -131,9 +131,10 @@ class TransformationEstimationPointToPlaneWeighted /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using LM. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix \note Uses the weights - * given by setWeights. + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -144,10 +145,12 @@ class TransformationEstimationPointToPlaneWeighted /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using LM. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix \note Uses the weights given by setWeights. + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix + * \note Uses the weights given by setWeights. */ void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index e6d003abef7..414c7bb2218 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -83,8 +83,9 @@ class TransformationEstimationSVD /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -95,10 +96,11 @@ class TransformationEstimationSVD /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/registration/include/pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h b/registration/include/pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h index 9bf47a8c894..076281e2e77 100644 --- a/registration/include/pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h +++ b/registration/include/pcl/registration/transformation_estimation_symmetric_point_to_plane_lls.h @@ -88,8 +88,9 @@ class TransformationEstimationSymmetricPointToPlaneLLS /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[out] - * transformation_matrix the resultant transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, @@ -100,10 +101,11 @@ class TransformationEstimationSymmetricPointToPlaneLLS /** \brief Estimate a rigid rotation transformation between a source and a target * point cloud using SVD. \param[in] cloud_src the source point cloud dataset * \param[in] indices_src the vector of indices describing the points of interest in - * \a cloud_src \param[in] cloud_tgt the target point cloud dataset \param[in] - * indices_tgt the vector of indices describing the correspondences of the interest - * points from \a indices_src \param[out] transformation_matrix the resultant - * transformation matrix + * \a cloud_src + * \param[in] cloud_tgt the target point cloud dataset + * \param[in] indices_tgt the vector of indices describing the correspondences of the + * interest points from \a indices_src + * \param[out] transformation_matrix the resultant transformation matrix */ inline void estimateRigidTransformation(const pcl::PointCloud& cloud_src, diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index cd9594b6cf4..d65beacad7d 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -68,14 +68,18 @@ void extractLabeledEuclideanClusters( unsigned int max_label); /** \brief Decompose a region of space into clusters based on the Euclidean distance - * between points \param[in] cloud the point cloud message \param[in] tree the spatial - * locator (e.g., kd-tree) used for nearest neighbors searching \note the tree has to be - * created as a spatial locator on \a cloud \param[in] tolerance the spatial cluster - * tolerance as a measure in L2 Euclidean space \param[out] labeled_clusters the - * resultant clusters containing point indices (as a vector of PointIndices) \param[in] - * min_pts_per_cluster minimum number of points that a cluster may contain (default: 1) + * between points + * \param[in] cloud the point cloud message + * \param[in] tree the spatial locator (e.g., kd-tree) used for nearest neighbors + * searching \note the tree has to be created as a spatial locator on \a cloud + * \param[in] tolerance the spatial cluster tolerance as a measure in L2 Euclidean space + * \param[out] labeled_clusters the resultant clusters containing point indices + * (as a vector of PointIndices) + * \param[in] min_pts_per_cluster minimum number of points that a cluster may contain + * (default: 1) * \param[in] max_pts_per_cluster maximum number of points that a cluster may contain - * (default: max int) \ingroup segmentation + * (default: max int) + * \ingroup segmentation */ template void From 9db86d4e2d832e9f6aee6fdf74c41422c6d8f7dd Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 28 Mar 2021 12:05:56 +0200 Subject: [PATCH 019/123] Better random point count generation --- test/io/test_octree_compression.cpp | 18 ++++++------------ 1 file changed, 6 insertions(+), 12 deletions(-) diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index ca65c61dd22..e71305300f0 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -65,10 +65,8 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - int point_count; - do { // empty point cloud hangs decoder - point_count = MAX_POINTS * rand() / RAND_MAX; - } while (point_count < 1); + // empty point cloud hangs decoder + const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; // create shared pointcloud instances pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); // assign input point clouds to octree @@ -121,10 +119,8 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZ) // loop over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - int point_count; - do { // empty point cloud hangs decoder - point_count = MAX_POINTS * rand() / RAND_MAX; - } while (point_count < 1); + // empty point cloud hangs decoder + const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; // create shared pointcloud instances pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); // assign input point clouds to octree @@ -168,10 +164,8 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); pcl::io::OctreePointCloudCompression pointcloud_decoder; - int point_count; - do { // empty point cloud hangs decoder - point_count = MAX_POINTS * rand() / RAND_MAX; - } while (point_count < 1); + // empty point cloud hangs decoder + const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; // create shared pointcloud instances pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); // assign input point clouds to octree From 7ca2d32e1d6630e821b939a323030fda13a146dd Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 2 Apr 2021 14:11:16 +0200 Subject: [PATCH 020/123] [CI] Add windows docker file (#4428) * Add windows docker build --- .ci/azure-pipelines/env.yml | 71 ++++++++++++++++++++--- .dev/docker/windows/Dockerfile | 47 +++++++++++++++ .dev/docker/windows/x64-windows-rel.cmake | 4 ++ .dev/docker/windows/x86-windows-rel.cmake | 4 ++ 4 files changed, 117 insertions(+), 9 deletions(-) create mode 100644 .dev/docker/windows/Dockerfile create mode 100644 .dev/docker/windows/x64-windows-rel.cmake create mode 100644 .dev/docker/windows/x86-windows-rel.cmake diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index 1fe345fa180..00ca0a80288 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -9,12 +9,14 @@ trigger: paths: include: - .dev/docker/env/Dockerfile + - .dev/docker/windows - .ci/azure-pipelines/env.yml pr: paths: include: - .dev/docker/env/Dockerfile + - .dev/docker/windows - .ci/azure-pipelines/env.yml schedules: @@ -32,7 +34,7 @@ variables: dockerHubID: "pointcloudlibrary" jobs: -- job: BuildAndPush +- job: BuildAndPushUbuntu timeoutInMinutes: 360 displayName: "Env" pool: @@ -44,27 +46,27 @@ jobs: UBUNTU_DISTRO: 18.04 USE_CUDA: true VTK_VERSION: 6 - tag: 18.04 + TAG: 18.04 Ubuntu 20.04: CUDA_VERSION: 11.2.1 UBUNTU_DISTRO: 20.04 VTK_VERSION: 7 USE_CUDA: true - tag: 20.04 + TAG: 20.04 Ubuntu 20.10: CUDA_VERSION: 11.2.1 UBUNTU_DISTRO: 20.10 VTK_VERSION: 7 # nvidia-cuda docker image has not been released for 20.10 yet USE_CUDA: "" - tag: 20.10 + TAG: 20.10 Ubuntu 21.04: CUDA_VERSION: 11.2.1 UBUNTU_DISTRO: 21.04 VTK_VERSION: 9 # nvidia-cuda docker image has not been released for 21.04 yet USE_CUDA: "" - tag: 21.04 + TAG: 21.04 steps: - task: Docker@2 displayName: "Build docker image" @@ -76,12 +78,12 @@ jobs: --build-arg UBUNTU_DISTRO=$(UBUNTU_DISTRO) --build-arg USE_CUDA=$(USE_CUDA) --build-arg VTK_VERSION=$(VTK_VERSION) - -t $(dockerHubID)/env:$(tag) + -t $(dockerHubID)/env:$(TAG) dockerfile: '$(Build.SourcesDirectory)/.dev/docker/env/Dockerfile' - tags: "$(tag)" + tags: "$(TAG)" - script: | set -x - docker run --rm -v "$(Build.SourcesDirectory)":/pcl $(dockerHubID)/env:$(tag) bash -c ' \ + docker run --rm -v "$(Build.SourcesDirectory)":/pcl $(dockerHubID)/env:$(TAG) bash -c ' \ mkdir /pcl/build && cd /pcl/build && \ cmake /pcl \ -DCMAKE_BUILD_TYPE="Release" \ @@ -96,6 +98,57 @@ jobs: command: push containerRegistry: $(dockerHub) repository: $(dockerHubID)/env - tags: "$(tag)" + tags: "$(TAG)" + condition: and(eq(variables['Build.Repository.Name'], 'PointCloudLibrary/pcl'), + eq(variables['Build.SourceBranch'], 'refs/heads/master')) +- job: BuildAndPushWindows + timeoutInMinutes: 360 + displayName: "Env" + pool: + vmImage: 'windows-2019' + strategy: + matrix: + Winx86: + PLATFORM: x86 + TAG: winx86 + GENERATOR: "'Visual Studio 16 2019' -A Win32" + VCPKGCOMMIT: 2bc10eae2fb0b8c7c098325c4e9d82aa5d0329d9 + Winx64: + PLATFORM: x64 + TAG: winx64 + GENERATOR: "'Visual Studio 16 2019' -A x64" + VCPKGCOMMIT: master + steps: + - task: Docker@2 + displayName: "Build docker image" + inputs: + command: build + arguments: | + --no-cache + --build-arg PLATFORM=$(PLATFORM) + --build-arg VCPKGCOMMIT=$(VCPKGCOMMIT) + -t $(dockerHubID)/env:$(TAG) + dockerfile: '$(Build.SourcesDirectory)/.dev/docker/windows/Dockerfile' + tags: "$(TAG)" + + - script: > + docker run --rm -v "$(Build.SourcesDirectory)":c:\pcl $(dockerHubID)/env:$(TAG) + powershell -command "mkdir c:\pcl\build; cd c:\pcl\build; + cmake c:\pcl -G$(GENERATOR) + -DVCPKG_TARGET_TRIPLET=$(PLATFORM)-windows-rel + -DCMAKE_BUILD_TYPE='Release' + -DCMAKE_TOOLCHAIN_FILE=c:\vcpkg\scripts\buildsystems\vcpkg.cmake + -DPCL_ONLY_CORE_POINT_TYPES=ON + -DBUILD_io:BOOL=OFF + -DBUILD_kdtree:BOOL=OFF; + cmake --build . " + displayName: 'Verify Dockerimage' + - task: Docker@2 + displayName: "Push docker image" + inputs: + command: push + containerRegistry: $(dockerHub) + repository: $(dockerHubID)/env + tags: "$(TAG)" condition: and(eq(variables['Build.Repository.Name'], 'PointCloudLibrary/pcl'), eq(variables['Build.SourceBranch'], 'refs/heads/master')) diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile new file mode 100644 index 00000000000..81047508383 --- /dev/null +++ b/.dev/docker/windows/Dockerfile @@ -0,0 +1,47 @@ +# escape=` + +FROM mcr.microsoft.com/windows/servercore:ltsc2019 + +# Use "--build-arg platform=x64" for 64 bit or x86 for 32 bit. +ARG PLATFORM + +# Use to set specific commit to checkout +ARG VCPKGCOMMIT + +# Download channel for fixed install. +ARG CHANNEL_BASE_URL=https://aka.ms/vs/16/release + +ADD $CHANNEL_BASE_URL/channel C:\TEMP\VisualStudio.chman + +SHELL ["powershell", "-Command", "$ErrorActionPreference = 'Stop'; $ProgressPreference = 'SilentlyContinue';"] + +# Download and install Build Tools for Visual Studio 2019 for native desktop +RUN wget $Env:CHANNEL_BASE_URL/vs_buildtools.exe -OutFile 'C:\TEMP\vs_buildtools.exe'; ` + Start-Process -FilePath C:\TEMP\vs_buildtools.exe -ArgumentList ` + "--quiet", ` + "--norestart", ` + "--nocache", ` + "--installPath", ` + "C:\BuildTools", ` + "--wait", ` + "--channelUri", ` + "C:\TEMP\VisualStudio.chman", ` + "--installChannelUri", ` + "C:\TEMP\VisualStudio.chman", ` + "--add", ` + "Microsoft.VisualStudio.Workload.VCTools", ` + "--includeRecommended" ` + -Wait -PassThru; ` + del c:\temp\vs_buildtools.exe; + +RUN iex ((New-Object System.Net.WebClient).DownloadString('https://chocolatey.org/install.ps1')); ` + choco install cmake git --installargs 'ADD_CMAKE_TO_PATH=System' -y --no-progress + +RUN git clone https://github.com/microsoft/vcpkg.git; cd vcpkg; git checkout $Env:VCPKGCOMMIT; + +# To explicit set VCPKG to only build Release version of the libraries. +COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cmake' + +RUN cd .\vcpkg; ` + .\bootstrap-vcpkg.bat; ` + .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest --triplet $Env:PLATFORM-windows-rel --clean-after-build; diff --git a/.dev/docker/windows/x64-windows-rel.cmake b/.dev/docker/windows/x64-windows-rel.cmake new file mode 100644 index 00000000000..f6c40253a08 --- /dev/null +++ b/.dev/docker/windows/x64-windows-rel.cmake @@ -0,0 +1,4 @@ +set(VCPKG_TARGET_ARCHITECTURE x64) +set(VCPKG_CRT_LINKAGE dynamic) +set(VCPKG_LIBRARY_LINKAGE dynamic) +set(VCPKG_BUILD_TYPE release) diff --git a/.dev/docker/windows/x86-windows-rel.cmake b/.dev/docker/windows/x86-windows-rel.cmake new file mode 100644 index 00000000000..0a277bdb77b --- /dev/null +++ b/.dev/docker/windows/x86-windows-rel.cmake @@ -0,0 +1,4 @@ +set(VCPKG_TARGET_ARCHITECTURE x86) +set(VCPKG_CRT_LINKAGE dynamic) +set(VCPKG_LIBRARY_LINKAGE dynamic) +set(VCPKG_BUILD_TYPE release) From e377982458784babbe032c185b178f7fb61b5cb3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 2 Apr 2021 18:30:52 +0200 Subject: [PATCH 021/123] Remove all deprecated for version 1.12 --- common/include/pcl/common/io.h | 19 +-- common/src/io.cpp | 109 -------------- io/include/pcl/io/grabber.h | 12 -- kdtree/CMakeLists.txt | 1 - kdtree/include/pcl/kdtree/flann.h | 53 ------- test/common/test_io.cpp | 199 -------------------------- tracking/include/pcl/tracking/boost.h | 46 ------ 7 files changed, 2 insertions(+), 437 deletions(-) delete mode 100644 kdtree/include/pcl/kdtree/flann.h delete mode 100644 tracking/include/pcl/tracking/boost.h diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index ccb6825de37..4e765e4ea20 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -254,10 +254,8 @@ namespace pcl /** \brief Concatenate two pcl::PCLPointCloud2 * - * \warning This function subtly differs from the deprecated concatenatePointCloud() - * The difference is that this function will concatenate IFF the non-skip fields - * are in the correct order and same in number. The deprecated function skipped - * fields even if both clouds didn't agree on the number of output fields + * \warning This function will concatenate IFF the non-skip fields are in the correct + * order and same in number. * \param[in] cloud1 the first input point cloud dataset * \param[in] cloud2 the second input point cloud dataset * \param[out] cloud_out the resultant output point cloud dataset @@ -287,19 +285,6 @@ namespace pcl return pcl::PolygonMesh::concatenate(mesh1, mesh2, mesh_out); } - /** \brief Concatenate two pcl::PCLPointCloud2 - * \param[in] cloud1 the first input point cloud dataset - * \param[in] cloud2 the second input point cloud dataset - * \param[out] cloud_out the resultant output point cloud dataset - * \return true if successful, false otherwise (e.g., name/number of fields differs) - * \ingroup common - */ - PCL_DEPRECATED(1, 12, "use pcl::concatenate() instead, but beware of subtle difference in behavior (see documentation)") - PCL_EXPORTS bool - concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1, - const pcl::PCLPointCloud2 &cloud2, - pcl::PCLPointCloud2 &cloud_out); - /** \brief Extract the indices of a given point cloud as a new point cloud * \param[in] cloud_in the input point cloud dataset * \param[in] indices the vector of indices representing the points to be copied from \a cloud_in diff --git a/common/src/io.cpp b/common/src/io.cpp index 838ab1c37a5..76841aecbb7 100644 --- a/common/src/io.cpp +++ b/common/src/io.cpp @@ -213,115 +213,6 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1, return (true); } -////////////////////////////////////////////////////////////////////////// -bool -pcl::concatenatePointCloud (const pcl::PCLPointCloud2 &cloud1, - const pcl::PCLPointCloud2 &cloud2, - pcl::PCLPointCloud2 &cloud_out) -{ - //if one input cloud has no points, but the other input does, just return the cloud with points - if (cloud1.width*cloud1.height == 0 && cloud2.width*cloud2.height > 0) - { - cloud_out = cloud2; - return (true); - } - if (cloud1.width*cloud1.height > 0 && cloud2.width*cloud2.height == 0) - { - cloud_out = cloud1; - return (true); - } - - bool strip = false; - for (const auto &field : cloud1.fields) - if (field.name == "_") - strip = true; - - for (const auto &field : cloud2.fields) - if (field.name == "_") - strip = true; - - if (!strip && cloud1.fields.size () != cloud2.fields.size ()) - { - PCL_ERROR ("[pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u)\n", cloud1.fields.size (), cloud2.fields.size ()); - return (false); - } - - // Copy cloud1 into cloud_out - cloud_out = cloud1; - std::size_t nrpts = cloud_out.data.size (); - // Height = 1 => no more organized - cloud_out.width = cloud1.width * cloud1.height + cloud2.width * cloud2.height; - cloud_out.height = 1; - if (!cloud1.is_dense || !cloud2.is_dense) - cloud_out.is_dense = false; - else - cloud_out.is_dense = true; - - // We need to strip the extra padding fields - if (strip) - { - // Get the field sizes for the second cloud - std::vector fields2; - std::vector fields2_sizes; - for (const auto &field : cloud2.fields) - { - if (field.name == "_") - continue; - - fields2_sizes.push_back (field.count * - pcl::getFieldSize (field.datatype)); - fields2.push_back (field); - } - - cloud_out.data.resize (nrpts + (cloud2.width * cloud2.height) * cloud_out.point_step); - - // Copy the second cloud - for (uindex_t cp = 0; cp < cloud2.width * cloud2.height; ++cp) - { - int i = 0; - for (std::size_t j = 0; j < fields2.size (); ++j) - { - if (cloud1.fields[i].name == "_") - { - ++i; - continue; - } - - // We're fine with the special RGB vs RGBA use case - if ((cloud1.fields[i].name == "rgb" && fields2[j].name == "rgba") || - (cloud1.fields[i].name == "rgba" && fields2[j].name == "rgb") || - (cloud1.fields[i].name == fields2[j].name)) - { - memcpy (reinterpret_cast (&cloud_out.data[nrpts + cp * cloud1.point_step + cloud1.fields[i].offset]), - reinterpret_cast (&cloud2.data[cp * cloud2.point_step + cloud2.fields[j].offset]), - fields2_sizes[j]); - ++i; // increment the field size i - } - } - } - } - else - { - for (std::size_t i = 0; i < cloud1.fields.size (); ++i) - { - // We're fine with the special RGB vs RGBA use case - if ((cloud1.fields[i].name == "rgb" && cloud2.fields[i].name == "rgba") || - (cloud1.fields[i].name == "rgba" && cloud2.fields[i].name == "rgb")) - continue; - // Otherwise we need to make sure the names are the same - if (cloud1.fields[i].name != cloud2.fields[i].name) - { - PCL_ERROR ("[pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s\n", i, cloud1.fields[i].name.c_str (), cloud2.fields[i].name.c_str ()); - return (false); - } - } - - cloud_out.data.resize (nrpts + cloud2.data.size ()); - memcpy (&cloud_out.data[nrpts], &cloud2.data[0], cloud2.data.size ()); - } - return (true); -} - ////////////////////////////////////////////////////////////////////////// bool pcl::getPointCloudAsEigen (const pcl::PCLPointCloud2 &in, Eigen::MatrixXf &out) diff --git a/io/include/pcl/io/grabber.h b/io/include/pcl/io/grabber.h index 378b81a8e2f..385ae501ebc 100644 --- a/io/include/pcl/io/grabber.h +++ b/io/include/pcl/io/grabber.h @@ -98,18 +98,6 @@ namespace pcl template boost::signals2::connection registerCallback (const std::function& callback); - /** \brief registers a callback function/method to a signal with the corresponding signature - * \param[in] callback: the callback function/method - * \return Connection object, that can be used to disconnect the callback method from the signal again. - */ - template class FunctionT> - PCL_DEPRECATED (1, 12, "please assign the callback to a std::function.") - boost::signals2::connection - registerCallback (const FunctionT& callback) - { - return registerCallback (std::function (callback)); - } - /** \brief indicates whether a signal with given parameter-type exists or not * \return true if signal exists, false otherwise */ diff --git a/kdtree/CMakeLists.txt b/kdtree/CMakeLists.txt index 826e902663d..a5a0fb9b8ec 100644 --- a/kdtree/CMakeLists.txt +++ b/kdtree/CMakeLists.txt @@ -19,7 +19,6 @@ set(srcs set(incs "include/pcl/${SUBSYS_NAME}/kdtree.h" "include/pcl/${SUBSYS_NAME}/io.h" - "include/pcl/${SUBSYS_NAME}/flann.h" "include/pcl/${SUBSYS_NAME}/kdtree_flann.h" ) diff --git a/kdtree/include/pcl/kdtree/flann.h b/kdtree/include/pcl/kdtree/flann.h deleted file mode 100644 index a49048d05ea..00000000000 --- a/kdtree/include/pcl/kdtree/flann.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2012, 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. - * - */ - -#pragma once - -#include - -PCL_DEPRECATED_HEADER(1, 12, "") - -#if defined _MSC_VER -# pragma warning(disable: 4267 4244) -#endif - -#include - -#if defined _MSC_VER -# pragma warning(default: 4267) -#endif diff --git a/test/common/test_io.cpp b/test/common/test_io.cpp index 6199fccc8a6..efdc8245b7b 100644 --- a/test/common/test_io.cpp +++ b/test/common/test_io.cpp @@ -128,205 +128,6 @@ TEST (PCL, copyPointCloud) } } -/////////////////////////////////////////////////////////////////////////////////////////// -// Ignore deprecation warnings on MSVC and GNU C Compiler -#ifdef _MSC_VER -#pragma warning(push) -#pragma warning(disable: 4996) -#elif defined __GNUC__ -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -#pragma GCC diagnostic push -#endif -TEST (PCL, concatenatePointCloud) -{ - CloudXYZRGBA cloud_xyz_rgba; - cloud_xyz_rgba.push_back (pt_xyz_rgba); - cloud_xyz_rgba.push_back (pt_xyz_rgba); - cloud_xyz_rgba.push_back (pt_xyz_rgba); - cloud_xyz_rgba.push_back (pt_xyz_rgba); - cloud_xyz_rgba.push_back (pt_xyz_rgba); - - CloudXYZRGBA cloud_xyz_rgba2; - cloud_xyz_rgba2.push_back (pt_xyz_rgba2); - cloud_xyz_rgba2.push_back (pt_xyz_rgba2); - - pcl::PCLPointCloud2 cloud1, cloud2, cloud_out, cloud_out2, cloud_out3, cloud_out4; - pcl::toPCLPointCloud2 (cloud_xyz_rgba, cloud1); - pcl::toPCLPointCloud2 (cloud_xyz_rgba2, cloud2); - - // Regular - pcl::concatenatePointCloud (cloud1, cloud2, cloud_out); - - CloudXYZRGBA cloud_all; - pcl::fromPCLPointCloud2 (cloud_out, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgba[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgba2.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]); - EXPECT_RGB_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]); - EXPECT_EQ (cloud_all[cloud_xyz_rgba.size () + i].rgba, cloud_xyz_rgba2[i].rgba); - } - - // RGB != RGBA - CloudXYZRGB cloud_xyz_rgb; - cloud_xyz_rgb.push_back (pt_xyz_rgb); - cloud_xyz_rgb.push_back (pt_xyz_rgb); - - pcl::toPCLPointCloud2 (cloud_xyz_rgb, cloud2); - pcl::concatenatePointCloud (cloud1, cloud2, cloud_out2); - - pcl::fromPCLPointCloud2 (cloud_out2, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgba[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); - EXPECT_RGB_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); - EXPECT_EQ (cloud_all[cloud_xyz_rgba.size () + i].rgba, cloud_xyz_rgb[i].rgba); - } - - // _ vs regular - int rgb_idx = pcl::getFieldIndex (cloud1, "rgba"); - cloud1.fields[rgb_idx].name = "_"; - pcl::concatenatePointCloud (cloud1, cloud2, cloud_out3); - - pcl::fromPCLPointCloud2 (cloud_out3, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); - // Data doesn't get modified - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgba[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); - - cloud1.fields[rgb_idx].name = "rgba"; - // regular vs _ - rgb_idx = pcl::getFieldIndex (cloud2, "rgb"); - cloud2.fields[rgb_idx].name = "_"; - pcl::concatenatePointCloud (cloud1, cloud2, cloud_out4); - - pcl::fromPCLPointCloud2 (cloud_out4, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); - // Data doesn't get modified - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgba[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].r, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].g, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].b, 0); - EXPECT_EQ (cloud_all[cloud_xyz_rgba.size () + i].rgba, 0); - } - - // _ vs _ - rgb_idx = pcl::getFieldIndex (cloud1, "rgba"); - cloud1.fields[rgb_idx].name = "_"; - pcl::toPCLPointCloud2 (cloud_xyz_rgb, cloud2); - rgb_idx = pcl::getFieldIndex (cloud2, "rgb"); - cloud2.fields[rgb_idx].name = "_"; - - pcl::concatenatePointCloud (cloud1, cloud2, cloud_out3); - - pcl::fromPCLPointCloud2 (cloud_out3, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); - // Data doesn't get modified - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgba[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgba[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].r, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].g, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgba.size () + i].b, 0); - EXPECT_EQ (cloud_all[cloud_xyz_rgba.size () + i].rgba, 0); - } - - cloud1.fields[rgb_idx].name = "rgba"; - // _ vs regular - rgb_idx = pcl::getFieldIndex (cloud1, "rgba"); - - cloud1.fields[rgb_idx].name = "_"; - pcl::toPCLPointCloud2 (cloud_xyz_rgb, cloud2); - pcl::concatenatePointCloud (cloud2, cloud1, cloud_out3); - - pcl::fromPCLPointCloud2 (cloud_out3, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgb[i]); - // Data doesn't get modified - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgb[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgb[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgb.size () + i], cloud_xyz_rgba[i]); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].r, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].g, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].b, 0); - EXPECT_EQ (cloud_all[cloud_xyz_rgb.size () + i].rgba, 0); - } - - cloud1.fields[rgb_idx].name = "rgba"; - // regular vs _ - rgb_idx = pcl::getFieldIndex (cloud2, "rgb"); - cloud2.fields[rgb_idx].name = "_"; - pcl::concatenatePointCloud (cloud2, cloud1, cloud_out4); - - pcl::fromPCLPointCloud2 (cloud_out4, cloud_all); - - EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgba2.size ()); - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgb[i]); - // Data doesn't get modified - EXPECT_RGB_EQ (cloud_all[i], cloud_xyz_rgb[i]); - EXPECT_EQ (cloud_all[i].rgba, cloud_xyz_rgb[i].rgba); - } - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) - { - EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgb.size () + i], cloud_xyz_rgba[i]); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].r, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].g, 0); - EXPECT_FLOAT_EQ (cloud_all[cloud_xyz_rgb.size () + i].b, 0); - EXPECT_EQ (cloud_all[cloud_xyz_rgb.size () + i].rgba, 0); - } -} -#ifdef _MSC_VER -#pragma warning(pop) -#elif defined __GNUC__ -#pragma GCC diagnostic pop -#endif - /////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, concatenatePointCloud2) { diff --git a/tracking/include/pcl/tracking/boost.h b/tracking/include/pcl/tracking/boost.h deleted file mode 100644 index 64a8d172e17..00000000000 --- a/tracking/include/pcl/tracking/boost.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * 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: lmeds.h 1370 2011-06-19 01:06:01Z jspricke $ - * - */ - -#pragma once - -#include - -PCL_DEPRECATED_HEADER(1, 12, "") - -#include From 785c046a3f966d64eed2b65811cb062c788e375b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 2 Apr 2021 18:34:28 +0200 Subject: [PATCH 022/123] Properly deprecate uniform_sampling header in keypoints __DEPRECATED might not be defined, so a user might not receive the warning. Start deprecation cycle again. --- keypoints/include/pcl/keypoints/uniform_sampling.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/keypoints/include/pcl/keypoints/uniform_sampling.h b/keypoints/include/pcl/keypoints/uniform_sampling.h index 4b9da1352c0..66596274997 100644 --- a/keypoints/include/pcl/keypoints/uniform_sampling.h +++ b/keypoints/include/pcl/keypoints/uniform_sampling.h @@ -39,8 +39,6 @@ #pragma once -#ifdef __DEPRECATED -PCL_DEPRECATED_HEADER(1, 12, "UniformSampling is not a Keypoint anymore, use instead.") -#endif +PCL_DEPRECATED_HEADER(1, 15, "UniformSampling is not a Keypoint anymore, use instead.") #include From 8b9dafdea1818fdf04fd9be93d04e39ac2e21d4d Mon Sep 17 00:00:00 2001 From: Yan Hang Date: Mon, 5 Apr 2021 17:14:57 +0800 Subject: [PATCH 023/123] [CI] Exclude doc files from CI to save CI time Fixed #3999. Updates to doc, README, etc. don't run formatting + main CI. --- .ci/azure-pipelines/azure-pipelines.yaml | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 511e093a8ee..53c61eec242 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -1,3 +1,19 @@ +trigger: + paths: + exclude: + - doc + - README.md + - CHANGES.md + - CONTRIBUTING.md + +pr: + paths: + exclude: + - doc + - README.md + - CHANGES.md + - CONTRIBUTING.md + resources: containers: - container: fmt From 5c8370a18be39cc62719af0bfcaf55f7f534bd74 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Nehil=20Dan=C4=B1=C5=9F?= Date: Mon, 5 Apr 2021 16:36:18 +0200 Subject: [PATCH 024/123] [tracking] made ParticleFilterTracker API user friendly (#4685) * made tracking API user friendly * Used if statement for type check in setUseNormal * Added use_normal is false cases to the condition --- tracking/include/pcl/tracking/particle_filter.h | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/tracking/include/pcl/tracking/particle_filter.h b/tracking/include/pcl/tracking/particle_filter.h index ce3ebf24d31..f4cf99e6113 100644 --- a/tracking/include/pcl/tracking/particle_filter.h +++ b/tracking/include/pcl/tracking/particle_filter.h @@ -293,7 +293,14 @@ class ParticleFilterTracker : public Tracker { inline void setUseNormal(bool use_normal) { - use_normal_ = use_normal; + if (traits::has_normal_v || !use_normal) { + use_normal_ = use_normal; + return; + } + PCL_WARN("[pcl::%s::setUseNormal] " + "use_normal_ == true is not supported in this Point Type.\n", + getClassName().c_str()); + use_normal_ = false; } /** \brief Get the value of use_normal_. */ @@ -461,7 +468,7 @@ class ParticleFilterTracker : public Tracker { void computeTransformedPointCloudWithNormal(const StateT&, pcl::Indices&, PointCloudIn&) { - PCL_WARN("[pcl::%s::computeTransformedPointCloudWithoutNormal] " + PCL_WARN("[pcl::%s::computeTransformedPointCloudWithNormal] " "use_normal_ == true is not supported in this Point Type.\n", getClassName().c_str()); } From 792f3e5e14928f2f5e10acbdaaaffa0ef5d19136 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 5 Apr 2021 22:06:24 +0200 Subject: [PATCH 025/123] [GPU] MSVC / CUDA fix (#4675) * Fix MSVC 16.9 change --- gpu/octree/src/utils/morton.hpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/gpu/octree/src/utils/morton.hpp b/gpu/octree/src/utils/morton.hpp index de08c47808e..943e3deb105 100644 --- a/gpu/octree/src/utils/morton.hpp +++ b/gpu/octree/src/utils/morton.hpp @@ -122,10 +122,12 @@ namespace pcl } __device__ __host__ __forceinline__ Morton::code_t operator()(const float3& p) const - { - const int cellx = min((int)std::floor(depth_mult * min(1.f, max(0.f, (p.x - minp_.x)/dims_.x))), depth_mult - 1); - const int celly = min((int)std::floor(depth_mult * min(1.f, max(0.f, (p.y - minp_.y)/dims_.y))), depth_mult - 1); - const int cellz = min((int)std::floor(depth_mult * min(1.f, max(0.f, (p.z - minp_.z)/dims_.z))), depth_mult - 1); + { + //Using floorf due to changes to MSVC 16.9. See details here: https://devtalk.blender.org/t/cuda-compile-error-windows-10/17886/4 + //floorf is without std:: see why here: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=79700 + const int cellx = min((int)floorf(depth_mult * min(1.f, max(0.f, (p.x - minp_.x)/dims_.x))), depth_mult - 1); + const int celly = min((int)floorf(depth_mult * min(1.f, max(0.f, (p.y - minp_.y)/dims_.y))), depth_mult - 1); + const int cellz = min((int)floorf(depth_mult * min(1.f, max(0.f, (p.z - minp_.z)/dims_.z))), depth_mult - 1); return Morton::createCode(cellx, celly, cellz); } @@ -151,4 +153,4 @@ namespace pcl } } -#endif /* PCL_GPU_OCTREE_MORTON_HPP */ \ No newline at end of file +#endif /* PCL_GPU_OCTREE_MORTON_HPP */ From 0df79823d8abcfc76552ff14455cf274a835bff9 Mon Sep 17 00:00:00 2001 From: ueqri Date: Wed, 7 Apr 2021 01:10:12 +0800 Subject: [PATCH 026/123] separated documentation & tutorials into a new pipeline --- .ci/azure-pipelines/azure-pipelines.yaml | 15 --------- .ci/azure-pipelines/docs-pipeline.yaml | 41 ++++++++++++++++++++++++ 2 files changed, 41 insertions(+), 15 deletions(-) create mode 100644 .ci/azure-pipelines/docs-pipeline.yaml diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 53c61eec242..69881c08317 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -24,8 +24,6 @@ resources: image: pointcloudlibrary/env:20.04 - container: env2010 image: pointcloudlibrary/env:20.10 - - container: doc - image: pointcloudlibrary/doc stages: - stage: formatting @@ -163,16 +161,3 @@ stages: VCPKG_ROOT: 'C:\vcpkg' steps: - template: build/windows.yaml - - - stage: documentation - displayName: Documentation - dependsOn: [] - jobs: - - template: documentation.yaml - - - stage: tutorials - displayName: Tutorials - dependsOn: build_gcc - jobs: - - template: tutorials.yaml - diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml new file mode 100644 index 00000000000..696bf537a5a --- /dev/null +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -0,0 +1,41 @@ +trigger: + paths: + include: + - doc + - README.md + - CHANGES.md + - CONTRIBUTING.md + +pr: + paths: + include: + - doc + - README.md + - CHANGES.md + - CONTRIBUTING.md + +resources: + pipelines: + - pipeline: Build + source: Build-CI + trigger: + stages: + - build_gcc + containers: + - container: doc # for documentation.yaml + image: pointcloudlibrary/doc + - container: env1804 # for tutorials.yaml + image: pointcloudlibrary/env:18.04 + +stages: + - stage: documentation + displayName: Documentation + jobs: + - template: documentation.yaml + + - stage: tutorials + displayName: Tutorials + # triggered only by build_gcc stage + condition: eq(variables['Build.Reason'], 'ResourceTrigger') + jobs: + - template: tutorials.yaml From 779fe025e4ce59a3d7bfeeb488a4de5dc7676651 Mon Sep 17 00:00:00 2001 From: Yan Hang Date: Wed, 7 Apr 2021 01:16:54 +0800 Subject: [PATCH 027/123] fixed a typo in docs-pipeline.yaml fixed the name of the main build pipeline. --- .ci/azure-pipelines/docs-pipeline.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index 696bf537a5a..26cbc717838 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -16,8 +16,8 @@ pr: resources: pipelines: - - pipeline: Build - source: Build-CI + - pipeline: Build-CI + source: Build trigger: stages: - build_gcc From f1b0d1a962d7fcec0dd100a0ea7960f0ba58c2f0 Mon Sep 17 00:00:00 2001 From: Guilhem Villemin Date: Tue, 6 Apr 2021 20:59:26 +0200 Subject: [PATCH 028/123] Add access to boxSearch (#4282) * Add access to boxSearch * Update octree.h * change boxSearch signature * fix indentation, use uindex_t as return type --- search/include/pcl/search/octree.h | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/search/include/pcl/search/octree.h b/search/include/pcl/search/octree.h index 0df81f3d311..d98e605e715 100644 --- a/search/include/pcl/search/octree.h +++ b/search/include/pcl/search/octree.h @@ -275,7 +275,17 @@ namespace pcl { return (tree_->approxNearestSearch (query_index, result_index, sqr_distance)); } - + /** \brief Search for points within rectangular search area + * \param[in] min_pt lower corner of search area + * \param[in] max_pt upper corner of search area + * \param[out] k_indices the resultant point indices + * \return number of points found within search area + */ + inline uindex_t + boxSearch(const Eigen::Vector3f &min_pt, const Eigen::Vector3f &max_pt, Indices &k_indices) const + { + return (tree_->boxSearch(min_pt, max_pt, k_indices)); + } }; } } From e9e3c022816d52b259d1e4cc5d631e9dc91035d3 Mon Sep 17 00:00:00 2001 From: ueqri Date: Wed, 7 Apr 2021 16:59:41 +0800 Subject: [PATCH 029/123] added formatting to docs pipeline & fixed tutorials stage --- .ci/azure-pipelines/docs-pipeline.yaml | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index 26cbc717838..c31ed8f26e8 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -22,12 +22,23 @@ resources: stages: - build_gcc containers: + - container: fmt # for formatting.yaml + image: pointcloudlibrary/fmt - container: doc # for documentation.yaml image: pointcloudlibrary/doc - container: env1804 # for tutorials.yaml image: pointcloudlibrary/env:18.04 stages: + - stage: formatting + displayName: Formatting + # if docs pipeline triggered by build_gcc stage, + # the formatting stage has already run, thus it + # won't run for a second time here. + condition: not(eq(variables['Build.Reason'], 'ResourceTrigger')) + jobs: + - template: formatting.yaml + - stage: documentation displayName: Documentation jobs: @@ -35,7 +46,5 @@ stages: - stage: tutorials displayName: Tutorials - # triggered only by build_gcc stage - condition: eq(variables['Build.Reason'], 'ResourceTrigger') jobs: - template: tutorials.yaml From d56cc62e7624dd701fe58a427490afad8f4d3eaa Mon Sep 17 00:00:00 2001 From: jmaiolini <45634864+jmaiolini@users.noreply.github.com> Date: Thu, 8 Apr 2021 14:56:12 +0200 Subject: [PATCH 030/123] [geometry] Update mesh_indices.h to not need a generator file (#4648) --- geometry/include/pcl/geometry/mesh_indices.h | 451 ++---------------- geometry/include/pcl/geometry/mesh_indices.py | 266 ----------- 2 files changed, 42 insertions(+), 675 deletions(-) delete mode 100644 geometry/include/pcl/geometry/mesh_indices.py diff --git a/geometry/include/pcl/geometry/mesh_indices.h b/geometry/include/pcl/geometry/mesh_indices.h index 115e2228c23..79cbddc8c9d 100644 --- a/geometry/include/pcl/geometry/mesh_indices.h +++ b/geometry/include/pcl/geometry/mesh_indices.h @@ -38,9 +38,6 @@ * */ -// NOTE: This file has been created with -// 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py' - #pragma once #include @@ -48,38 +45,42 @@ #include //////////////////////////////////////////////////////////////////////////////// -// VertexIndex +// MeshIndex //////////////////////////////////////////////////////////////////////////////// namespace pcl { -namespace geometry { -/** \brief Index used to access elements in the half-edge mesh. It is basically just a - * wrapper around an integer with a few added methods. - * \author Martin Saelzle - * \ingroup geometry - */ -class VertexIndex +namespace detail { + +template +class MeshIndex; + +template +std::istream& +operator>>(std::istream& is, MeshIndex&); + +template +class MeshIndex : boost::totally_ordered< - pcl::geometry::VertexIndex // < > <= >= == != - , - boost::unit_steppable, // < > <= >= == != + boost::unit_steppable, // ++ -- (pre and post) + boost::additive // += + + // -= - >>> { + public: using Base = boost::totally_ordered< - pcl::geometry::VertexIndex, - boost::unit_steppable>>; - using Self = pcl::geometry::VertexIndex; + MeshIndex, + boost::unit_steppable, + boost::additive>>>; + using Self = MeshIndex; /** \brief Constructor. Initializes with an invalid index. */ - VertexIndex() : index_(-1) {} + MeshIndex() : index_(-1) {} /** \brief Constructor. * \param[in] index The integer index. */ - explicit VertexIndex(const int index) : index_(index) {} + explicit MeshIndex(const int index) : index_(index) {} /** \brief Returns true if the index is valid. */ inline bool @@ -159,31 +160,28 @@ class VertexIndex /** \brief Stored index. */ int index_; - friend std::istream& - operator>>(std::istream& is, pcl::geometry::VertexIndex& index); + friend std::istream& operator>><>(std::istream& is, MeshIndex& index); }; /** \brief ostream operator. */ +template inline std::ostream& -operator<<(std::ostream& os, const pcl::geometry::VertexIndex& index) +operator<<(std::ostream& os, const MeshIndex& index) { return (os << index.get()); } /** \brief istream operator. */ +template inline std::istream& -operator>>(std::istream& is, pcl::geometry::VertexIndex& index) +operator>>(std::istream& is, MeshIndex& index) { return (is >> index.index_); } -} // End namespace geometry +} // End namespace detail } // End namespace pcl -//////////////////////////////////////////////////////////////////////////////// -// HalfEdgeIndex -//////////////////////////////////////////////////////////////////////////////// - namespace pcl { namespace geometry { /** \brief Index used to access elements in the half-edge mesh. It is basically just a @@ -191,390 +189,25 @@ namespace geometry { * \author Martin Saelzle * \ingroup geometry */ -class HalfEdgeIndex -: boost::totally_ordered< - pcl::geometry::HalfEdgeIndex // < > <= >= == != - , - boost::unit_steppable>> { -public: - using Base = boost::totally_ordered< - pcl::geometry::HalfEdgeIndex, - boost::unit_steppable>>; - using Self = pcl::geometry::HalfEdgeIndex; - - /** \brief Constructor. Initializes with an invalid index. */ - HalfEdgeIndex() : index_(-1) {} - - /** \brief Constructor. - * \param[in] index The integer index. - */ - explicit HalfEdgeIndex(const int index) : index_(index) {} - - /** \brief Returns true if the index is valid. */ - inline bool - isValid() const - { - return (index_ >= 0); - } - - /** \brief Invalidate the index. */ - inline void - invalidate() - { - index_ = -1; - } - - /** \brief Get the index. */ - inline int - get() const - { - return (index_); - } - - /** \brief Set the index. */ - inline void - set(const int index) - { - index_ = index; - } - - /** \brief Comparison operators (with boost::operators): < > <= >= */ - inline bool - operator<(const Self& other) const - { - return (this->get() < other.get()); - } - - /** \brief Comparison operators (with boost::operators): == != */ - inline bool - operator==(const Self& other) const - { - return (this->get() == other.get()); - } - - /** \brief Increment operators (with boost::operators): ++ (pre and post) */ - inline Self& - operator++() - { - ++index_; - return (*this); - } - - /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ - inline Self& - operator--() - { - --index_; - return (*this); - } - - /** \brief Addition operators (with boost::operators): + += */ - inline Self& - operator+=(const Self& other) - { - index_ += other.get(); - return (*this); - } - - /** \brief Subtraction operators (with boost::operators): - -= */ - inline Self& - operator-=(const Self& other) - { - index_ -= other.get(); - return (*this); - } - -private: - /** \brief Stored index. */ - int index_; - - friend std::istream& - operator>>(std::istream& is, pcl::geometry::HalfEdgeIndex& index); -}; - -/** \brief ostream operator. */ -inline std::ostream& -operator<<(std::ostream& os, const pcl::geometry::HalfEdgeIndex& index) -{ - return (os << index.get()); -} - -/** \brief istream operator. */ -inline std::istream& -operator>>(std::istream& is, pcl::geometry::HalfEdgeIndex& index) -{ - return (is >> index.index_); -} - -} // End namespace geometry -} // End namespace pcl - -//////////////////////////////////////////////////////////////////////////////// -// EdgeIndex -//////////////////////////////////////////////////////////////////////////////// - -namespace pcl { -namespace geometry { +using VertexIndex = pcl::detail::MeshIndex; /** \brief Index used to access elements in the half-edge mesh. It is basically just a * wrapper around an integer with a few added methods. * \author Martin Saelzle * \ingroup geometry */ -class EdgeIndex -: boost::totally_ordered< - pcl::geometry::EdgeIndex // < > <= >= == != - , - boost::unit_steppable>> { -public: - using Base = boost::totally_ordered< - pcl::geometry::EdgeIndex, - boost::unit_steppable>>; - using Self = pcl::geometry::EdgeIndex; - - /** \brief Constructor. Initializes with an invalid index. */ - EdgeIndex() : index_(-1) {} - - /** \brief Constructor. - * \param[in] index The integer index. - */ - explicit EdgeIndex(const int index) : index_(index) {} - - /** \brief Returns true if the index is valid. */ - inline bool - isValid() const - { - return (index_ >= 0); - } - - /** \brief Invalidate the index. */ - inline void - invalidate() - { - index_ = -1; - } - - /** \brief Get the index. */ - inline int - get() const - { - return (index_); - } - - /** \brief Set the index. */ - inline void - set(const int index) - { - index_ = index; - } - - /** \brief Comparison operators (with boost::operators): < > <= >= */ - inline bool - operator<(const Self& other) const - { - return (this->get() < other.get()); - } - - /** \brief Comparison operators (with boost::operators): == != */ - inline bool - operator==(const Self& other) const - { - return (this->get() == other.get()); - } - - /** \brief Increment operators (with boost::operators): ++ (pre and post) */ - inline Self& - operator++() - { - ++index_; - return (*this); - } - - /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ - inline Self& - operator--() - { - --index_; - return (*this); - } - - /** \brief Addition operators (with boost::operators): + += */ - inline Self& - operator+=(const Self& other) - { - index_ += other.get(); - return (*this); - } - - /** \brief Subtraction operators (with boost::operators): - -= */ - inline Self& - operator-=(const Self& other) - { - index_ -= other.get(); - return (*this); - } - -private: - /** \brief Stored index. */ - int index_; - - friend std::istream& - operator>>(std::istream& is, pcl::geometry::EdgeIndex& index); -}; - -/** \brief ostream operator. */ -inline std::ostream& -operator<<(std::ostream& os, const pcl::geometry::EdgeIndex& index) -{ - return (os << index.get()); -} - -/** \brief istream operator. */ -inline std::istream& -operator>>(std::istream& is, pcl::geometry::EdgeIndex& index) -{ - return (is >> index.index_); -} - -} // End namespace geometry -} // End namespace pcl - -//////////////////////////////////////////////////////////////////////////////// -// FaceIndex -//////////////////////////////////////////////////////////////////////////////// - -namespace pcl { -namespace geometry { +using HalfEdgeIndex = pcl::detail::MeshIndex; /** \brief Index used to access elements in the half-edge mesh. It is basically just a * wrapper around an integer with a few added methods. * \author Martin Saelzle * \ingroup geometry */ -class FaceIndex -: boost::totally_ordered< - pcl::geometry::FaceIndex // < > <= >= == != - , - boost::unit_steppable>> { -public: - using Base = boost::totally_ordered< - pcl::geometry::FaceIndex, - boost::unit_steppable>>; - using Self = pcl::geometry::FaceIndex; - - /** \brief Constructor. Initializes with an invalid index. */ - FaceIndex() : index_(-1) {} - - /** \brief Constructor. - * \param[in] index The integer index. - */ - explicit FaceIndex(const int index) : index_(index) {} - - /** \brief Returns true if the index is valid. */ - inline bool - isValid() const - { - return (index_ >= 0); - } - - /** \brief Invalidate the index. */ - inline void - invalidate() - { - index_ = -1; - } - - /** \brief Get the index. */ - inline int - get() const - { - return (index_); - } - - /** \brief Set the index. */ - inline void - set(const int index) - { - index_ = index; - } - - /** \brief Comparison operators (with boost::operators): < > <= >= */ - inline bool - operator<(const Self& other) const - { - return (this->get() < other.get()); - } - - /** \brief Comparison operators (with boost::operators): == != */ - inline bool - operator==(const Self& other) const - { - return (this->get() == other.get()); - } - - /** \brief Increment operators (with boost::operators): ++ (pre and post) */ - inline Self& - operator++() - { - ++index_; - return (*this); - } - - /** \brief Decrement operators (with boost::operators): \-\- (pre and post) */ - inline Self& - operator--() - { - --index_; - return (*this); - } - - /** \brief Addition operators (with boost::operators): + += */ - inline Self& - operator+=(const Self& other) - { - index_ += other.get(); - return (*this); - } - - /** \brief Subtraction operators (with boost::operators): - -= */ - inline Self& - operator-=(const Self& other) - { - index_ -= other.get(); - return (*this); - } - -private: - /** \brief Stored index. */ - int index_; - - friend std::istream& - operator>>(std::istream& is, pcl::geometry::FaceIndex& index); -}; - -/** \brief ostream operator. */ -inline std::ostream& -operator<<(std::ostream& os, const pcl::geometry::FaceIndex& index) -{ - return (os << index.get()); -} - -/** \brief istream operator. */ -inline std::istream& -operator>>(std::istream& is, pcl::geometry::FaceIndex& index) -{ - return (is >> index.index_); -} +using EdgeIndex = pcl::detail::MeshIndex; +/** \brief Index used to access elements in the half-edge mesh. It is basically just a + * wrapper around an integer with a few added methods. + * \author Martin Saelzle + * \ingroup geometry + */ +using FaceIndex = pcl::detail::MeshIndex; } // End namespace geometry } // End namespace pcl @@ -586,7 +219,7 @@ operator>>(std::istream& is, pcl::geometry::FaceIndex& index) namespace pcl { namespace geometry { /** \brief Convert the given half-edge index to an edge index. */ -inline pcl::geometry::EdgeIndex +inline EdgeIndex toEdgeIndex(const HalfEdgeIndex& index) { return (index.isValid() ? EdgeIndex(index.get() / 2) : EdgeIndex()); @@ -594,10 +227,10 @@ toEdgeIndex(const HalfEdgeIndex& index) /** \brief Convert the given edge index to a half-edge index. * \param index - * \param[in] get_first The first half-edge of the edge is returned if this variable is - * true; elsewise the second. + * \param[in] get_first The first half-edge of the edge is returned if this + * variable is true; elsewise the second. */ -inline pcl::geometry::HalfEdgeIndex +inline HalfEdgeIndex toHalfEdgeIndex(const EdgeIndex& index, const bool get_first = true) { return (index.isValid() diff --git a/geometry/include/pcl/geometry/mesh_indices.py b/geometry/include/pcl/geometry/mesh_indices.py deleted file mode 100644 index 9bd0f53f3fc..00000000000 --- a/geometry/include/pcl/geometry/mesh_indices.py +++ /dev/null @@ -1,266 +0,0 @@ -## -# Software License Agreement (BSD License) -# -# Point Cloud Library (PCL) - www.pointclouds.org -# Copyright (c) 2009-2012, 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. -# - -import os - -filename = os.path.join (os.path.dirname (__file__), 'mesh_indices.h') -class_names = ['VertexIndex', 'HalfEdgeIndex', 'EdgeIndex', 'FaceIndex'] - -################################################################################ - -f = open (filename, 'w') - -f.write ('/*\n') -f.write (' * Software License Agreement (BSD License)\n') -f.write (' *\n') -f.write (' * Point Cloud Library (PCL) - www.pointclouds.org\n') -f.write (' * Copyright (c) 2009-2012, Willow Garage, Inc.\n') -f.write (' * Copyright (c) 2012-, Open Perception, Inc.\n') -f.write (' *\n') -f.write (' * All rights reserved.\n') -f.write (' *\n') -f.write (' * Redistribution and use in source and binary forms, with or without\n') -f.write (' * modification, are permitted provided that the following conditions\n') -f.write (' * are met:\n') -f.write (' *\n') -f.write (' * * Redistributions of source code must retain the above copyright\n') -f.write (' * notice, this list of conditions and the following disclaimer.\n') -f.write (' * * Redistributions in binary form must reproduce the above\n') -f.write (' * copyright notice, this list of conditions and the following\n') -f.write (' * disclaimer in the documentation and/or other materials provided\n') -f.write (' * with the distribution.\n') -f.write (' * * Neither the name of the copyright holder(s) nor the names of its\n') -f.write (' * contributors may be used to endorse or promote products derived\n') -f.write (' * from this software without specific prior written permission.\n') -f.write (' *\n') -f.write (' * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n') -f.write (' * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n') -f.write (' * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n') -f.write (' * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n') -f.write (' * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n') -f.write (' * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n') -f.write (' * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n') -f.write (' * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n') -f.write (' * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n') -f.write (' * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n') -f.write (' * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n') -f.write (' * POSSIBILITY OF SUCH DAMAGE.\n') -f.write (' *\n') -f.write (' * $Id$\n') -f.write (' *\n') -f.write (' */\n\n') - -f.write ("// NOTE: This file has been created with 'pcl_src/geometry/include/pcl/geometry/mesh_indices.py'\n\n") - -f.write ('#ifndef PCL_GEOMETRY_MESH_INDICES_H\n') -f.write ('#define PCL_GEOMETRY_MESH_INDICES_H\n\n') - -f.write ('#include \n\n') - -f.write ('#include \n\n') - -for cn in class_names: - - f.write ('////////////////////////////////////////////////////////////////////////////////\n') - f.write ('// ' + cn + '\n') - f.write ('////////////////////////////////////////////////////////////////////////////////\n\n') - - f.write ('namespace pcl\n') - f.write ('{\n') - f.write (' namespace geometry\n') - f.write (' {\n') - f.write (' /** \\brief Index used to access elements in the half-edge mesh. It is basically just a\n') - f.write (' * wrapper around an integer with a few added methods.\n') - f.write (' * \\author Martin Saelzle\n') - f.write (' * \ingroup geometry\n') - f.write (' */\n') - f.write (' class ' + cn + '\n') - f.write (' : boost::totally_ordered <= >= == !=\n') - f.write (' , boost::unit_steppable > >\n') - f.write (' {\n') - f.write (' public:\n\n') - - f.write (' typedef boost::totally_ordered > > Base;\n') - f.write (' typedef pcl::geometry::' + cn + ' Self;\n\n') - - f.write (' /** \\brief Constructor. Initializes with an invalid index. */\n') - f.write (' ' + cn + ' ()\n') - f.write (' : index_ (-1)\n') - f.write (' {\n') - f.write (' }\n\n') - - f.write (' /** \\brief Constructor.\n') - f.write (' * \param[in] index The integer index.\n') - f.write (' */\n') - f.write (' explicit ' + cn + ' (const int index)\n') - f.write (' : index_ (index)\n') - f.write (' {\n') - f.write (' }\n\n') - - f.write (' /** \\brief Returns true if the index is valid. */\n') - f.write (' inline bool\n') - f.write (' isValid () const\n') - f.write (' {\n') - f.write (' return (index_ >= 0);\n') - f.write (' }\n\n') - - f.write (' /** \\brief Invalidate the index. */\n') - f.write (' inline void\n') - f.write (' invalidate ()\n') - f.write (' {\n') - f.write (' index_ = -1;\n') - f.write (' }\n\n') - - f.write (' /** \\brief Get the index. */\n') - f.write (' inline int\n') - f.write (' get () const\n') - f.write (' {\n') - f.write (' return (index_);\n') - f.write (' }\n\n') - - f.write (' /** \\brief Set the index. */\n') - f.write (' inline void\n') - f.write (' set (const int index)\n') - f.write (' {\n') - f.write (' index_ = index;\n') - f.write (' }\n\n') - - f.write (' /** \\brief Comparison operators (with boost::operators): < > <= >= */\n') - f.write (' inline bool\n') - f.write (' operator < (const Self& other) const\n') - f.write (' {\n') - f.write (' return (this->get () < other.get ());\n') - f.write (' }\n\n') - - f.write (' /** \\brief Comparison operators (with boost::operators): == != */\n') - f.write (' inline bool\n') - f.write (' operator == (const Self& other) const\n') - f.write (' {\n') - f.write (' return (this->get () == other.get ());\n') - f.write (' }\n\n') - - f.write (' /** \\brief Increment operators (with boost::operators): ++ (pre and post) */\n') - f.write (' inline Self&\n') - f.write (' operator ++ ()\n') - f.write (' {\n') - f.write (' ++index_;\n') - f.write (' return (*this);\n') - f.write (' }\n\n') - - f.write (' /** \\brief Decrement operators (with boost::operators): \-\- (pre and post) */\n') - f.write (' inline Self&\n') - f.write (' operator -- ()\n') - f.write (' {\n') - f.write (' --index_;\n') - f.write (' return (*this);\n') - f.write (' }\n\n') - - f.write (' /** \\brief Addition operators (with boost::operators): + += */\n') - f.write (' inline Self&\n') - f.write (' operator += (const Self& other)\n') - f.write (' {\n') - f.write (' index_ += other.get ();\n') - f.write (' return (*this);\n') - f.write (' }\n\n') - - f.write (' /** \\brief Subtraction operators (with boost::operators): - -= */\n') - f.write (' inline Self&\n') - f.write (' operator -= (const Self& other)\n') - f.write (' {\n') - f.write (' index_ -= other.get ();\n') - f.write (' return (*this);\n') - f.write (' }\n\n') - - f.write (' private:\n\n') - - f.write (' /** \\brief Stored index. */\n') - f.write (' int index_;\n\n') - - f.write (' friend std::istream&\n') - f.write (' operator >> (std::istream& is, pcl::geometry::' + cn + '& index);\n') - f.write (' };\n\n') - - f.write (' /** \\brief ostream operator. */\n') - f.write (' inline std::ostream&\n') - f.write (' operator << (std::ostream& os, const pcl::geometry::' + cn + '& index)\n') - f.write (' {\n') - f.write (' return (os << index.get ());\n') - f.write (' }\n\n') - - f.write (' /** \\brief istream operator. */\n') - f.write (' inline std::istream&\n') - f.write (' operator >> (std::istream& is, pcl::geometry::' + cn + '& index)\n') - f.write (' {\n') - f.write (' return (is >> index.index_);\n') - f.write (' }\n\n') - - f.write (' } // End namespace geometry\n') - f.write ('} // End namespace pcl\n\n') - -f.write ('////////////////////////////////////////////////////////////////////////////////\n') -f.write ('// Conversions\n') -f.write ('////////////////////////////////////////////////////////////////////////////////\n\n') - -f.write ('namespace pcl\n') -f.write ('{\n') -f.write (' namespace geometry\n') -f.write (' {\n') -f.write (' /** \\brief Convert the given half-edge index to an edge index. */\n') -f.write (' inline pcl::geometry::EdgeIndex\n') -f.write (' toEdgeIndex (const HalfEdgeIndex& index)\n') -f.write (' {\n') -f.write (' return (index.isValid () ? EdgeIndex (index.get () / 2) : EdgeIndex ());\n') -f.write (' }\n\n') - -f.write (' /** \\brief Convert the given edge index to a half-edge index.\n') -f.write (' * \\param[in] get_first The first half-edge of the edge is returned if this variable is true; elsewise the second.\n') -f.write (' */\n') -f.write (' inline pcl::geometry::HalfEdgeIndex\n') -f.write (' toHalfEdgeIndex (const EdgeIndex& index, const bool get_first=true)\n') -f.write (' {\n') -f.write (' return (index.isValid () ? HalfEdgeIndex (index.get () * 2 + static_cast (!get_first)) : HalfEdgeIndex ());\n') -f.write (' }\n') -f.write (' } // End namespace geometry\n') -f.write ('} // End namespace pcl\n\n') - -f.write ('#endif // PCL_GEOMETRY_MESH_INDICES_H\n') - -f.close() From e1664a4ba63107b2c5ca10bc4137c5a8f73ae0b5 Mon Sep 17 00:00:00 2001 From: Yosshi999 Date: Thu, 8 Apr 2021 22:42:08 +0900 Subject: [PATCH 031/123] add ellipsoid shape to pcl_visualizer (#4531) * add ellipsoid shape to pcl_visualizer * more accurate description * addEllipsoid with Isometry3f * use const * support only Isometry3d argument * add a component for ellipsoid * add a link library for ellipsoid --- cmake/pcl_find_vtk.cmake | 1 + visualization/CMakeLists.txt | 1 + .../include/pcl/visualization/common/shapes.h | 12 ++++++++ .../pcl/visualization/pcl_visualizer.h | 14 ++++++++++ visualization/src/common/shapes.cpp | 27 ++++++++++++++++++ visualization/src/pcl_visualizer.cpp | 28 +++++++++++++++++++ 6 files changed, 83 insertions(+) diff --git a/cmake/pcl_find_vtk.cmake b/cmake/pcl_find_vtk.cmake index 99f8d558606..300e27ff80b 100644 --- a/cmake/pcl_find_vtk.cmake +++ b/cmake/pcl_find_vtk.cmake @@ -37,6 +37,7 @@ endif() set(NON_PREFIX_PCL_VTK_COMPONENTS ChartsCore CommonColor + CommonComputationalGeometry CommonCore CommonDataModel CommonExecutionModel diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index e9ead2ac0e7..ed2c4ca1b99 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -168,6 +168,7 @@ else() target_link_libraries("${LIB_NAME}" VTK::ChartsCore VTK::CommonColor + VTK::CommonComputationalGeometry VTK::CommonDataModel VTK::FiltersExtraction VTK::FiltersGeometry diff --git a/visualization/include/pcl/visualization/common/shapes.h b/visualization/include/pcl/visualization/common/shapes.h index 3396753b6b8..d74389ddde7 100644 --- a/visualization/include/pcl/visualization/common/shapes.h +++ b/visualization/include/pcl/visualization/common/shapes.h @@ -280,6 +280,18 @@ namespace pcl createCube (double x_min, double x_max, double y_min, double y_max, double z_min, double z_max); + + /** \brief Create an ellipsoid shape from the given parameters. + * + * \param[in] transform a transformation to apply to the ellipsoid from 0,0,0 + * \param[in] radius_x the ellipsoid's radius along its local x-axis + * \param[in] radius_y the ellipsoid's radius along its local y-axis + * \param[in] radius_z the ellipsoid's radius along its local z-axis + * \ingroup visualization + */ + PCL_EXPORTS vtkSmartPointer + createEllipsoid (const Eigen::Isometry3d &transform, + double radius_x, double radius_y, double radius_z); /** \brief Allocate a new unstructured grid smartpointer. For internal use only. * \param[out] polydata the resultant unstructured grid. diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 64e14ebf8ac..1c0c0154d88 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -1694,6 +1694,20 @@ namespace pcl addCube (float x_min, float x_max, float y_min, float y_max, float z_min, float z_max, double r = 1.0, double g = 1.0, double b = 1.0, const std::string &id = "cube", int viewport = 0); + /** \brief Add an ellipsoid from the given parameters + * \param[in] transform a transformation to apply to the ellipsoid from 0,0,0 + * \param[in] radius_x the ellipsoid's radius along its local x-axis + * \param[in] radius_y the ellipsoid's radius along its local y-axis + * \param[in] radius_z the ellipsoid's radius along its local z-axis + * \param[in] id the ellipsoid id/name (default: "ellipsoid") + * \param[in] viewport (optional) the id of the new viewport (default: 0) + */ + bool + addEllipsoid (const Eigen::Isometry3d &transform, + double radius_x, double radius_y, double radius_z, + const std::string &id = "ellipsoid", + int viewport = 0); + /** \brief Changes the visual representation for all actors to surface representation. */ void setRepresentationToSurfaceForAllActors (); diff --git a/visualization/src/common/shapes.cpp b/visualization/src/common/shapes.cpp index 445db9f555a..8893ea96d4e 100644 --- a/visualization/src/common/shapes.cpp +++ b/visualization/src/common/shapes.cpp @@ -47,6 +47,8 @@ #include #include #include +#include +#include //////////////////////////////////////////////////////////////////////////////////////////// vtkSmartPointer @@ -304,6 +306,31 @@ pcl::visualization::createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4 return (line->GetOutput ()); } +////////////////////////////////////////////////////////////////////////////////////////////// +vtkSmartPointer +pcl::visualization::createEllipsoid (const Eigen::Isometry3d &transform, + double radius_x, double radius_y, double radius_z) +{ + const vtkSmartPointer t = vtkSmartPointer::New (); + const Eigen::Matrix4d trMatrix = transform.matrix ().transpose (); // Eigen is col-major while vtk is row-major, so transpose it. + t->SetMatrix (trMatrix.data ()); + + vtkSmartPointer ellipsoid = vtkSmartPointer::New (); + ellipsoid->SetXRadius (radius_x); + ellipsoid->SetYRadius (radius_y); + ellipsoid->SetZRadius (radius_z); + + vtkSmartPointer s_ellipsoid = vtkSmartPointer::New (); + s_ellipsoid->SetParametricFunction (ellipsoid); + + vtkSmartPointer tf = vtkSmartPointer::New (); + tf->SetTransform (t); + tf->SetInputConnection (s_ellipsoid->GetOutputPort ()); + tf->Update (); + + return (tf->GetOutput ()); +} + ////////////////////////////////////////////////////////////////////////////////////////////// void pcl::visualization::allocVtkUnstructuredGrid (vtkSmartPointer &polydata) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 79b3d12263a..0a110ee5763 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -2435,6 +2435,34 @@ pcl::visualization::PCLVisualizer::addCube (float x_min, float x_max, return (true); } +//////////////////////////////////////////////////////////////////////////////////////////// +bool +pcl::visualization::PCLVisualizer::addEllipsoid ( + const Eigen::Isometry3d &transform, + double radius_x, double radius_y, double radius_z, + const std::string &id, int viewport) +{ + // Check to see if this ID entry already exists (has it been already added to the visualizer?) + ShapeActorMap::iterator am_it = shape_actor_map_->find (id); + if (am_it != shape_actor_map_->end ()) + { + pcl::console::print_warn (stderr, "[addEllipsoid] A shape with id <%s> already exists! Please choose a different id and retry.\n", id.c_str ()); + return (false); + } + + vtkSmartPointer data = createEllipsoid (transform, radius_x, radius_y, radius_z); + + // Create an Actor + vtkSmartPointer actor; + createActorFromVTKDataSet (data, actor); + actor->GetProperty ()->SetRepresentationToSurface (); + addActorToRenderer (actor, viewport); + + // Save the pointer/ID pair to the global actor map + (*shape_actor_map_)[id] = actor; + return (true); +} + //////////////////////////////////////////////////////////////////////////////////////////// bool pcl::visualization::PCLVisualizer::addSphere (const pcl::ModelCoefficients &coefficients, From 2c8053fae97d950ff9fdec8729f1d2bb0e0dde25 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Wed, 10 Mar 2021 11:55:31 +0530 Subject: [PATCH 032/123] Move the init of static variables to library load time Added header for `array`, newly added in this PR Move the LUT for sRGB and XYZ to common, Also utilize them in gicp6d and SHOT --- common/include/pcl/common/colors.h | 86 ++++++++++++++++++++- features/include/pcl/features/impl/shot.hpp | 34 ++------ features/include/pcl/features/shot.h | 7 +- registration/src/gicp6d.cpp | 66 +++++----------- 4 files changed, 115 insertions(+), 78 deletions(-) diff --git a/common/include/pcl/common/colors.h b/common/include/pcl/common/colors.h index 5490c06bb52..34fb86d8170 100644 --- a/common/include/pcl/common/colors.h +++ b/common/include/pcl/common/colors.h @@ -40,6 +40,8 @@ #include #include +#include // for is_floating_point + namespace pcl { @@ -83,4 +85,86 @@ namespace pcl using GlasbeyLUT = ColorLUT; using ViridisLUT = ColorLUT; -} + /** + * @brief Returns a Look-Up Table useful in converting RGB to sRGB + * @tparam T floating point type with resultant value + * @tparam bits depth of RGB + * @return 1-D LUT for converting R, G or B into Rs, Gs or Bs + * @remarks sRGB was proposed by Stokes et al. as a uniform default color + * space for the internet + * M. Stokes, M. Anderson, S. Chandrasekar, and R. Motta: A standard default colorspace for the internet - sRGB (Nov 1996) + * IEC 61966-2.1 Default RGB Colour Space - sRGB (International Electrotechnical Commission, Geneva, Switzerland, 1999) + * www.srgb.com, www.color.org/srgb.html + */ + template + inline std::array + RGB2sRGB_LUT() noexcept + { + static_assert(std::is_floating_point::value, "LUT value must be a floating point"); + + constexpr std::size_t size = 1 << bits; + + static const std::array sRGB_LUT = [&]() { + std::array LUT; + for (std::size_t i = 0; i < size; ++i) { + T f = static_cast(i) / static_cast(size - 1); + if (f > 0.04045) { + // ((f + 0.055)/1.055)^2.4 + LUT[i] = static_cast( + std::pow((f + static_cast(0.055)) / static_cast(1.055), + static_cast(2.4))); + } + else { + // f / 12.92 + LUT[i] = f / static_cast(12.92); + } + } + return LUT; + }(); + return sRGB_LUT; + } + + /** + * @brief Returns a Look-Up Table useful in converting scaled CIE XYZ into CIE L*a*b* + * @details The function assumes that the XYZ values are + * * not normalized using reference illuminant + * * scaled such that reference illuminant has Xn = Yn = Zn = discretizations + * @tparam T floating point type with resultant value + * @tparam discretizations number of levels for the LUT + * @return 1-D LUT with results of f(X/Xn) + * @note This function doesn't convert from CIE XYZ to CIE L*a*b*. The actual conversion + * is as follows: + * L* = 116 * [f(Y/Yn) - 16/116] + * a* = 500 * [f(X/Xn) - f(Y/Yn)] + * b* = 200 * [f(Y/Yn) - f(Z/Zn)] + * Where, Xn, Yn and Zn are values of the reference illuminant (at prescribed angle) + * f is appropriate function such that L* = 100, a* = b* = 0 for white color + * Reference: Billmeyer and Saltzman’s Principles of Color Technology + */ + template + inline const std::array& + XYZ2LAB_LUT() noexcept + { + static_assert(std::is_floating_point::value, "LUT value must be a floating point"); + + constexpr std::size_t size = discretizations; + + static const std::array f_LUT = [&]() { + std::array LUT; + for (std::size_t i = 0; i < size; ++i) { + T f = static_cast(i) / static_cast(size); + if (f > static_cast(0.008856)) { + // f^(1/3) + LUT[i] = static_cast(std::pow(f, (static_cast(1) / static_cast(3)))); + } + else { + // 7.87 * f + 16/116 + LUT[i] = + static_cast(7.87) * f + (static_cast(16) / static_cast(116)); + } + } + return LUT; + }(); + return f_LUT; + } +} // namespace pcl diff --git a/features/include/pcl/features/impl/shot.hpp b/features/include/pcl/features/impl/shot.hpp index 297a55a40de..73a50e004cf 100644 --- a/features/include/pcl/features/impl/shot.hpp +++ b/features/include/pcl/features/impl/shot.hpp @@ -43,6 +43,8 @@ #include #include +#include // for RGB2sRGB_LUT, XYZ2LAB_LUT + // Useful constants. #define PST_PI 3.1415926535897932384626433832795 #define PST_RAD_45 0.78539816339744830961566084581988 @@ -84,12 +86,14 @@ areEquals (float val1, float val2, float zeroFloatEps = zeroFloatEps8) } ////////////////////////////////////////////////////////////////////////////////////////////// -template float -pcl::SHOTColorEstimation::sRGB_LUT[256] = {- 1}; +template +std::array + pcl::SHOTColorEstimation::sRGB_LUT = pcl::RGB2sRGB_LUT(); ////////////////////////////////////////////////////////////////////////////////////////////// -template float -pcl::SHOTColorEstimation::sXYZ_LUT[4000] = {- 1}; +template +std::array + pcl::SHOTColorEstimation::sXYZ_LUT = pcl::XYZ2LAB_LUT(); ////////////////////////////////////////////////////////////////////////////////////////////// template void @@ -97,28 +101,6 @@ pcl::SHOTColorEstimation::RGB2CIELAB (un unsigned char B, float &L, float &A, float &B2) { - // @TODO: C++17 supports constexpr lambda for compile time init - if (sRGB_LUT[0] < 0) - { - for (int i = 0; i < 256; i++) - { - float f = static_cast (i) / 255.0f; - if (f > 0.04045) - sRGB_LUT[i] = powf ((f + 0.055f) / 1.055f, 2.4f); - else - sRGB_LUT[i] = f / 12.92f; - } - - for (int i = 0; i < 4000; i++) - { - float f = static_cast (i) / 4000.0f; - if (f > 0.008856) - sXYZ_LUT[i] = static_cast (powf (f, 0.3333f)); - else - sXYZ_LUT[i] = static_cast((7.787 * f) + (16.0 / 116.0)); - } - } - float fr = sRGB_LUT[R]; float fg = sRGB_LUT[G]; float fb = sRGB_LUT[B]; diff --git a/features/include/pcl/features/shot.h b/features/include/pcl/features/shot.h index 24041664c3a..0e3581febb2 100644 --- a/features/include/pcl/features/shot.h +++ b/features/include/pcl/features/shot.h @@ -42,6 +42,8 @@ #include #include +#include // for sRGB_LUT, sXYZ_LUT + namespace pcl { /** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for @@ -98,7 +100,6 @@ namespace pcl { feature_name_ = "SHOTEstimation"; }; - public: @@ -400,8 +401,8 @@ namespace pcl static void RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2); - static float sRGB_LUT[256]; - static float sXYZ_LUT[4000]; + static std::array sRGB_LUT; + static std::array sXYZ_LUT; }; } diff --git a/registration/src/gicp6d.cpp b/registration/src/gicp6d.cpp index b3a4f5db033..1b5a30a0f7a 100644 --- a/registration/src/gicp6d.cpp +++ b/registration/src/gicp6d.cpp @@ -36,6 +36,7 @@ * */ +#include // for RGB2sRGB_LUT, XYZ2LAB_LUT #include #include // for pcl::make_shared @@ -47,59 +48,28 @@ RGB2Lab(const Eigen::Vector3i& colorRGB) // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2 // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7 - double R, G, B, X, Y, Z; + const auto& sRGB_LUT = RGB2sRGB_LUT(); + const auto& XYZ_LUT = XYZ2LAB_LUT(); - // map sRGB values to [0, 1] - R = colorRGB[0] / 255.0; - G = colorRGB[1] / 255.0; - B = colorRGB[2] / 255.0; + const double R = sRGB_LUT[colorRGB[0]]; + const double G = sRGB_LUT[colorRGB[1]]; + const double B = sRGB_LUT[colorRGB[2]]; - // linearize sRGB values - if (R > 0.04045) - R = pow((R + 0.055) / 1.055, 2.4); - else - R /= 12.92; + // linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees + double X = R * 0.4124 + G * 0.3576 + B * 0.1805; + double Y = R * 0.2126 + G * 0.7152 + B * 0.0722; + double Z = R * 0.0193 + G * 0.1192 + B * 0.9505; - if (G > 0.04045) - G = pow((G + 0.055) / 1.055, 2.4); - else - G /= 12.92; - - if (B > 0.04045) - B = pow((B + 0.055) / 1.055, 2.4); - else - B /= 12.92; - - // postponed: - // R *= 100.0; - // G *= 100.0; - // B *= 100.0; - - // linear sRGB -> CIEXYZ - X = R * 0.4124 + G * 0.3576 + B * 0.1805; - Y = R * 0.2126 + G * 0.7152 + B * 0.0722; - Z = R * 0.0193 + G * 0.1192 + B * 0.9505; - - // *= 100.0 including: - X /= 0.95047; // 95.047; - // Y /= 1;//100.000; - Z /= 1.08883; // 108.883; + // normalize X, Y, Z with tristimulus values for Xn, Yn, Zn + // and scale for using the LUT with 4000 steps + X = (X / 0.95047) * 4000; + Y = (Y / 1) * 4000; + Z = (Z / 1.08883) * 4000; // CIEXYZ -> CIELAB - if (X > 0.008856) - X = pow(X, 1.0 / 3.0); - else - X = 7.787 * X + 16.0 / 116.0; - - if (Y > 0.008856) - Y = pow(Y, 1.0 / 3.0); - else - Y = 7.787 * Y + 16.0 / 116.0; - - if (Z > 0.008856) - Z = pow(Z, 1.0 / 3.0); - else - Z = 7.787 * Z + 16.0 / 116.0; + X = XYZ_LUT[static_cast(X)]; + Y = XYZ_LUT[static_cast(Y)]; + Z = XYZ_LUT[static_cast(Z)]; Eigen::Vector3f colorLab; colorLab[0] = static_cast(116.0 * Y - 16.0); From 22831c9a05ddda83cb8d18c1f7033423058b0676 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Sun, 14 Mar 2021 08:02:03 +0530 Subject: [PATCH 033/123] Here's hoping one of this makes MSVC happier --- common/include/pcl/common/colors.h | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/common/include/pcl/common/colors.h b/common/include/pcl/common/colors.h index 34fb86d8170..50599a7a402 100644 --- a/common/include/pcl/common/colors.h +++ b/common/include/pcl/common/colors.h @@ -97,15 +97,16 @@ namespace pcl * www.srgb.com, www.color.org/srgb.html */ template - inline std::array + PCL_EXPORTS inline std::array RGB2sRGB_LUT() noexcept { static_assert(std::is_floating_point::value, "LUT value must be a floating point"); - constexpr std::size_t size = 1 << bits; + constexpr const std::size_t size = 1 << bits; - static const std::array sRGB_LUT = [&]() { - std::array LUT; + static const auto sRGB_LUT = [&]() { + // MSVC wouldn't take `size` here instead of the expression + std::array LUT; for (std::size_t i = 0; i < size; ++i) { T f = static_cast(i) / static_cast(size - 1); if (f > 0.04045) { @@ -142,17 +143,15 @@ namespace pcl * Reference: Billmeyer and Saltzman’s Principles of Color Technology */ template - inline const std::array& + PCL_EXPORTS inline const std::array& XYZ2LAB_LUT() noexcept { static_assert(std::is_floating_point::value, "LUT value must be a floating point"); - constexpr std::size_t size = discretizations; - - static const std::array f_LUT = [&]() { - std::array LUT; - for (std::size_t i = 0; i < size; ++i) { - T f = static_cast(i) / static_cast(size); + static const auto f_LUT = [&]() { + std::array LUT; + for (std::size_t i = 0; i < discretizations; ++i) { + T f = static_cast(i) / static_cast(discretizations); if (f > static_cast(0.008856)) { // f^(1/3) LUT[i] = static_cast(std::pow(f, (static_cast(1) / static_cast(3)))); From 400a4ec6b60a8a917716a7e4ab7df55b6a987289 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Tue, 16 Mar 2021 08:13:54 +0530 Subject: [PATCH 034/123] Minor rewrite to use the new LUT for RGB Not used for XYZ due to windows getting low accuracy with LUT --- registration/src/gicp6d.cpp | 33 +++++++++++++++++++-------------- 1 file changed, 19 insertions(+), 14 deletions(-) diff --git a/registration/src/gicp6d.cpp b/registration/src/gicp6d.cpp index 1b5a30a0f7a..27afd8ccab4 100644 --- a/registration/src/gicp6d.cpp +++ b/registration/src/gicp6d.cpp @@ -47,34 +47,39 @@ RGB2Lab(const Eigen::Vector3i& colorRGB) { // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2 // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7 + // an overview at: https://www.comp.nus.edu.sg/~leowwk/papers/colordiff.pdf const auto& sRGB_LUT = RGB2sRGB_LUT(); - const auto& XYZ_LUT = XYZ2LAB_LUT(); const double R = sRGB_LUT[colorRGB[0]]; const double G = sRGB_LUT[colorRGB[1]]; const double B = sRGB_LUT[colorRGB[2]]; // linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees - double X = R * 0.4124 + G * 0.3576 + B * 0.1805; - double Y = R * 0.2126 + G * 0.7152 + B * 0.0722; - double Z = R * 0.0193 + G * 0.1192 + B * 0.9505; + const double X = R * 0.4124 + G * 0.3576 + B * 0.1805; + const double Y = R * 0.2126 + G * 0.7152 + B * 0.0722; + const double Z = R * 0.0193 + G * 0.1192 + B * 0.9505; // normalize X, Y, Z with tristimulus values for Xn, Yn, Zn - // and scale for using the LUT with 4000 steps - X = (X / 0.95047) * 4000; - Y = (Y / 1) * 4000; - Z = (Z / 1.08883) * 4000; + float f[3] = {static_cast(X), static_cast(Y), static_cast(Z)}; + f[0] /= 0.95047; + f[1] /= 1; + f[2] /= 1.08883; // CIEXYZ -> CIELAB - X = XYZ_LUT[static_cast(X)]; - Y = XYZ_LUT[static_cast(Y)]; - Z = XYZ_LUT[static_cast(Z)]; + for (int i = 0; i < 3; ++i) { + if (f[i] > 0.008856) { + f[i] = std::pow(f[i], 1.0 / 3.0); + } + else { + f[i] = 7.787 * f[i] + 16.0 / 116.0; + } + } Eigen::Vector3f colorLab; - colorLab[0] = static_cast(116.0 * Y - 16.0); - colorLab[1] = static_cast(500.0 * (X - Y)); - colorLab[2] = static_cast(200.0 * (Y - Z)); + colorLab[0] = 116.0f * f[1] - 16.0f; + colorLab[1] = 500.0f * (f[0] - f[1]); + colorLab[2] = 200.0f * (f[1] - f[2]); return colorLab; } From fcc948a10d1fe653fb93f4274c155fa38a4b14fe Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 9 Apr 2021 09:38:46 +0200 Subject: [PATCH 035/123] [CMake] Add AVX for windows (#4598) * Add AVX for windows * Update cmake/pcl_find_avx.cmake Co-authored-by: SunBlack --- CMakeLists.txt | 8 +++++++- cmake/pcl_find_avx.cmake | 41 ++++++++++++++++++++++++++++++++++++++++ cmake/pcl_options.cmake | 6 ++++++ 3 files changed, 54 insertions(+), 1 deletion(-) create mode 100644 cmake/pcl_find_avx.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 9997b151655..f4de5856f82 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -90,6 +90,12 @@ if(PCL_ENABLE_SSE AND "${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}" PCL_CHECK_FOR_SSE() endif() +# check for AVX flags for windows +if(PCL_ENABLE_AVX AND "${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") + include("${PCL_SOURCE_DIR}/cmake/pcl_find_avx.cmake") + PCL_CHECK_FOR_AVX() +endif() + # ---[ Unix/Darwin/Windows specific flags if(CMAKE_COMPILER_IS_GNUCXX) if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") @@ -127,7 +133,7 @@ if(CMAKE_COMPILER_IS_MSVC) add_compile_options(/bigobj) if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") - string(APPEND CMAKE_CXX_FLAGS " /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS_STR}") + string(APPEND CMAKE_CXX_FLAGS " /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS_STR} ${AVX_FLAGS}") # Add extra code generation/link optimizations if(CMAKE_MSVC_CODE_LINK_OPTIMIZATION AND (NOT BUILD_CUDA) AND (NOT BUILD_GPU)) diff --git a/cmake/pcl_find_avx.cmake b/cmake/pcl_find_avx.cmake new file mode 100644 index 00000000000..d3187ea70e4 --- /dev/null +++ b/cmake/pcl_find_avx.cmake @@ -0,0 +1,41 @@ +############################################################################### +# Check for the presence of AVX and figure out the flags to use for it. +function(PCL_CHECK_FOR_AVX) + set(AVX_FLAGS) + + include(CheckCXXSourceRuns) + + check_cxx_source_runs(" + #include + int main() + { + __m256i a = {0}; + a = _mm256_abs_epi16(a); + return 0; + }" + HAVE_AVX2) + + if(NOT HAVE_AVX2) + check_cxx_source_runs(" + #include + int main() + { + __m256 a; + a = _mm256_set1_ps(0); + return 0; + }" + HAVE_AVX) + endif() + +# Setting the /arch defines __AVX(2)__, see here https://docs.microsoft.com/en-us/cpp/build/reference/arch-x64?view=msvc-160 +# AVX2 extends and includes AVX. +# Setting these defines allows the compiler to use AVX instructions as well as code guarded with the defines. +# TODO: Add AVX512 variant if needed. + if(MSVC) + if(HAVE_AVX2) + set(AVX_FLAGS "/arch:AVX2" PARENT_SCOPE) + elseif(HAVE_AVX) + set(AVX_FLAGS "/arch:AVX" PARENT_SCOPE) + endif() + endif() +endfunction() diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index b8e023486f2..c8d0a6506dc 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -44,6 +44,12 @@ mark_as_advanced(PCL_NO_PRECOMPILE) option(PCL_ENABLE_SSE "Enable or Disable SSE optimizations." ON) mark_as_advanced(PCL_ENABLE_SSE) +if(WIN32) + # Enable or Disable the check for AVX optimizations + option(PCL_ENABLE_AVX "Enable or Disable AVX optimizations." ON) + mark_as_advanced(PCL_ENABLE_AVX) +endif() + # Allow the user to enable compiler cache option(PCL_ENABLE_CCACHE "Enable using compiler cache for compilation" OFF) mark_as_advanced(PCL_ENABLE_CCACHE) From f8df44487c8c8105d0bd9e049e0b3df979f602c3 Mon Sep 17 00:00:00 2001 From: Yan Hang Date: Sat, 10 Apr 2021 22:52:51 +0800 Subject: [PATCH 036/123] removed md files from docs-pipeline.yaml Those md files are not part of the documentation, so no need for trigger. --- .ci/azure-pipelines/docs-pipeline.yaml | 3 --- 1 file changed, 3 deletions(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index c31ed8f26e8..4121c13f3d7 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -2,9 +2,6 @@ trigger: paths: include: - doc - - README.md - - CHANGES.md - - CONTRIBUTING.md pr: paths: From 30294b9e810eb35a30830760a607f564fe4d8c42 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 9 Apr 2021 21:31:39 +0200 Subject: [PATCH 037/123] Enable more warnings on tutorial CI --- .ci/scripts/build_tutorials.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.ci/scripts/build_tutorials.sh b/.ci/scripts/build_tutorials.sh index 169128ec943..c26d02d974e 100755 --- a/.ci/scripts/build_tutorials.sh +++ b/.ci/scripts/build_tutorials.sh @@ -73,7 +73,7 @@ for DIRECTORY in "$SOURCE_DIR"/*/ ; do TUTORIAL_BUILD_DIR="$BUILD_DIR/$NAME" mkdir -p "$TUTORIAL_BUILD_DIR" && cd "$TUTORIAL_BUILD_DIR" || exit echo "Configuring tutorial: $NAME" - if ! cmake "$TUTORIAL_SOURCE_DIR" -DPCL_DIR="$INSTALL_DIR" -DCMAKE_CXX_FLAGS="-Werror"; then + if ! cmake "$TUTORIAL_SOURCE_DIR" -DPCL_DIR="$INSTALL_DIR" -DCMAKE_CXX_FLAGS="-Wall -Wextra -Wpedantic -Werror"; then STATUS="cmake error" else echo "Building tutorial: $NAME" From e6dd586eeb8a0c177d4a6084db51ee837146754f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 10:53:53 +0200 Subject: [PATCH 038/123] Remove unused argc, argv in tutorials --- doc/tutorials/content/sources/bare_earth/bare_earth.cpp | 2 +- .../content/sources/concatenate_fields/concatenate_fields.cpp | 2 +- .../content/sources/concatenate_points/concatenate_points.cpp | 2 +- .../content/sources/concave_hull_2d/concave_hull_2d.cpp | 2 +- .../conditional_euclidean_clustering.cpp | 2 +- .../sources/conditional_removal/conditional_removal.cpp | 2 +- .../content/sources/convex_hull_2d/convex_hull_2d.cpp | 2 +- .../sources/cylinder_segmentation/cylinder_segmentation.cpp | 2 +- .../content/sources/extract_indices/extract_indices.cpp | 2 +- .../content/sources/function_filter/sphere_removal.cpp | 2 +- .../content/sources/greedy_projection/greedy_projection.cpp | 2 +- .../iterative_closest_point/iterative_closest_point.cpp | 2 +- doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp | 2 +- .../sources/min_cut_segmentation/min_cut_segmentation.cpp | 4 ++-- .../normal_distributions_transform.cpp | 2 +- .../octree_change_detection/octree_change_detection.cpp | 2 +- doc/tutorials/content/sources/octree_search/octree_search.cpp | 2 +- doc/tutorials/content/sources/passthrough/passthrough.cpp | 2 +- doc/tutorials/content/sources/pcd_read/pcd_read.cpp | 2 +- doc/tutorials/content/sources/pcd_write/pcd_write.cpp | 2 +- .../content/sources/pcl_painter2D/pcl_painter2D_demo.cpp | 4 ++-- .../content/sources/pcl_plotter/pcl_plotter_demo.cpp | 2 +- .../sources/planar_segmentation/planar_segmentation.cpp | 2 +- .../point_cloud_compression/point_cloud_compression.cpp | 2 +- .../content/sources/project_inliers/project_inliers.cpp | 2 +- .../sources/radius_outlier_removal/radius_outlier_removal.cpp | 2 +- .../sources/range_image_creation/range_image_creation.cpp | 2 +- .../region_growing_rgb_segmentation.cpp | 2 +- .../region_growing_segmentation.cpp | 2 +- doc/tutorials/content/sources/resampling/resampling.cpp | 2 +- .../sources/statistical_removal/statistical_removal.cpp | 4 ++-- doc/tutorials/content/sources/voxel_grid/voxel_grid.cpp | 2 +- 32 files changed, 35 insertions(+), 35 deletions(-) diff --git a/doc/tutorials/content/sources/bare_earth/bare_earth.cpp b/doc/tutorials/content/sources/bare_earth/bare_earth.cpp index c09f49b08b1..c977407907e 100644 --- a/doc/tutorials/content/sources/bare_earth/bare_earth.cpp +++ b/doc/tutorials/content/sources/bare_earth/bare_earth.cpp @@ -5,7 +5,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/concatenate_fields/concatenate_fields.cpp b/doc/tutorials/content/sources/concatenate_fields/concatenate_fields.cpp index 8768aec32c1..74a3a4ab65f 100644 --- a/doc/tutorials/content/sources/concatenate_fields/concatenate_fields.cpp +++ b/doc/tutorials/content/sources/concatenate_fields/concatenate_fields.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud cloud_a; pcl::PointCloud cloud_b; diff --git a/doc/tutorials/content/sources/concatenate_points/concatenate_points.cpp b/doc/tutorials/content/sources/concatenate_points/concatenate_points.cpp index e3912109ed3..e0b7a1064b3 100644 --- a/doc/tutorials/content/sources/concatenate_points/concatenate_points.cpp +++ b/doc/tutorials/content/sources/concatenate_points/concatenate_points.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud cloud_a, cloud_b, cloud_c; diff --git a/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp b/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp index 828e904ffbf..9293d61a0a5 100644 --- a/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp +++ b/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp @@ -9,7 +9,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud), cloud_filtered (new pcl::PointCloud), diff --git a/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp b/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp index b2dcb748bf0..ee1a827e1c6 100644 --- a/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp +++ b/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp @@ -49,7 +49,7 @@ customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, } int -main (int argc, char** argv) +main () { // Data containers used pcl::PointCloud::Ptr cloud_in (new pcl::PointCloud), cloud_out (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/conditional_removal/conditional_removal.cpp b/doc/tutorials/content/sources/conditional_removal/conditional_removal.cpp index 7eb6dc35269..9b2a81c6776 100644 --- a/doc/tutorials/content/sources/conditional_removal/conditional_removal.cpp +++ b/doc/tutorials/content/sources/conditional_removal/conditional_removal.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp b/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp index ca9af729ee3..b2118533421 100644 --- a/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp +++ b/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp @@ -9,7 +9,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud), cloud_filtered (new pcl::PointCloud), cloud_projected (new pcl::PointCloud); pcl::PCDReader reader; diff --git a/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp b/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp index 703d8763693..1c2f7a4b2ff 100644 --- a/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp +++ b/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp @@ -11,7 +11,7 @@ typedef pcl::PointXYZ PointT; int -main (int argc, char** argv) +main () { // All the objects needed pcl::PCDReader reader; diff --git a/doc/tutorials/content/sources/extract_indices/extract_indices.cpp b/doc/tutorials/content/sources/extract_indices/extract_indices.cpp index 993f31b492c..ee4bc6be2db 100644 --- a/doc/tutorials/content/sources/extract_indices/extract_indices.cpp +++ b/doc/tutorials/content/sources/extract_indices/extract_indices.cpp @@ -9,7 +9,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PCLPointCloud2::Ptr cloud_blob (new pcl::PCLPointCloud2), cloud_filtered_blob (new pcl::PCLPointCloud2); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud), cloud_p (new pcl::PointCloud), cloud_f (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/function_filter/sphere_removal.cpp b/doc/tutorials/content/sources/function_filter/sphere_removal.cpp index 858d28e44fe..1362c80d600 100644 --- a/doc/tutorials/content/sources/function_filter/sphere_removal.cpp +++ b/doc/tutorials/content/sources/function_filter/sphere_removal.cpp @@ -5,7 +5,7 @@ #include int -main(int argc, char** argv) +main() { using XYZCloud = pcl::PointCloud; const auto cloud = pcl::make_shared(); diff --git a/doc/tutorials/content/sources/greedy_projection/greedy_projection.cpp b/doc/tutorials/content/sources/greedy_projection/greedy_projection.cpp index 17df0e1400f..a0403c61ae8 100644 --- a/doc/tutorials/content/sources/greedy_projection/greedy_projection.cpp +++ b/doc/tutorials/content/sources/greedy_projection/greedy_projection.cpp @@ -5,7 +5,7 @@ #include int -main (int argc, char** argv) +main () { // Load input file into a PointCloud with an appropriate type pcl::PointCloud::Ptr cloud (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp b/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp index 06cffa96eb1..d45ab78c837 100644 --- a/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp +++ b/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp @@ -4,7 +4,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud_in (new pcl::PointCloud(5,1)); pcl::PointCloud::Ptr cloud_out (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp b/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp index e704c9cc65c..d2b99cfa2ef 100644 --- a/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp +++ b/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp @@ -6,7 +6,7 @@ #include int -main (int argc, char** argv) +main () { srand (time (NULL)); diff --git a/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp b/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp index 31ce6979cfc..c3b23a3f378 100644 --- a/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp +++ b/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp @@ -6,7 +6,7 @@ #include #include -int main (int argc, char** argv) +int main () { pcl::PointCloud ::Ptr cloud (new pcl::PointCloud ); if ( pcl::io::loadPCDFile ("min_cut_segmentation_tutorial.pcd", *cloud) == -1 ) @@ -52,4 +52,4 @@ int main (int argc, char** argv) } return (0); -} \ No newline at end of file +} diff --git a/doc/tutorials/content/sources/normal_distributions_transform/normal_distributions_transform.cpp b/doc/tutorials/content/sources/normal_distributions_transform/normal_distributions_transform.cpp index 24938193ab8..b5a525d25da 100644 --- a/doc/tutorials/content/sources/normal_distributions_transform/normal_distributions_transform.cpp +++ b/doc/tutorials/content/sources/normal_distributions_transform/normal_distributions_transform.cpp @@ -12,7 +12,7 @@ using namespace std::chrono_literals; int -main (int argc, char** argv) +main () { // Loading first scan of room. pcl::PointCloud::Ptr target_cloud (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/octree_change_detection/octree_change_detection.cpp b/doc/tutorials/content/sources/octree_change_detection/octree_change_detection.cpp index 16aeef1c8cc..6f48ba3af96 100644 --- a/doc/tutorials/content/sources/octree_change_detection/octree_change_detection.cpp +++ b/doc/tutorials/content/sources/octree_change_detection/octree_change_detection.cpp @@ -6,7 +6,7 @@ #include int -main (int argc, char** argv) +main () { srand ((unsigned int) time (NULL)); diff --git a/doc/tutorials/content/sources/octree_search/octree_search.cpp b/doc/tutorials/content/sources/octree_search/octree_search.cpp index a37daad2fb0..6b49d22c5d5 100644 --- a/doc/tutorials/content/sources/octree_search/octree_search.cpp +++ b/doc/tutorials/content/sources/octree_search/octree_search.cpp @@ -6,7 +6,7 @@ #include int -main (int argc, char** argv) +main () { srand ((unsigned int) time (NULL)); diff --git a/doc/tutorials/content/sources/passthrough/passthrough.cpp b/doc/tutorials/content/sources/passthrough/passthrough.cpp index 98ec9b9c48d..b942ec6177c 100644 --- a/doc/tutorials/content/sources/passthrough/passthrough.cpp +++ b/doc/tutorials/content/sources/passthrough/passthrough.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/pcd_read/pcd_read.cpp b/doc/tutorials/content/sources/pcd_read/pcd_read.cpp index 0d92382925e..2b41d3d5019 100644 --- a/doc/tutorials/content/sources/pcd_read/pcd_read.cpp +++ b/doc/tutorials/content/sources/pcd_read/pcd_read.cpp @@ -3,7 +3,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/pcd_write/pcd_write.cpp b/doc/tutorials/content/sources/pcd_write/pcd_write.cpp index dd5638b559f..f42098871c6 100644 --- a/doc/tutorials/content/sources/pcd_write/pcd_write.cpp +++ b/doc/tutorials/content/sources/pcd_write/pcd_write.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud cloud; diff --git a/doc/tutorials/content/sources/pcl_painter2D/pcl_painter2D_demo.cpp b/doc/tutorials/content/sources/pcl_painter2D/pcl_painter2D_demo.cpp index 55082baa90d..9e578a4e323 100644 --- a/doc/tutorials/content/sources/pcl_painter2D/pcl_painter2D_demo.cpp +++ b/doc/tutorials/content/sources/pcl_painter2D/pcl_painter2D_demo.cpp @@ -6,7 +6,7 @@ #include //---------------------------------------------------------------------------- -int main (int argc, char * argv []) +int main () { pcl::visualization::PCLPainter2D *painter = new pcl::visualization::PCLPainter2D(); @@ -47,4 +47,4 @@ int main (int argc, char * argv []) return 0; -} \ No newline at end of file +} diff --git a/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp b/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp index aa832223b02..d1e173abba3 100644 --- a/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp +++ b/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp @@ -39,7 +39,7 @@ identity (double val) //............................................................................ int -main (int argc, char * argv []) +main () { //defining a plotter PCLPlotter *plotter = new PCLPlotter ("My Plotter"); diff --git a/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp b/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp index 07e6f8f0864..45cf0d5a698 100644 --- a/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp +++ b/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp @@ -7,7 +7,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud(new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/point_cloud_compression/point_cloud_compression.cpp b/doc/tutorials/content/sources/point_cloud_compression/point_cloud_compression.cpp index 0c1f9350475..7621752c5eb 100644 --- a/doc/tutorials/content/sources/point_cloud_compression/point_cloud_compression.cpp +++ b/doc/tutorials/content/sources/point_cloud_compression/point_cloud_compression.cpp @@ -90,7 +90,7 @@ class SimpleOpenNIViewer }; int -main (int argc, char **argv) +main () { SimpleOpenNIViewer v; v.run (); diff --git a/doc/tutorials/content/sources/project_inliers/project_inliers.cpp b/doc/tutorials/content/sources/project_inliers/project_inliers.cpp index b4d373d7965..325a271d759 100644 --- a/doc/tutorials/content/sources/project_inliers/project_inliers.cpp +++ b/doc/tutorials/content/sources/project_inliers/project_inliers.cpp @@ -5,7 +5,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_projected (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/radius_outlier_removal/radius_outlier_removal.cpp b/doc/tutorials/content/sources/radius_outlier_removal/radius_outlier_removal.cpp index 6093fcdda4a..64bdaea0622 100644 --- a/doc/tutorials/content/sources/radius_outlier_removal/radius_outlier_removal.cpp +++ b/doc/tutorials/content/sources/radius_outlier_removal/radius_outlier_removal.cpp @@ -3,7 +3,7 @@ #include int - main (int argc, char** argv) + main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); diff --git a/doc/tutorials/content/sources/range_image_creation/range_image_creation.cpp b/doc/tutorials/content/sources/range_image_creation/range_image_creation.cpp index 8168cf1b9a2..a3d56ab13b1 100644 --- a/doc/tutorials/content/sources/range_image_creation/range_image_creation.cpp +++ b/doc/tutorials/content/sources/range_image_creation/range_image_creation.cpp @@ -1,6 +1,6 @@ #include -int main (int argc, char** argv) { +int main () { pcl::PointCloud pointCloud; // Generate the data diff --git a/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp b/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp index ba2db4119c8..1066d52a9e1 100644 --- a/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp +++ b/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp @@ -13,7 +13,7 @@ using namespace std::chrono_literals; int -main (int argc, char** argv) +main () { pcl::search::Search ::Ptr tree (new pcl::search::KdTree); diff --git a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp index 5b472eae133..61646d98be6 100644 --- a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp +++ b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp @@ -10,7 +10,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); if ( pcl::io::loadPCDFile ("region_growing_tutorial.pcd", *cloud) == -1) diff --git a/doc/tutorials/content/sources/resampling/resampling.cpp b/doc/tutorials/content/sources/resampling/resampling.cpp index 0efbca9c30b..a47cb6d1ad7 100644 --- a/doc/tutorials/content/sources/resampling/resampling.cpp +++ b/doc/tutorials/content/sources/resampling/resampling.cpp @@ -4,7 +4,7 @@ #include int -main (int argc, char** argv) +main () { // Load input file into a PointCloud with an appropriate type pcl::PointCloud::Ptr cloud (new pcl::PointCloud ()); diff --git a/doc/tutorials/content/sources/statistical_removal/statistical_removal.cpp b/doc/tutorials/content/sources/statistical_removal/statistical_removal.cpp index 8ccba826f40..98e5aebef3c 100644 --- a/doc/tutorials/content/sources/statistical_removal/statistical_removal.cpp +++ b/doc/tutorials/content/sources/statistical_removal/statistical_removal.cpp @@ -4,7 +4,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); @@ -35,4 +35,4 @@ main (int argc, char** argv) writer.write ("table_scene_lms400_outliers.pcd", *cloud_filtered, false); return (0); -} \ No newline at end of file +} diff --git a/doc/tutorials/content/sources/voxel_grid/voxel_grid.cpp b/doc/tutorials/content/sources/voxel_grid/voxel_grid.cpp index 95c52067408..a59feef7807 100644 --- a/doc/tutorials/content/sources/voxel_grid/voxel_grid.cpp +++ b/doc/tutorials/content/sources/voxel_grid/voxel_grid.cpp @@ -4,7 +4,7 @@ #include int -main (int argc, char** argv) +main () { pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2 ()); pcl::PCLPointCloud2::Ptr cloud_filtered (new pcl::PCLPointCloud2 ()); From a6252e2db7f3faee94825aaf589c78a59a32b448 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 10:57:40 +0200 Subject: [PATCH 039/123] Remove wrong additional loop in tutorial --- .../content/sources/planar_segmentation/planar_segmentation.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp b/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp index 45cf0d5a698..b78fcf97227 100644 --- a/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp +++ b/doc/tutorials/content/sources/planar_segmentation/planar_segmentation.cpp @@ -61,7 +61,6 @@ int << coefficients->values[3] << std::endl; std::cerr << "Model inliers: " << inliers->indices.size () << std::endl; - for (std::size_t i = 0; i < inliers->indices.size (); ++i) for (const auto& idx: inliers->indices) std::cerr << idx << " " << cloud->points[idx].x << " " << cloud->points[idx].y << " " From 815437a6fe68672064100f7b800c52912f04a98d Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 11:32:17 +0200 Subject: [PATCH 040/123] Solve sign-compare warnings in tutorials --- .../global_hypothesis_verification.cpp | 2 +- .../content/sources/iccv2011/src/correspondence_viewer.cpp | 2 +- doc/tutorials/content/sources/iccv2011/src/tutorial.cpp | 2 +- .../content/sources/iros2011/src/correspondence_viewer.cpp | 2 +- .../sources/model_outlier_removal/model_outlier_removal.cpp | 6 +++--- .../narf_descriptor_visualization.cpp | 2 +- .../random_sample_consensus/random_sample_consensus.cpp | 2 +- .../region_growing_segmentation.cpp | 2 +- doc/tutorials/content/sources/registration_api/example2.cpp | 4 ++-- 9 files changed, 12 insertions(+), 12 deletions(-) diff --git a/doc/tutorials/content/sources/global_hypothesis_verification/global_hypothesis_verification.cpp b/doc/tutorials/content/sources/global_hypothesis_verification/global_hypothesis_verification.cpp index 26225bf77cd..293a9b108ea 100644 --- a/doc/tutorials/content/sources/global_hypothesis_verification/global_hypothesis_verification.cpp +++ b/doc/tutorials/content/sources/global_hypothesis_verification/global_hypothesis_verification.cpp @@ -451,7 +451,7 @@ main (int argc, GoHv.verify (); GoHv.getMask (hypotheses_mask); // i-element TRUE if hvModels[i] verifies hypotheses - for (int i = 0; i < hypotheses_mask.size (); i++) + for (std::size_t i = 0; i < hypotheses_mask.size (); i++) { if (hypotheses_mask[i]) { diff --git a/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp b/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp index 40297cccfa3..3ba7056d215 100644 --- a/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp @@ -71,7 +71,7 @@ void visualize_correspondences (const PointCloudPtr points1, const PointCloudPtr keypoints1, const PointCloudPtr points2, const PointCloudPtr keypoints2, const std::vector &correspondences, - const std::vector &correspondence_scores, int max_to_display) + const std::vector &correspondence_scores, std::size_t max_to_display) { // We want to visualize two clouds side-by-side, so do to this, we'll make copies of the clouds and transform them // by shifting one to the left and the other to the right. Then we'll draw lines between the corresponding points diff --git a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp index a3570fa0198..616e8d440bb 100644 --- a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp @@ -310,7 +310,7 @@ void ICCVTutorial::filterCorrespondences () std::cout << "correspondence rejection..." << std::flush; std::vector > correspondences; for (unsigned cIdx = 0; cIdx < source2target_.size (); ++cIdx) - if (target2source_[source2target_[cIdx]] == cIdx) + if (static_cast(target2source_[source2target_[cIdx]]) == cIdx) correspondences.push_back(std::make_pair(cIdx, source2target_[cIdx])); correspondences_->resize (correspondences.size()); diff --git a/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp b/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp index 40297cccfa3..3ba7056d215 100644 --- a/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp +++ b/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp @@ -71,7 +71,7 @@ void visualize_correspondences (const PointCloudPtr points1, const PointCloudPtr keypoints1, const PointCloudPtr points2, const PointCloudPtr keypoints2, const std::vector &correspondences, - const std::vector &correspondence_scores, int max_to_display) + const std::vector &correspondence_scores, std::size_t max_to_display) { // We want to visualize two clouds side-by-side, so do to this, we'll make copies of the clouds and transform them // by shifting one to the left and the other to the right. Then we'll draw lines between the corresponding points diff --git a/doc/tutorials/content/sources/model_outlier_removal/model_outlier_removal.cpp b/doc/tutorials/content/sources/model_outlier_removal/model_outlier_removal.cpp index b7de1fed328..80735fade99 100644 --- a/doc/tutorials/content/sources/model_outlier_removal/model_outlier_removal.cpp +++ b/doc/tutorials/content/sources/model_outlier_removal/model_outlier_removal.cpp @@ -9,8 +9,8 @@ main () pcl::PointCloud::Ptr cloud_sphere_filtered (new pcl::PointCloud); // 1. Generate cloud data - int noise_size = 5; - int sphere_data_size = 10; + std::size_t noise_size = 5; + std::size_t sphere_data_size = 10; cloud->width = noise_size + sphere_data_size; cloud->height = 1; cloud->points.resize (cloud->width * cloud->height); @@ -24,7 +24,7 @@ main () // 1.2 Add sphere: double rand_x1 = 1; double rand_x2 = 1; - for (std::size_t i = noise_size; i < noise_size + sphere_data_size; ++i) + for (std::size_t i = noise_size; i < (noise_size + sphere_data_size); ++i) { // See: http://mathworld.wolfram.com/SpherePointPicking.html while (pow (rand_x1, 2) + pow (rand_x2, 2) >= 1) diff --git a/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp b/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp index 25200c3daeb..87ca778d0bb 100644 --- a/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp +++ b/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp @@ -120,7 +120,7 @@ main (int argc, char** argv) std::cout << "Now extracting NARFs in every image point.\n"; std::vector > narfs; narfs.resize (range_image.size ()); - int last_percentage=-1; + unsigned int last_percentage=0; for (unsigned int y=0; yheight = 1; cloud->is_dense = false; cloud->points.resize (cloud->width * cloud->height); - for (pcl::index_t i = 0; i < cloud->size (); ++i) + for (pcl::index_t i = 0; i < static_cast(cloud->size ()); ++i) { if (pcl::console::find_argument (argc, argv, "-s") >= 0 || pcl::console::find_argument (argc, argv, "-sf") >= 0) { diff --git a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp index 61646d98be6..2702b411036 100644 --- a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp +++ b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp @@ -52,7 +52,7 @@ main () std::cout << "First cluster has " << clusters[0].indices.size () << " points." << std::endl; std::cout << "These are the indices of the points of the initial" << std::endl << "cloud that belong to the first cluster:" << std::endl; - int counter = 0; + std::size_t counter = 0; while (counter < clusters[0].indices.size ()) { std::cout << clusters[0].indices[counter] << ", "; diff --git a/doc/tutorials/content/sources/registration_api/example2.cpp b/doc/tutorials/content/sources/registration_api/example2.cpp index fc70b24c632..18177a8e7e0 100644 --- a/doc/tutorials/content/sources/registration_api/example2.cpp +++ b/doc/tutorials/content/sources/registration_api/example2.cpp @@ -166,8 +166,8 @@ computeTransformation (const PointCloud::Ptr &src, // Reject correspondences based on their XYZ distance rejectBadCorrespondences (all_correspondences, keypoints_src, keypoints_tgt, *good_correspondences); - for (int i = 0; i < good_correspondences->size (); ++i) - std::cerr << good_correspondences->at (i) << std::endl; + for (const auto& corr : (*good_correspondences)) + std::cerr << corr << std::endl; // Obtain the best transformation between the two sets of keypoints given the remaining correspondences TransformationEstimationSVD trans_est; trans_est.estimateRigidTransformation (*keypoints_src, *keypoints_tgt, *good_correspondences, transform); From 301ce60cb2dbd9bff9dddef4cb0df7f0da0680a1 Mon Sep 17 00:00:00 2001 From: Yan Hang Date: Sun, 11 Apr 2021 03:42:30 +0800 Subject: [PATCH 041/123] fixed docs-pipeline.yaml removed md files from PR trigger, and added conditions for `documentation` and `tutorials` stages to make sure they run as expected. --- .ci/azure-pipelines/docs-pipeline.yaml | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index 4121c13f3d7..42fd82a6b1d 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -7,9 +7,6 @@ pr: paths: include: - doc - - README.md - - CHANGES.md - - CONTRIBUTING.md resources: pipelines: @@ -38,10 +35,12 @@ stages: - stage: documentation displayName: Documentation + condition: in(dependencies.formatting.result, 'Succeeded', 'SucceededWithIssues', 'Skipped') jobs: - template: documentation.yaml - stage: tutorials displayName: Tutorials + condition: in(dependencies.documentation.result, 'Succeeded', 'SucceededWithIssues') jobs: - template: tutorials.yaml From b3d77445a167a7f13fd754b9044e057fa3a919e4 Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Mon, 12 Apr 2021 22:09:45 +0300 Subject: [PATCH 042/123] =?UTF-8?q?replace=20uint32=5Ft=20to=20auto=20for?= =?UTF-8?q?=20Indices=20after=20@=C2=96mvieth=20proposition?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- filters/include/pcl/filters/impl/crop_hull.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/filters/include/pcl/filters/impl/crop_hull.hpp b/filters/include/pcl/filters/impl/crop_hull.hpp index 7b913ba6bf0..166b598e664 100644 --- a/filters/include/pcl/filters/impl/crop_hull.hpp +++ b/filters/include/pcl/filters/impl/crop_hull.hpp @@ -106,7 +106,7 @@ pcl::CropHull::getHullCloudRange () ); for (pcl::Vertices const & poly : hull_polygons_) { - for (std::uint32_t const & idx : poly.vertices) + for (auto const & idx : poly.vertices) { Eigen::Vector3f pt = (*hull_cloud_)[idx].getVector3fMap (); cloud_min = cloud_min.cwiseMin(pt); From cbc195cb9a52aa9f042867f470998f131242a20c Mon Sep 17 00:00:00 2001 From: ueqri Date: Tue, 13 Apr 2021 21:24:46 +0800 Subject: [PATCH 043/123] simplified condition expression --- .ci/azure-pipelines/docs-pipeline.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index 42fd82a6b1d..bde0ec8bfda 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -29,7 +29,7 @@ stages: # if docs pipeline triggered by build_gcc stage, # the formatting stage has already run, thus it # won't run for a second time here. - condition: not(eq(variables['Build.Reason'], 'ResourceTrigger')) + condition: ne(variables['Build.Reason'], 'ResourceTrigger')) jobs: - template: formatting.yaml From a53ef5aa26797a0c6cd18beeab361bd9630db65a Mon Sep 17 00:00:00 2001 From: Daniil Nikulin Date: Tue, 13 Apr 2021 19:20:55 +0300 Subject: [PATCH 044/123] uint32_t -> pcl::index_t in test_crop_hull --- test/filters/test_crop_hull.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index 0b534f1e59a..d46838a3baf 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -198,7 +198,7 @@ template struct RandomGenerator }; -static std::vector> cube_elements = { +static std::vector> cube_elements = { {0, 2, 1}, // l {1, 2, 3}, // l {3, 2, 6}, // f From 0afd2a9522f57904daa0cd34b54d9b6be2fd4f25 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Wed, 14 Apr 2021 08:18:41 +0530 Subject: [PATCH 045/123] Update LICENSE blurb in CONTRIBUTION.md (#4696) --- CONTRIBUTING.md | 34 +++------------------------------- 1 file changed, 3 insertions(+), 31 deletions(-) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 71aa4672da6..c940ed3bcdf 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -114,40 +114,12 @@ of each `.h` and `.cpp` file: ```cpp /* - * Software License Agreement (BSD License) + * SPDX-License-Identifier: BSD-3-Clause * * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2014-, 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. + * Copyright (c) 2014-, Open Perception Inc. * + * All rights reserved */ ``` From 6f2ab13b960206431ce7cc2009611814295890e3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 14 Apr 2021 21:49:37 +0200 Subject: [PATCH 046/123] Octree compression test: add function for random cloud generation --- test/io/test_octree_compression.cpp | 87 +++++++++++------------------ 1 file changed, 33 insertions(+), 54 deletions(-) diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index e71305300f0..89618c86096 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -51,6 +51,36 @@ char* pcd_file; #define MAX_COLOR 255 #define NUMBER_OF_TEST_RUNS 3 +template inline PointT generateRandomPoint(const float MAX_XYZ); + +template<> inline pcl::PointXYZRGBA generateRandomPoint(const float MAX_XYZ) { + return pcl::PointXYZRGBA(static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_COLOR * rand() / RAND_MAX), + static_cast (MAX_COLOR * rand() / RAND_MAX), + static_cast (MAX_COLOR * rand() / RAND_MAX), + static_cast (MAX_COLOR * rand() / RAND_MAX)); +} + +template<> inline pcl::PointXYZ generateRandomPoint(const float MAX_XYZ) { + return pcl::PointXYZ(static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX), + static_cast (MAX_XYZ * rand() / RAND_MAX)); +} + +template inline +typename pcl::PointCloud::Ptr generateRandomCloud(const float MAX_XYZ) { + // empty point cloud hangs decoder + const unsigned int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; + // create shared pointcloud instances + typename pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); + for (unsigned int point = 0; point < point_count; point++) { + cloud->push_back(generateRandomPoint(MAX_XYZ)); + } + return cloud; +} + TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) { srand(static_cast (time(NULL))); @@ -65,26 +95,7 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - // empty point cloud hangs decoder - const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; - // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - // assign input point clouds to octree - // create random point cloud - for (int point = 0; point < point_count; point++) - { - // generate a random point - pcl::PointXYZRGBA new_point; - new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), - new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); - // OctreePointCloudPointVector can store all points.. - cloud->push_back(new_point); - } + auto cloud = generateRandomCloud(MAX_XYZ); EXPECT_EQ(cloud->height, 1); // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; @@ -119,20 +130,7 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZ) // loop over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - // empty point cloud hangs decoder - const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; - // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - // assign input point clouds to octree - // create random point cloud - for (int point = 0; point < point_count; point++) - { - // generate a random point - pcl::PointXYZ new_point(static_cast (MAX_XYZ * rand() / RAND_MAX), - static_cast (MAX_XYZ * rand() / RAND_MAX), - static_cast (MAX_XYZ * rand() / RAND_MAX)); - cloud->push_back(new_point); - } + auto cloud = generateRandomCloud(MAX_XYZ); EXPECT_EQ(cloud->height, 1); // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; std::stringstream compressed_data; @@ -164,26 +162,7 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); pcl::io::OctreePointCloudCompression pointcloud_decoder; - // empty point cloud hangs decoder - const int point_count = 1 + (MAX_POINTS - 1) * rand() / RAND_MAX; - // create shared pointcloud instances - pcl::PointCloud::Ptr cloud(new pcl::PointCloud()); - // assign input point clouds to octree - // create random point cloud - for (int point = 0; point < point_count; point++) - { - // generate a random point - pcl::PointXYZRGBA new_point; - new_point.x = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.y = static_cast (MAX_XYZ * rand() / RAND_MAX), - new_point.z = static_cast (MAX_XYZ * rand() / RAND_MAX); - new_point.r = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.g = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.b = static_cast (MAX_COLOR * rand() / RAND_MAX); - new_point.a = static_cast (MAX_COLOR * rand() / RAND_MAX); - // OctreePointCloudPointVector can store all points.. - cloud->push_back(new_point); - } + auto cloud = generateRandomCloud(MAX_XYZ); EXPECT_EQ(cloud->height, 1); // iterate over runs From e7939aec32b27b0613d20c47ebb8e364d5fde796 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 15 Apr 2021 16:05:12 +0200 Subject: [PATCH 047/123] [CMake] Add SSE definitions for SSE 4.1 and 4.2 (#4596) * Restructure and add additional SSE definitions Co-authored-by: SunBlack --- CMakeLists.txt | 4 +- cmake/pcl_find_sse.cmake | 399 ++++++++++++++++++++++----------------- 2 files changed, 225 insertions(+), 178 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f4de5856f82..beb00c8e4b5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -104,7 +104,7 @@ if(CMAKE_COMPILER_IS_GNUCXX) else() string(APPEND CMAKE_CXX_FLAGS " -Wabi") endif() - string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS_STR}") + string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS}") if(PCL_WARNINGS_ARE_ERRORS) string(APPEND CMAKE_CXX_FLAGS " -Werror") endif() @@ -133,7 +133,7 @@ if(CMAKE_COMPILER_IS_MSVC) add_compile_options(/bigobj) if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") - string(APPEND CMAKE_CXX_FLAGS " /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS_STR} ${AVX_FLAGS}") + string(APPEND CMAKE_CXX_FLAGS " /fp:precise /wd4800 /wd4521 /wd4251 /wd4275 /wd4305 /wd4355 ${SSE_FLAGS} ${AVX_FLAGS}") # Add extra code generation/link optimizations if(CMAKE_MSVC_CODE_LINK_OPTIMIZATION AND (NOT BUILD_CUDA) AND (NOT BUILD_GPU)) diff --git a/cmake/pcl_find_sse.cmake b/cmake/pcl_find_sse.cmake index b64f6bce0d6..541ec580b55 100644 --- a/cmake/pcl_find_sse.cmake +++ b/cmake/pcl_find_sse.cmake @@ -1,210 +1,257 @@ ############################################################################### # Check for the presence of SSE and figure out the flags to use for it. -macro(PCL_CHECK_FOR_SSE) - set(SSE_FLAGS) - set(SSE_DEFINITIONS) - - if(NOT CMAKE_CROSSCOMPILING) - # Test GCC/G++ and CLANG - if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - include(CheckCXXCompilerFlag) - check_cxx_compiler_flag("-march=native" HAVE_MARCH) - if(HAVE_MARCH) - list(APPEND SSE_FLAGS "-march=native") - else() - list(APPEND SSE_FLAGS "-mtune=native") - endif() - message(STATUS "Using CPU native flags for SSE optimization: ${SSE_FLAGS}") - endif() - endif() - - # Unfortunately we need to check for SSE to enable "-mfpmath=sse" alongside - # "-march=native". The reason for this is that by default, 32bit architectures - # tend to use the x87 FPU (which has 80 bit internal precision), thus leading - # to different results than 64bit architectures which are using SSE2 (64 bit internal - # precision). One solution would be to use "-ffloat-store" on 32bit (see - # http://gcc.gnu.org/onlinedocs/gcc/Optimize-Options.html), but that slows code down, - # so the preferred solution is to try "-mpfmath=sse" first. - include(CheckCXXSourceRuns) - set(CMAKE_REQUIRED_FLAGS) +function(PCL_CHECK_FOR_SSE) + set(SSE_FLAGS) + set(SSE_DEFINITIONS) - check_cxx_source_runs(" - // Intel compiler defines an incompatible _mm_malloc signature - #if defined(__INTEL_COMPILER) - #include - #else - #include - #endif - int main() - { - void* mem = _mm_malloc (100, 16); - return 0; - }" - HAVE_MM_MALLOC) + if(NOT CMAKE_CROSSCOMPILING) + # Test GCC/G++ and CLANG + if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) + include(CheckCXXCompilerFlag) + check_cxx_compiler_flag("-march=native" HAVE_MARCH) + if(HAVE_MARCH) + list(APPEND SSE_FLAGS "-march=native") + else() + list(APPEND SSE_FLAGS "-mtune=native") + endif() + message(STATUS "Using CPU native flags for SSE optimization: ${SSE_FLAGS}") + endif() + endif() - check_cxx_source_runs(" - #include - int main() - { - void* mem; - return posix_memalign (&mem, 16, 100); - }" - HAVE_POSIX_MEMALIGN) + # Unfortunately we need to check for SSE to enable "-mfpmath=sse" alongside + # "-march=native". The reason for this is that by default, 32bit architectures + # tend to use the x87 FPU (which has 80 bit internal precision), thus leading + # to different results than 64bit architectures which are using SSE2 (64 bit internal + # precision). One solution would be to use "-ffloat-store" on 32bit (see + # http://gcc.gnu.org/onlinedocs/gcc/Optimize-Options.html), but that slows code down, + # so the preferred solution is to try "-mpfmath=sse" first. + include(CheckCXXSourceRuns) + set(CMAKE_REQUIRED_FLAGS) + set(SSE_LEVEL 0) + + check_cxx_source_runs(" + // Intel compiler defines an incompatible _mm_malloc signature + #if defined(__INTEL_COMPILER) + #include + #else + #include + #endif + int main() + { + void* mem = _mm_malloc (100, 16); + return 0; + }" + HAVE_MM_MALLOC) + + check_cxx_source_runs(" + #include + int main() + { + void* mem; + return posix_memalign (&mem, 16, 100); + }" + HAVE_POSIX_MEMALIGN) + if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) + set(CMAKE_REQUIRED_FLAGS "-msse4.2") + endif() + + check_cxx_source_runs(" + #include + #include + int main () + { + long long a[2] = { 1, 2 }; + long long b[2] = { -1, 3 }; + long long c[2]; + __m128i va = _mm_loadu_si128 ((__m128i*)a); + __m128i vb = _mm_loadu_si128 ((__m128i*)b); + __m128i vc = _mm_cmpgt_epi64 (va, vb); + + _mm_storeu_si128 ((__m128i*)c, vc); + if (c[0] == -1LL && c[1] == 0LL) + return (0); + else + return (1); + }" + HAVE_SSE4_2_EXTENSIONS) + + if(HAVE_SSE4_2_EXTENSIONS) + set(SSE_LEVEL 4.2) + endif() + + if(SSE_LEVEL LESS 4.2) if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-msse4.2") + set(CMAKE_REQUIRED_FLAGS "-msse4.1") endif() check_cxx_source_runs(" - #include - #include - int main () - { - long long a[2] = { 1, 2 }; - long long b[2] = { -1, 3 }; - long long c[2]; - __m128i va = _mm_loadu_si128 ((__m128i*)a); - __m128i vb = _mm_loadu_si128 ((__m128i*)b); - __m128i vc = _mm_cmpgt_epi64 (va, vb); - - _mm_storeu_si128 ((__m128i*)c, vc); - if (c[0] == -1LL && c[1] == 0LL) - return (0); - else - return (1); - }" - HAVE_SSE4_2_EXTENSIONS) + #include + int main () + { + __m128 a, b; + float vals[4] = {1, 2, 3, 4}; + const int mask = 123; + a = _mm_loadu_ps (vals); + b = a; + b = _mm_dp_ps (a, a, mask); + _mm_storeu_ps (vals,b); + return (0); + }" + HAVE_SSE4_1_EXTENSIONS) + + if(HAVE_SSE4_1_EXTENSIONS) + set(SSE_LEVEL 4.1) + endif() + endif() + if(SSE_LEVEL LESS 4.1) if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-msse4.1") + set(CMAKE_REQUIRED_FLAGS "-mssse3") endif() - + check_cxx_source_runs(" - #include - int main () - { - __m128 a, b; - float vals[4] = {1, 2, 3, 4}; - const int mask = 123; - a = _mm_loadu_ps (vals); - b = a; - b = _mm_dp_ps (a, a, mask); - _mm_storeu_ps (vals,b); - return (0); - }" - HAVE_SSE4_1_EXTENSIONS) + #include + int main () + { + __m128i a, b; + int vals[4] = {-1, -2, -3, -4}; + a = _mm_loadu_si128 ((const __m128i*)vals); + b = _mm_abs_epi32 (a); + _mm_storeu_si128 ((__m128i*)vals, b); + return (0); + }" + HAVE_SSSE3_EXTENSIONS) + if(HAVE_SSSE3_EXTENSIONS) + set(SSE_LEVEL 3.1) + endif() + endif() + + if(SSE_LEVEL LESS 3.1) if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-mssse3") + set(CMAKE_REQUIRED_FLAGS "-msse3") endif() check_cxx_source_runs(" - #include - int main () - { - __m128i a, b; - int vals[4] = {-1, -2, -3, -4}; - a = _mm_loadu_si128 ((const __m128i*)vals); - b = _mm_abs_epi32 (a); - _mm_storeu_si128 ((__m128i*)vals, b); + #include + int main () + { + __m128d a, b; + double vals[2] = {0}; + a = _mm_loadu_pd (vals); + b = _mm_hadd_pd (a,a); + _mm_storeu_pd (vals, b); return (0); - }" - HAVE_SSSE3_EXTENSIONS) + }" + HAVE_SSE3_EXTENSIONS) - if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-msse3") + if(HAVE_SSE3_EXTENSIONS) + set( SSE_LEVEL 3.0) endif() + endif() - check_cxx_source_runs(" - #include - int main () - { - __m128d a, b; - double vals[2] = {0}; - a = _mm_loadu_pd (vals); - b = _mm_hadd_pd (a,a); - _mm_storeu_pd (vals, b); - return (0); - }" - HAVE_SSE3_EXTENSIONS) - + if(SSE_LEVEL LESS 3.0) if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-msse2") + set(CMAKE_REQUIRED_FLAGS "-msse2") elseif(MSVC AND NOT CMAKE_CL_64) - set(CMAKE_REQUIRED_FLAGS "/arch:SSE2") + set(CMAKE_REQUIRED_FLAGS "/arch:SSE2") endif() check_cxx_source_runs(" - #include - int main () - { - __m128d a, b; - double vals[2] = {0}; - a = _mm_loadu_pd (vals); - b = _mm_add_pd (a,a); - _mm_storeu_pd (vals,b); - return (0); - }" - HAVE_SSE2_EXTENSIONS) + #include + int main () + { + __m128d a, b; + double vals[2] = {0}; + a = _mm_loadu_pd (vals); + b = _mm_add_pd (a,a); + _mm_storeu_pd (vals,b); + return (0); + }" + HAVE_SSE2_EXTENSIONS) + + if(HAVE_SSE2_EXTENSIONS) + set(SSE_LEVEL 2.0) + endif() + endif() + if(SSE_LEVEL LESS 2.0) if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - set(CMAKE_REQUIRED_FLAGS "-msse") + set(CMAKE_REQUIRED_FLAGS "-msse") elseif(MSVC AND NOT CMAKE_CL_64) - set(CMAKE_REQUIRED_FLAGS "/arch:SSE") + set(CMAKE_REQUIRED_FLAGS "/arch:SSE") endif() check_cxx_source_runs(" - #include - int main () - { - __m128 a, b; - float vals[4] = {0}; - a = _mm_loadu_ps (vals); - b = a; - b = _mm_add_ps (a,b); - _mm_storeu_ps (vals,b); - return (0); - }" - HAVE_SSE_EXTENSIONS) - - set(CMAKE_REQUIRED_FLAGS) + #include + int main () + { + __m128 a, b; + float vals[4] = {0}; + a = _mm_loadu_ps (vals); + b = a; + b = _mm_add_ps (a,b); + _mm_storeu_ps (vals,b); + return (0); + }" + HAVE_SSE_EXTENSIONS) - if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) - if(HAVE_SSE4_2_EXTENSIONS) - list(APPEND SSE_FLAGS "-msse4.2" "-mfpmath=sse") - elseif(HAVE_SSE4_1_EXTENSIONS) - list(APPEND SSE_FLAGS "-msse4.1" "-mfpmath=sse") - elseif(HAVE_SSSE3_EXTENSIONS) - list(APPEND SSE_FLAGS "-mssse3" "-mfpmath=sse") - elseif(HAVE_SSE3_EXTENSIONS) - list(APPEND SSE_FLAGS "-msse3" "-mfpmath=sse") - elseif(HAVE_SSE2_EXTENSIONS) - list(APPEND SSE_FLAGS "-msse2" "-mfpmath=sse") - elseif(HAVE_SSE_EXTENSIONS) - list(APPEND SSE_FLAGS "-msse" "-mfpmath=sse") - else() - # Setting -ffloat-store to alleviate 32bit vs 64bit discrepancies on non-SSE - # platforms. - list(APPEND SSE_FLAGS "-ffloat-store") - endif() - elseif(MSVC AND NOT CMAKE_CL_64) - if(HAVE_SSE2_EXTENSIONS) - list(APPEND SSE_FLAGS "/arch:SSE2") - elseif(HAVE_SSE_EXTENSIONS) - list(APPEND SSE_FLAGS "/arch:SSE") - endif() - endif() - - if(MSVC) - if(HAVE_SSSE3_EXTENSIONS) - string(APPEND SSE_DEFINITIONS " -D__SSSE3__") - endif() - if(HAVE_SSE2_EXTENSIONS) - string(APPEND SSE_DEFINITIONS " -D__SSE2__") - endif() - if(HAVE_SSE_EXTENSIONS) - string(APPEND SSE_DEFINITIONS " -D__SSE__") - endif() - endif() - string(REPLACE ";" " " SSE_FLAGS_STR "${SSE_FLAGS}") -endmacro() + if(HAVE_SSE_EXTENSIONS) + set(SSE_LEVEL 1.0) + endif() + endif() + + if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_IS_CLANG) + if(SSE_LEVEL GREATER_EQUAL 1.0) + if(SSE_LEVEL GREATER_EQUAL 4.2) + set(SSE_FLAGS "-msse4.2") + elseif(SSE_LEVEL GREATER_EQUAL 4.1) + set(SSE_FLAGS "-msse4.1") + elseif(SSE_LEVEL GREATER_EQUAL 3.1) + set(SSE_FLAGS "-msse3") + elseif(SSE_LEVEL GREATER_EQUAL 3.0) + set(SSE_FLAGS "-msse3") + elseif(SSE_LEVEL GREATER_EQUAL 2.0) + set(SSE_FLAGS "-msse2") + else() + set(SSE_FLAGS "-msse") + endif() + string(APPEND SSE_FLAGS " -mfpmath=sse") + else() + # Setting -ffloat-store to alleviate 32bit vs 64bit discrepancies on non-SSE + # platforms. + list(APPEND SSE_FLAGS "-ffloat-store") + endif() + elseif(MSVC AND NOT CMAKE_SIZEOF_VOID_P) + if(SSE_LEVEL GREATER_EQUAL 2.0) + set( SSE_FLAGS "/arch:SSE2") + elseif(SSE_LEVEL GREATER_EQUAL 1.0) + set( SSE_FLAGS "/arch:SSE") + endif() + elseif(MSVC) + if(SSE_LEVEL GREATER_EQUAL 4.2) + string(APPEND SSE_DEFINITIONS " -D__SSE4_2__") + endif() + if(SSE_LEVEL GREATER_EQUAL 4.1) + string(APPEND SSE_DEFINITIONS " -D__SSE4_1__") + endif() + if(SSE_LEVEL GREATER_EQUAL 3.1) + string(APPEND SSE_DEFINITIONS " -D__SSSE3__") + endif() + if(SSE_LEVEL GREATER_EQUAL 3.0) + string(APPEND SSE_DEFINITIONS " -D__SSE3__") + endif() + if(SSE_LEVEL GREATER_EQUAL 2.0) + string(APPEND SSE_DEFINITIONS " -D__SSE2__") + endif() + if(SSE_LEVEL GREATER_EQUAL 1.0) + string(APPEND SSE_DEFINITIONS " -D__SSE__") + endif() + endif() + + set(SSE_FLAGS ${SSE_FLAGS} PARENT_SCOPE) + set(SSE_DEFINITIONS ${SSE_DEFINITIONS} PARENT_SCOPE) + + unset(CMAKE_REQUIRED_FLAGS) +endfunction() From b20ead022ae2013dedf06c55988062000520892a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 15 Apr 2021 21:25:36 +0200 Subject: [PATCH 048/123] Unify test for XYZ and XYZRGBA by using typed test --- test/io/test_octree_compression.cpp | 50 +++++++---------------------- 1 file changed, 11 insertions(+), 39 deletions(-) diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 89618c86096..d268e45dd2c 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -81,7 +81,13 @@ typename pcl::PointCloud::Ptr generateRandomCloud(const float MAX_XYZ) { return cloud; } -TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) +template +class OctreeDeCompressionTest : public testing::Test {}; + +using TestTypes = ::testing::Types; +TYPED_TEST_SUITE(OctreeDeCompressionTest, TestTypes); + +TYPED_TEST (OctreeDeCompressionTest, RandomClouds) { srand(static_cast (time(NULL))); for (const double MAX_XYZ : {1.0, 1024.0}) { // Small clouds, large clouds @@ -89,13 +95,13 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) { // instantiate point cloud compression encoder/decoder - pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); - pcl::io::OctreePointCloudCompression pointcloud_decoder; - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); + pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression pointcloud_decoder; + typename pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); // iterate over runs for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) { - auto cloud = generateRandomCloud(MAX_XYZ); + auto cloud = generateRandomCloud(MAX_XYZ); EXPECT_EQ(cloud->height, 1); // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; @@ -115,40 +121,6 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBA) } // small clouds, large clouds } // TEST -TEST (PCL, OctreeDeCompressionRandomPointXYZ) -{ - srand(static_cast (time(NULL))); - for (const double MAX_XYZ : {1.0, 1024.0}) { // Small clouds, large clouds - // iterate over all pre-defined compression profiles - for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; - compression_profile != pcl::io::COMPRESSION_PROFILE_COUNT; ++compression_profile) - { - // instantiate point cloud compression encoder/decoder - pcl::io::OctreePointCloudCompression pointcloud_encoder((pcl::io::compression_Profiles_e) compression_profile, false); - pcl::io::OctreePointCloudCompression pointcloud_decoder; - pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); - // loop over runs - for (int test_idx = 0; test_idx < NUMBER_OF_TEST_RUNS; test_idx++, total_runs++) - { - auto cloud = generateRandomCloud(MAX_XYZ); - EXPECT_EQ(cloud->height, 1); - // std::cout << "Run: " << total_runs << " compression profile:" << compression_profile << " point_count: " << point_count; - std::stringstream compressed_data; - pointcloud_encoder.encodePointCloud(cloud, compressed_data); - pointcloud_decoder.decodePointCloud(compressed_data, cloud_out); - if (pcl::io::compressionProfiles_[compression_profile].doVoxelGridDownSampling) { - EXPECT_GT(cloud_out->width, 0); - EXPECT_LE(cloud_out->width, cloud->width) << "cloud width after encoding and decoding greater than before. Profile: " << compression_profile; - } - else { - EXPECT_EQ(cloud_out->width, cloud->width) << "cloud width after encoding and decoding not the same. Profile: " << compression_profile; - } - EXPECT_EQ(cloud_out->height, 1) << "cloud height after encoding and decoding should be 1 (as before). Profile: " << compression_profile; - } // runs - } // compression profiles - } // small clouds, large clouds -} // TEST - TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) { // Generate a random cloud. Put it into the encoder several times and make From 69ec601e013069ecc27bbadcb02773c06315523d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mos=C3=A8=20Giordano?= Date: Sat, 17 Apr 2021 01:45:12 +0100 Subject: [PATCH 049/123] Consistently use lowercase for headers and libs for Windows When building on Windows, a case-insensitive file-system is usually employed, but when cross-compiling on a Linux host for a Windows target case-senstive file-systems are more common. MinGW is the most common cross-compiler and consistently uses lowercase names for all libraries and header files. --- io/include/pcl/io/low_level_io.h | 2 +- surface/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/io/include/pcl/io/low_level_io.h b/io/include/pcl/io/low_level_io.h index 39ad6d246c3..1950aa42cbd 100644 --- a/io/include/pcl/io/low_level_io.h +++ b/io/include/pcl/io/low_level_io.h @@ -51,7 +51,7 @@ # endif # include # include -# include +# include using ssize_t = SSIZE_T; #else # include diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index 9ccf3b3c0fb..eae2d3ae011 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -193,5 +193,5 @@ if(VTK_FOUND AND NOT ANDROID) endif() if(WIN32) - target_link_libraries("${LIB_NAME}" Rpcrt4.lib) + target_link_libraries("${LIB_NAME}" rpcrt4.lib) endif() From a8e2170a6f12dd31f668c98a2e2a5b0dd921e73e Mon Sep 17 00:00:00 2001 From: Heiko Thiel Date: Sat, 17 Apr 2021 17:15:42 +0200 Subject: [PATCH 050/123] Fix compile issue of visualization::details::fillCells under MSVC due to missing symbol export --- visualization/include/pcl/visualization/pcl_visualizer.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 1c0c0154d88..c847ac9ac4a 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -80,7 +80,7 @@ namespace pcl { namespace details { - vtkIdType fillCells(std::vector& lookup, const std::vector& vertices, vtkSmartPointer cell_array, int max_size_of_polygon); + PCL_EXPORTS vtkIdType fillCells(std::vector& lookup, const std::vector& vertices, vtkSmartPointer cell_array, int max_size_of_polygon); } /** \brief PCL Visualizer main class. From 2279d91a42b00623d73d4dc0ff6b20e721d99bc1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mos=C3=A8=20Giordano?= Date: Sat, 17 Apr 2021 19:04:37 +0100 Subject: [PATCH 051/123] Link pcl_io against `ws2_32` when building with MinGW --- io/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index d26e6042179..ab918424e07 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -204,6 +204,10 @@ set(PLY_INCLUDES ) PCL_ADD_LIBRARY(pcl_io_ply COMPONENT ${SUBSYS_NAME} SOURCES ${PLY_SOURCES} ${PLY_INCLUDES}) +if(MINGW) + # libws2_32 isn't added by default for MinGW + target_link_libraries(pcl_io_ply ws2_32) +endif() PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/ply" ${PLY_INCLUDES}) target_include_directories(pcl_io_ply PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") From 69f6c51c8947dfd4b611b04fd65ee7419b93fd1c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mos=C3=A8=20Giordano?= Date: Sat, 17 Apr 2021 19:21:42 +0100 Subject: [PATCH 052/123] Alias `ssize_t` to `SSIZE_T` only for MSVC MinGW defines `ssize_t` as `int` for a 32-bit target (https://github.com/mirror/mingw-w64/blob/c6e13e0c105eab7797c2373819b49fff6b05566c/mingw-w64-headers/crt/time.h#L76-L80), which conflicts with the definition of `SSIZE_T`, which is `LONG_PTR`, i.e. `long` for a 32-bit target (https://docs.microsoft.com/en-us/windows/win32/winprog/windows-data-types). --- io/include/pcl/io/low_level_io.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/io/include/pcl/io/low_level_io.h b/io/include/pcl/io/low_level_io.h index 1950aa42cbd..e59d1a632ed 100644 --- a/io/include/pcl/io/low_level_io.h +++ b/io/include/pcl/io/low_level_io.h @@ -51,8 +51,12 @@ # endif # include # include -# include +# ifdef _MSC_VER +// ssize_t is already defined in MinGW and its definition conflicts with that of +// SSIZE_T on a 32-bit target, so do this only for MSVC. +# include using ssize_t = SSIZE_T; +# endif /* _MSC_VER */ #else # include # include From 64a31d3a6596bc386981786f72576c5ad7625f15 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 15 Apr 2021 16:06:04 +0200 Subject: [PATCH 053/123] More std::floor to floorf fixes. --- gpu/features/src/fpfh.cu | 8 +++++--- gpu/features/src/pfh.cu | 14 ++++++++------ gpu/features/src/spinimages.cu | 6 ++++-- gpu/features/src/vfh.cu | 12 +++++++----- 4 files changed, 24 insertions(+), 16 deletions(-) diff --git a/gpu/features/src/fpfh.cu b/gpu/features/src/fpfh.cu index f51055029c2..d2ae7fda43d 100644 --- a/gpu/features/src/fpfh.cu +++ b/gpu/features/src/fpfh.cu @@ -140,15 +140,17 @@ namespace pcl if (computePairFeatures (current_point[warp_idx], current_nomal[warp_idx], p, n, f1, f2, f3, f4)) { // Normalize the f1, f2, f3 features and push them in the histogram - h_index = std::floor (bins1 * ((f1 + M_PI) * (1.0f / (2.0f * M_PI)))); + //Using floorf due to changes to MSVC 16.9. See details here: https://devtalk.blender.org/t/cuda-compile-error-windows-10/17886/4 + //floorf is without std:: see why here: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=79700 + h_index = floorf (bins1 * ((f1 + M_PI) * (1.0f / (2.0f * M_PI)))); h_index = min(bins1 - 1, max(0, h_index)); atomicAdd(shist_b1 + h_index, hist_incr); - h_index = std::floor (bins2 * ((f2 + 1.0f) * 0.5f)); + h_index = floorf (bins2 * ((f2 + 1.0f) * 0.5f)); h_index = min(bins2 - 1, max (0, h_index)); atomicAdd(shist_b2 + h_index, hist_incr); - h_index = std::floor (bins3 * ((f3 + 1.0f) * 0.5f)); + h_index = floorf (bins3 * ((f3 + 1.0f) * 0.5f)); h_index = min(bins3 - 1, max (0, h_index)); atomicAdd(shist_b3 + h_index, hist_incr); diff --git a/gpu/features/src/pfh.cu b/gpu/features/src/pfh.cu index 2b4bbc83cdc..b5a508b3bcb 100644 --- a/gpu/features/src/pfh.cu +++ b/gpu/features/src/pfh.cu @@ -197,13 +197,15 @@ namespace pcl //if (computePairFeatures (pi, ni, pj, nj, f1, f2, f3, f4)) { // Normalize the f1, f2, f3 features and push them in the histogram - int find0 = std::floor( NR_SPLIT * ((f1 + PI) * (1.f / (2.f * PI))) ); + //Using floorf due to changes to MSVC 16.9. See details here: https://devtalk.blender.org/t/cuda-compile-error-windows-10/17886/4 + //floorf is without std:: see why here: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=79700 + int find0 = floorf( NR_SPLIT * ((f1 + PI) * (1.f / (2.f * PI))) ); find0 = min(NR_SPLIT - 1, max(0, find0)); - int find1 = std::floor( NR_SPLIT * ( (f2 + 1.f) * 0.5f ) ); + int find1 = floorf( NR_SPLIT * ( (f2 + 1.f) * 0.5f ) ); find1 = min(NR_SPLIT - 1, max(0, find1)); - int find2 = std::floor( NR_SPLIT * ( (f3 + 1.f) * 0.5f ) ); + int find2 = floorf( NR_SPLIT * ( (f3 + 1.f) * 0.5f ) ); find2 = min(NR_SPLIT - 1, max(0, find2)); int h_index = find0 + NR_SPLIT * find1 + NR_SPLIT_2 * find2; @@ -218,13 +220,13 @@ namespace pcl computeRGBPairFeatures_RGBOnly(ci, cj, f5, f6, f7); // color ratios are in [-1, 1] - int find4 = std::floor (NR_SPLIT * ((f5 + 1.f) * 0.5f)); + int find4 = floorf(NR_SPLIT * ((f5 + 1.f) * 0.5f)); find4 = min(NR_SPLIT - 1, max(0, find4)); - int find5 = std::floor (NR_SPLIT * ((f6 + 1.f) * 0.5f)); + int find5 = floorf(NR_SPLIT * ((f6 + 1.f) * 0.5f)); find5 = min(NR_SPLIT - 1, max(0, find5)); - int find6 = std::floor (NR_SPLIT * ((f7 + 1.f) * 0.5f)); + int find6 = floorf(NR_SPLIT * ((f7 + 1.f) * 0.5f)); find6 = min(NR_SPLIT - 1, max(0, find6)); // and the colors diff --git a/gpu/features/src/spinimages.cu b/gpu/features/src/spinimages.cu index 4b9f587d951..c763ae3b27a 100644 --- a/gpu/features/src/spinimages.cu +++ b/gpu/features/src/spinimages.cu @@ -197,8 +197,10 @@ namespace pcl // bilinear interpolation float beta_bin_size = radial ? (PI*0.5f/image_width) : bin_size; - int beta_bin = std::floor(beta / beta_bin_size) + image_width; - int alpha_bin = std::floor(alpha / bin_size); + //Using floorf due to changes to MSVC 16.9. See details here: https://devtalk.blender.org/t/cuda-compile-error-windows-10/17886/4 + //floorf is without std:: see why here: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=79700 + int beta_bin = floorf(beta / beta_bin_size) + image_width; + int alpha_bin = floorf(alpha / bin_size); //alpha_bin = min(simage_cols, max(0, alpha_bin)); //beta_bin = min(simage_rows, max(0, beta_bin)); diff --git a/gpu/features/src/vfh.cu b/gpu/features/src/vfh.cu index c221ccf088a..2a577157266 100644 --- a/gpu/features/src/vfh.cu +++ b/gpu/features/src/vfh.cu @@ -136,20 +136,22 @@ namespace pcl if (computePairFeatures(centroid_p, centroid_n, p, n, f1, f2, f3, f4)) { // Normalize the f1, f2, f3, f4 features and push them in the histogram - h_index = std::floor (bins1 * ((f1 + M_PI) * (1.f / (2.f * M_PI)))); + //Using floorf due to changes to MSVC 16.9. See details here: https://devtalk.blender.org/t/cuda-compile-error-windows-10/17886/4 + //floorf is without std:: see why here: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=79700 + h_index = floorf (bins1 * ((f1 + M_PI) * (1.f / (2.f * M_PI)))); h_index = min(bins1 - 1, max(0, h_index)); atomicAdd(shist_b1 + h_index, hist_incr); - h_index = std::floor (bins2 * ((f2 + 1.f) * 0.5f)); + h_index = floorf (bins2 * ((f2 + 1.f) * 0.5f)); h_index = min(bins2 - 1, max (0, h_index)); atomicAdd(shist_b2 + h_index, hist_incr); - h_index = std::floor (bins3 * ((f3 + 1.f) * 0.5f)); + h_index = floorf (bins3 * ((f3 + 1.f) * 0.5f)); h_index = min(bins3 - 1, max (0, h_index)); atomicAdd(shist_b3 + h_index, hist_incr); if (normalize_distances) - h_index = std::floor (bins4 * (f4 * distance_normalization_factor_inv)); + h_index = floorf (bins4 * (f4 * distance_normalization_factor_inv)); else h_index = __float2int_rn (f4 * 100); @@ -159,7 +161,7 @@ namespace pcl // viewpoint component float alfa = ((dot(n, d_vp_p) + 1.f) * 0.5f); - h_index = std::floor (bins_vp * alfa); + h_index = floorf (bins_vp * alfa); h_index = min(bins_vp - 1, max (0, h_index)); atomicAdd(shist_vp + h_index, hist_incr_vp); From 93653fa50556e6bb64ae78dd5fe65ea2a77c72ef Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Tue, 20 Apr 2021 07:41:00 +0530 Subject: [PATCH 054/123] Hotfix for the new doc CI --- .ci/azure-pipelines/docs-pipeline.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.ci/azure-pipelines/docs-pipeline.yaml b/.ci/azure-pipelines/docs-pipeline.yaml index bde0ec8bfda..e9c787cb0af 100644 --- a/.ci/azure-pipelines/docs-pipeline.yaml +++ b/.ci/azure-pipelines/docs-pipeline.yaml @@ -29,7 +29,7 @@ stages: # if docs pipeline triggered by build_gcc stage, # the formatting stage has already run, thus it # won't run for a second time here. - condition: ne(variables['Build.Reason'], 'ResourceTrigger')) + condition: ne(variables['Build.Reason'], 'ResourceTrigger') jobs: - template: formatting.yaml From 446f2d5c1fd34672a22330df0e0bbec24a5bba63 Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Tue, 20 Apr 2021 08:27:33 +0530 Subject: [PATCH 055/123] Add separate badge for docs pipeline --- README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/README.md b/README.md index eb0109ab4c6..36a1b0d1d85 100644 --- a/README.md +++ b/README.md @@ -28,12 +28,15 @@ Continuous integration [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20VS2017%20Build&configuration=Windows%20VS2017%20Build%20x64&label=Windows%20VS2017%20x64 [ci-macos-10.14]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Mojave%2010.14&label=macOS%20Mojave%2010.14 [ci-macos-10.15]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Catalina%2010.15&label=macOS%20Catalina%2010.15 +[ci-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/Documentation?branchName=master +[ci-latest-docs]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=14&branchName=master Build Platform | Status ------------------------ | ------------------------------------------------------------------------------------------------- | Ubuntu | [![Status][ci-ubuntu-18.04]][ci-latest-build]
[![Status][ci-ubuntu-20.04]][ci-latest-build]
[![Status][ci-ubuntu-20.10]][ci-latest-build] | Windows | [![Status][ci-windows-x86]][ci-latest-build]
[![Status][ci-windows-x64]][ci-latest-build] | macOS | [![Status][ci-macos-10.14]][ci-latest-build]
[![Status][ci-macos-10.15]][ci-latest-build] | +Documentation | [![Status][ci-docs]][ci-latest-docs] | Community --------- From f79847e4eba3357c91786fb039246ef325e8a0c0 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 14:24:49 +0200 Subject: [PATCH 056/123] Fix unused-value warnings in tutorials - the options are mandatory, so return with error message if not found - it is not necessary to keep the line count in these cpp files, so formatting can be done freely --- .../iccv2011/src/build_all_object_models.cpp | 24 +++++++++++++++---- .../iccv2011/src/build_object_model.cpp | 24 +++++++++++++++---- .../iccv2011/src/test_object_recognition.cpp | 24 +++++++++++++++---- .../iros2011/src/build_all_object_models.cpp | 24 +++++++++++++++---- .../iros2011/src/build_object_model.cpp | 24 +++++++++++++++---- .../iros2011/src/test_object_recognition.cpp | 24 +++++++++++++++---- 6 files changed, 120 insertions(+), 24 deletions(-) diff --git a/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp b/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp index e660b2cb10a..53ce73c889d 100644 --- a/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp @@ -90,7 +90,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } params_stream.open (filter_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -109,7 +113,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } params_stream.open (segmentation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -129,7 +137,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } params_stream.open (feature_estimation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -150,7 +162,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } params_stream.open (registration_parameters_file.c_str ()); if (params_stream.is_open()) { diff --git a/doc/tutorials/content/sources/iccv2011/src/build_object_model.cpp b/doc/tutorials/content/sources/iccv2011/src/build_object_model.cpp index ea946530980..deaf2760d65 100644 --- a/doc/tutorials/content/sources/iccv2011/src/build_object_model.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/build_object_model.cpp @@ -66,7 +66,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } params_stream.open (filter_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -85,7 +89,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } params_stream.open (segmentation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -105,7 +113,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } params_stream.open (feature_estimation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -126,7 +138,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } params_stream.open (registration_parameters_file.c_str ()); if (params_stream.is_open()) { diff --git a/doc/tutorials/content/sources/iccv2011/src/test_object_recognition.cpp b/doc/tutorials/content/sources/iccv2011/src/test_object_recognition.cpp index d9ebb473dd5..bd363d2b5e0 100644 --- a/doc/tutorials/content/sources/iccv2011/src/test_object_recognition.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/test_object_recognition.cpp @@ -86,7 +86,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } input_stream.open (filter_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -105,7 +109,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } input_stream.open (segmentation_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -125,7 +133,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } input_stream.open (feature_estimation_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -146,7 +158,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } input_stream.open (registration_parameters_file.c_str ()); if (input_stream.is_open()) { diff --git a/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp b/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp index cb77cdf8f48..094c9e220da 100644 --- a/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp +++ b/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp @@ -90,7 +90,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } params_stream.open (filter_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -109,7 +113,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } params_stream.open (segmentation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -129,7 +137,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } params_stream.open (feature_estimation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -150,7 +162,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } params_stream.open (registration_parameters_file.c_str ()); if (params_stream.is_open()) { diff --git a/doc/tutorials/content/sources/iros2011/src/build_object_model.cpp b/doc/tutorials/content/sources/iros2011/src/build_object_model.cpp index ea946530980..deaf2760d65 100644 --- a/doc/tutorials/content/sources/iros2011/src/build_object_model.cpp +++ b/doc/tutorials/content/sources/iros2011/src/build_object_model.cpp @@ -66,7 +66,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } params_stream.open (filter_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -85,7 +89,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } params_stream.open (segmentation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -105,7 +113,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } params_stream.open (feature_estimation_parameters_file.c_str ()); if (params_stream.is_open()) { @@ -126,7 +138,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } params_stream.open (registration_parameters_file.c_str ()); if (params_stream.is_open()) { diff --git a/doc/tutorials/content/sources/iros2011/src/test_object_recognition.cpp b/doc/tutorials/content/sources/iros2011/src/test_object_recognition.cpp index 251463d58cb..79f24a2cd8b 100644 --- a/doc/tutorials/content/sources/iros2011/src/test_object_recognition.cpp +++ b/doc/tutorials/content/sources/iros2011/src/test_object_recognition.cpp @@ -86,7 +86,11 @@ main (int argc, char ** argv) //Parse filter parameters std::string filter_parameters_file; - pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--filter", filter_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --filter\n"); + return (1); + } input_stream.open (filter_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -105,7 +109,11 @@ main (int argc, char ** argv) // Parse segmentation parameters std::string segmentation_parameters_file; - pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--segment", segmentation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --segment\n"); + return (1); + } input_stream.open (segmentation_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -125,7 +133,11 @@ main (int argc, char ** argv) // Parse feature estimation parameters std::string feature_estimation_parameters_file; - pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--feature", feature_estimation_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --feature\n"); + return (1); + } input_stream.open (feature_estimation_parameters_file.c_str ()); if (input_stream.is_open()) { @@ -146,7 +158,11 @@ main (int argc, char ** argv) // Parse the registration parameters std::string registration_parameters_file; - pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) > 0; + if (pcl::console::parse_argument (argc, argv, "--registration", registration_parameters_file) < 0) + { + pcl::console::print_error ("Missing option --registration\n"); + return (1); + } input_stream.open (registration_parameters_file.c_str ()); if (input_stream.is_open()) { From 66a4530f18475d68a72fa8ca97806257021a9530 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 14:46:59 +0200 Subject: [PATCH 057/123] Fix unused-variable warnings in tutorials --- .../narf_descriptor_visualization.cpp | 4 ++-- .../openni_narf_keypoint_extraction.cpp | 2 +- .../openni_range_image_visualization.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp b/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp index 87ca778d0bb..3df0b1d359f 100644 --- a/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp +++ b/doc/tutorials/content/sources/narf_descriptor_visualization/narf_descriptor_visualization.cpp @@ -188,7 +188,7 @@ main (int argc, char** argv) float surface_patch_world_size = narf.getSurfacePatchWorldSize (); surface_patch_widget.showFloatImage (narf.getSurfacePatch (), surface_patch_pixel_size, surface_patch_pixel_size, -0.5f*surface_patch_world_size, 0.5f*surface_patch_world_size, true); - float surface_patch_rotation = narf.getSurfacePatchRotation (); + /*float surface_patch_rotation = narf.getSurfacePatchRotation (); float patch_middle = 0.5f* (float (surface_patch_pixel_size-1)); float angle_step_size = pcl::deg2rad (360.0f)/narf.getDescriptorSize (); float cell_size = surface_patch_world_size/float (surface_patch_pixel_size), @@ -208,7 +208,7 @@ main (int argc, char** argv) { //surface_patch_widget.markLine (radius-0.5, radius-0.5, radius-0.5f + 2.0f*radius*sinf (rotations[i]), //radius-0.5f - 2.0f*radius*std::cos (rotations[i]), pcl::visualization::Vector3ub (255,0,0)); - } + }*/ descriptor_widget.showFloatImage (narf.getDescriptor (), narf.getDescriptorSize (), 1, -0.1f, 0.3f, true); diff --git a/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp b/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp index 4ab9cd179e7..6f0dd70d955 100644 --- a/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp +++ b/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp @@ -156,7 +156,7 @@ int main (int argc, char** argv) int width = depth_image_ptr->getWidth (), height = depth_image_ptr->getHeight (); float center_x = width/2, center_y = height/2; float focal_length_x = depth_image_ptr->getFocalLength (), focal_length_y = focal_length_x; - float original_angular_resolution = asinf (0.5f*float (width)/float (focal_length_x)) / (0.5f*float (width)); + // float original_angular_resolution = asinf (0.5f*float (width)/float (focal_length_x)) / (0.5f*float (width)); float desired_angular_resolution = angular_resolution; range_image_planar.setDepthImage (depth_map, width, height, center_x, center_y, focal_length_x, focal_length_y, desired_angular_resolution); diff --git a/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp b/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp index 038512853e9..a7cdbdb9da7 100644 --- a/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp +++ b/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp @@ -121,7 +121,7 @@ int main (int argc, char** argv) int width = depth_image_ptr->getWidth (), height = depth_image_ptr->getHeight (); float center_x = width/2, center_y = height/2; float focal_length_x = depth_image_ptr->getFocalLength (), focal_length_y = focal_length_x; - float original_angular_resolution = asinf (0.5f*float (width)/float (focal_length_x)) / (0.5f*float (width)); + // float original_angular_resolution = asinf (0.5f*float (width)/float (focal_length_x)) / (0.5f*float (width)); float desired_angular_resolution = angular_resolution; range_image_planar.setDepthImage (depth_map, width, height, center_x, center_y, focal_length_x, focal_length_y, desired_angular_resolution); From 5c2b975efa190823840391beb07f1416b84651dc Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 16:08:14 +0200 Subject: [PATCH 058/123] Fix reorder warnings in tutorials --- doc/tutorials/content/sources/iccv2011/src/openni_capture.cpp | 2 +- doc/tutorials/content/sources/iros2011/src/openni_capture.cpp | 4 ++-- doc/tutorials/content/sources/qt_colorize_cloud/pclviewer.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/doc/tutorials/content/sources/iccv2011/src/openni_capture.cpp b/doc/tutorials/content/sources/iccv2011/src/openni_capture.cpp index 1f1c507343d..7266fde4e36 100644 --- a/doc/tutorials/content/sources/iccv2011/src/openni_capture.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/openni_capture.cpp @@ -7,8 +7,8 @@ OpenNICapture::OpenNICapture (const std::string& device_id) : grabber_ (device_id) - , most_recent_frame_ () , frame_counter_ (0) + , most_recent_frame_ () , use_trigger_ (false) , trigger_ (false) { diff --git a/doc/tutorials/content/sources/iros2011/src/openni_capture.cpp b/doc/tutorials/content/sources/iros2011/src/openni_capture.cpp index 29ae70d5649..36c623c97c4 100644 --- a/doc/tutorials/content/sources/iros2011/src/openni_capture.cpp +++ b/doc/tutorials/content/sources/iros2011/src/openni_capture.cpp @@ -7,11 +7,11 @@ OpenNICapture::OpenNICapture (const std::string& device_id) : grabber_ (device_id) - , most_recent_frame_ () + , preview_ () , frame_counter_ (0) + , most_recent_frame_ () , use_trigger_ (false) , trigger_ (false) - , preview_ () { // Register a callback function to our OpenNI grabber... std::function frame_cb = [this] (const PointCloudConstPtr& cloud) { onNewFrame (cloud); }; diff --git a/doc/tutorials/content/sources/qt_colorize_cloud/pclviewer.cpp b/doc/tutorials/content/sources/qt_colorize_cloud/pclviewer.cpp index 9132ec5ceff..2a22446b645 100644 --- a/doc/tutorials/content/sources/qt_colorize_cloud/pclviewer.cpp +++ b/doc/tutorials/content/sources/qt_colorize_cloud/pclviewer.cpp @@ -3,9 +3,9 @@ PCLViewer::PCLViewer (QWidget *parent) : QMainWindow (parent), - ui (new Ui::PCLViewer), filtering_axis_ (1), // = y - color_mode_ (4) // = Rainbow + color_mode_ (4), // = Rainbow + ui (new Ui::PCLViewer) { ui->setupUi (this); this->setWindowTitle ("PCL viewer"); From 09bc4f040f7b406caccb08706142b414d8b3c5af Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Apr 2021 17:06:08 +0200 Subject: [PATCH 059/123] Fix unused-parameter warnings in tutorials --- .../conditional_euclidean_clustering.cpp | 4 ++-- .../sources/iccv2011/include/feature_estimation.h | 2 +- .../content/sources/iccv2011/src/tutorial.cpp | 2 +- .../sources/interactive_icp/interactive_icp.cpp | 2 +- .../sources/iros2011/include/object_recognition.h | 6 +++--- .../iros2011/include/solution/feature_estimation.h | 2 +- .../content/sources/iros2011/include/surface.h | 14 +++++++------- 7 files changed, 16 insertions(+), 16 deletions(-) diff --git a/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp b/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp index ee1a827e1c6..eb4eb13e59c 100644 --- a/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp +++ b/doc/tutorials/content/sources/conditional_euclidean_clustering/conditional_euclidean_clustering.cpp @@ -10,7 +10,7 @@ typedef pcl::PointXYZI PointTypeIO; typedef pcl::PointXYZINormal PointTypeFull; bool -enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance) +enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/) { if (std::abs (point_a.intensity - point_b.intensity) < 5.0f) return (true); @@ -19,7 +19,7 @@ enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& p } bool -enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance) +enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/) { Eigen::Map point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap (); if (std::abs (point_a.intensity - point_b.intensity) < 5.0f) diff --git a/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h b/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h index 04b9ed3ea62..92d7d84c23f 100644 --- a/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h +++ b/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h @@ -46,7 +46,7 @@ estimateSurfaceNormals (const PointCloudPtr & input, float radius) * Return: A pointer to a point cloud of keypoints */ PointCloudPtr -detectKeypoints (const PointCloudPtr & points, const SurfaceNormalsPtr & normals, +detectKeypoints (const PointCloudPtr & points, const SurfaceNormalsPtr & /*normals*/, float min_scale, int nr_octaves, int nr_scales_per_octave, float min_contrast) { pcl::SIFTKeypoint sift_detect; diff --git a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp index 616e8d440bb..f5f8a7744a3 100644 --- a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp @@ -398,7 +398,7 @@ void ICCVTutorial::run() } template -void ICCVTutorial::keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie) +void ICCVTutorial::keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* /*cookie*/) { if (event.keyUp()) { diff --git a/doc/tutorials/content/sources/interactive_icp/interactive_icp.cpp b/doc/tutorials/content/sources/interactive_icp/interactive_icp.cpp index d0351ae012a..dfb6cbfbc85 100644 --- a/doc/tutorials/content/sources/interactive_icp/interactive_icp.cpp +++ b/doc/tutorials/content/sources/interactive_icp/interactive_icp.cpp @@ -25,7 +25,7 @@ print4x4Matrix (const Eigen::Matrix4d & matrix) void keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event, - void* nothing) + void*) { if (event.getKeySym () == "space" && event.keyDown ()) next_iteration = true; diff --git a/doc/tutorials/content/sources/iros2011/include/object_recognition.h b/doc/tutorials/content/sources/iros2011/include/object_recognition.h index e403efc55f1..ed9080c2ecc 100644 --- a/doc/tutorials/content/sources/iros2011/include/object_recognition.h +++ b/doc/tutorials/content/sources/iros2011/include/object_recognition.h @@ -59,19 +59,19 @@ class ObjectRecognition {} void - populateDatabase (const std::vector & filenames) + populateDatabase (const std::vector & /*filenames*/) { } const ObjectModel & - recognizeObject (const PointCloudPtr & query_cloud) + recognizeObject (const PointCloudPtr & /*query_cloud*/) { int best_match = 0; return (models_[best_match]); } PointCloudPtr - recognizeAndAlignPoints (const PointCloudPtr & query_cloud) + recognizeAndAlignPoints (const PointCloudPtr & /*query_cloud*/) { PointCloudPtr output; return (output); diff --git a/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h b/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h index 96d11d30aa4..6249aaa20da 100644 --- a/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h +++ b/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h @@ -47,7 +47,7 @@ estimateSurfaceNormals (const PointCloudPtr & input, float radius) * Return: A pointer to a point cloud of keypoints */ PointCloudPtr -detectKeypoints (const PointCloudPtr & points, const SurfaceNormalsPtr & normals, +detectKeypoints (const PointCloudPtr & points, const SurfaceNormalsPtr & /*normals*/, float min_scale, int nr_octaves, int nr_scales_per_octave, float min_contrast) { pcl::SIFTKeypoint sift_detect; diff --git a/doc/tutorials/content/sources/iros2011/include/surface.h b/doc/tutorials/content/sources/iros2011/include/surface.h index 7749faedd34..189d3d80d72 100644 --- a/doc/tutorials/content/sources/iros2011/include/surface.h +++ b/doc/tutorials/content/sources/iros2011/include/surface.h @@ -21,21 +21,21 @@ class Mesh using MeshPtr = std::shared_ptr; PointCloudPtr -smoothPointCloud (const PointCloudPtr & input, float radius, int polynomial_order) +smoothPointCloud (const PointCloudPtr & /*input*/, float /*radius*/, int /*polynomial_order*/) { PointCloudPtr output (new PointCloud); return (output); } SurfaceElementsPtr -computeSurfaceElements (const PointCloudPtr & input, float radius, int polynomial_order) +computeSurfaceElements (const PointCloudPtr & /*input*/, float /*radius*/, int /*polynomial_order*/) { SurfaceElementsPtr surfels (new SurfaceElements); return (surfels); } MeshPtr -computeConvexHull (const PointCloudPtr & input) +computeConvexHull (const PointCloudPtr & /*input*/) { MeshPtr output (new Mesh); return (output); @@ -43,15 +43,15 @@ computeConvexHull (const PointCloudPtr & input) MeshPtr -computeConcaveHull (const PointCloudPtr & input, float alpha) +computeConcaveHull (const PointCloudPtr & /*input*/, float /*alpha*/) { MeshPtr output (new Mesh); return (output); } pcl::PolygonMesh::Ptr -greedyTriangulation (const SurfaceElementsPtr & surfels, float radius, float mu, int max_nearest_neighbors, - float max_surface_angle, float min_angle, float max_angle) +greedyTriangulation (const SurfaceElementsPtr & /*surfels*/, float /*radius*/, float /*mu*/, int /*max_nearest_neighbors*/, + float /*max_surface_angle*/, float /*min_angle*/, float /*max_angle*/) { pcl::PolygonMesh::Ptr output (new pcl::PolygonMesh); @@ -60,7 +60,7 @@ greedyTriangulation (const SurfaceElementsPtr & surfels, float radius, float mu, pcl::PolygonMesh::Ptr -marchingCubesTriangulation (const SurfaceElementsPtr & surfels, float leaf_size, float iso_level) +marchingCubesTriangulation (const SurfaceElementsPtr & /*surfels*/, float /*leaf_size*/, float /*iso_level*/) { pcl::PolygonMesh::Ptr output (new pcl::PolygonMesh); return (output); From f67053e94ec2654a564c9a691d6e31c47b7108f3 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Wed, 21 Apr 2021 13:39:48 +0200 Subject: [PATCH 060/123] Suppress cmake warnings for pcl modules (#4431) * Suppress cmake warnings for mismatched names --- PCLConfig.cmake.in | 2 ++ 1 file changed, 2 insertions(+) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 2ce6bc811cf..283a1a75b2a 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -519,6 +519,7 @@ foreach(component ${PCL_TO_FIND_COMPONENTS}) #pcl_message("No include directory found for pcl_${component}.") endif() + set(FPHSA_NAME_MISMATCHED 1) # Suppress warnings, see https://cmake.org/cmake/help/v3.17/module/FindPackageHandleStandardArgs.html # Skip find_library for header only modules list(FIND pcl_header_only_components ${component} _is_header_only) if(_is_header_only EQUAL -1) @@ -555,6 +556,7 @@ foreach(component ${PCL_TO_FIND_COMPONENTS}) find_package_handle_standard_args(PCL_${COMPONENT} DEFAULT_MSG PCL_${COMPONENT}_INCLUDE_DIR) endif() + unset(FPHSA_NAME_MISMATCHED) if(PCL_${COMPONENT}_FOUND) if(NOT "${PCL_${COMPONENT}_INCLUDE_DIRS}" STREQUAL "") From 4f76fd2527bc88b276175cc017744b0b92166a93 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 19 Apr 2021 12:52:05 +0200 Subject: [PATCH 061/123] Fix PFM --- common/include/pcl/common/point_tests.h | 12 +++++++++++- .../registration/impl/pyramid_feature_matching.hpp | 4 ++++ 2 files changed, 15 insertions(+), 1 deletion(-) diff --git a/common/include/pcl/common/point_tests.h b/common/include/pcl/common/point_tests.h index abd58c3508a..dc11edef481 100644 --- a/common/include/pcl/common/point_tests.h +++ b/common/include/pcl/common/point_tests.h @@ -69,8 +69,13 @@ namespace pcl template<> inline bool isFinite(const pcl::BRISKSignature512&) { return (true); } template<> inline bool isFinite(const pcl::BorderDescription &) { return true; } template<> inline bool isFinite(const pcl::Boundary&) { return (true); } + template<> inline bool isFinite(const pcl::CPPFSignature&) { return (true); } template<> inline bool isFinite(const pcl::ESFSignature640&) { return (true); } template<> inline bool isFinite(const pcl::FPFHSignature33&) { return (true); } + template<> inline bool isFinite(const pcl::GASDSignature512&) { return (true); } + template<> inline bool isFinite(const pcl::GASDSignature984&) { return (true); } + template<> inline bool isFinite(const pcl::GASDSignature7992&) { return (true); } + template<> inline bool isFinite(const pcl::GRSDSignature21&) { return (true); } template<> inline bool isFinite(const pcl::Intensity&) { return (true); } template<> inline bool isFinite(const pcl::IntensityGradient&) { return (true); } template<> inline bool isFinite(const pcl::Label&) { return (true); } @@ -79,7 +84,12 @@ namespace pcl template<> inline bool isFinite(const pcl::PFHRGBSignature250&) { return (true); } template<> inline bool isFinite(const pcl::PFHSignature125&) { return (true); } template<> inline bool isFinite(const pcl::PPFRGBSignature&) { return (true); } - template<> inline bool isFinite(const pcl::PPFSignature&) { return (true); } + + template<> inline bool isFinite(const pcl::PPFSignature& pt) + { + return std::isfinite(pt.f1) && std::isfinite(pt.f2) && std::isfinite(pt.f3) && std::isfinite(pt.f4) && std::isfinite(pt.alpha_m); + } + template<> inline bool isFinite(const pcl::PrincipalCurvatures&) { return (true); } template<> inline bool isFinite(const pcl::PrincipalRadiiRSD&) { return (true); } template<> inline bool isFinite(const pcl::RGB&) { return (true); } diff --git a/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp b/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp index 7e0cf749311..ad5f4a725ed 100644 --- a/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp +++ b/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp @@ -42,6 +42,7 @@ #ifndef PCL_REGISTRATION_IMPL_PYRAMID_FEATURE_MATCHING_H_ #define PCL_REGISTRATION_IMPL_PYRAMID_FEATURE_MATCHING_H_ +#include // for pcl::isFinite #include #include @@ -309,6 +310,9 @@ PyramidFeatureHistogram::compute() for (const auto& point : *input_) { std::vector feature_vector; + // NaN is converted to very high number that gives out of bound exception. + if (!pcl::isFinite(point)) + continue; convertFeatureToVector(point, feature_vector); addFeature(feature_vector); } From a99a594dc035a5adb4d0e3dbc2798727460df097 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 21 Apr 2021 13:07:45 +0200 Subject: [PATCH 062/123] Update values for test to pass. --- test/registration/test_registration.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index 045fb2eebce..2c33e690cd6 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -694,7 +694,7 @@ TEST (PCL, PyramidFeatureHistogram) pyramid_target->compute (); float similarity_value = PyramidFeatureHistogram::comparePyramidFeatureHistograms (pyramid_source, pyramid_target); - EXPECT_NEAR (similarity_value, 0.74101555347442627, 1e-4); + EXPECT_NEAR (similarity_value, 0.738492727, 1e-4); std::vector > dim_range_target2; for (std::size_t i = 0; i < 3; ++i) dim_range_target2.emplace_back(static_cast (-M_PI) * 5.0f, static_cast (M_PI) * 5.0f); @@ -707,7 +707,7 @@ TEST (PCL, PyramidFeatureHistogram) pyramid_target->compute (); float similarity_value2 = PyramidFeatureHistogram::comparePyramidFeatureHistograms (pyramid_source, pyramid_target); - EXPECT_NEAR (similarity_value2, 0.80097091197967529, 1e-4); + EXPECT_NEAR (similarity_value2, 0.798465133, 1e-4); std::vector > dim_range_target3; @@ -721,7 +721,7 @@ TEST (PCL, PyramidFeatureHistogram) pyramid_target->compute (); float similarity_value3 = PyramidFeatureHistogram::comparePyramidFeatureHistograms (pyramid_source, pyramid_target); - EXPECT_NEAR (similarity_value3, 0.87623238563537598, 1e-3); + EXPECT_NEAR (similarity_value3, 0.873699546, 1e-3); } // Suat G: disabled, since the transformation does not look correct. From 4dce6354516538d400b499855b80e32ea1140d8f Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Thu, 22 Apr 2021 10:40:25 +0200 Subject: [PATCH 063/123] Pass surface_ point to isFinite This caused segfaults. Seems like the check is done on the wrong dataset. Occurs when `setSearchSurface` is set, so `input_->size()` != `surface_->size()`. --- features/include/pcl/features/impl/fpfh_omp.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/features/include/pcl/features/impl/fpfh_omp.hpp b/features/include/pcl/features/impl/fpfh_omp.hpp index 5e87d22a94e..a81a4b00cb3 100644 --- a/features/include/pcl/features/impl/fpfh_omp.hpp +++ b/features/include/pcl/features/impl/fpfh_omp.hpp @@ -119,7 +119,7 @@ pcl::FPFHEstimationOMP::computeFeature (PointCloud int p_idx = spfh_indices_vec[i]; // Find the neighborhood around p_idx - if (!isFinite ((*input_)[p_idx]) || + if (!isFinite ((*surface_)[p_idx]) || this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0) continue; From 88c52d0ba78063c095d5bcd469c0a5532b22c226 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sat, 24 Apr 2021 18:45:23 +0200 Subject: [PATCH 064/123] Fix GPU Octree test --- test/gpu/octree/test_approx_nearest.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/test/gpu/octree/test_approx_nearest.cpp b/test/gpu/octree/test_approx_nearest.cpp index 2c4f6d2f8e4..c140d770ce0 100644 --- a/test/gpu/octree/test_approx_nearest.cpp +++ b/test/gpu/octree/test_approx_nearest.cpp @@ -18,6 +18,7 @@ #include #include #include +#include // for std::array TEST(PCL_OctreeGPU, approxNearesSearch) { From a05ccf71376ea4361544b605b8a456d0add81c42 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 26 Apr 2021 10:57:17 +0200 Subject: [PATCH 065/123] Clear cloud at each view iteration. --- tools/virtual_scanner.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index 89e5bbc1539..cda5149a59a 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -252,6 +252,9 @@ main (int argc, char** argv) int sid = -1; for (int i = 0; i < number_of_points; i++) { + // Clear cloud for next view scan + cloud.clear(); + sphere->GetPoint (i, eye); if (std::abs(eye[0]) < EPS) eye[0] = 0; if (std::abs(eye[1]) < EPS) eye[1] = 0; From a42fb1e3a59d1246776ef51d9d53dd6810c8c2d1 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 26 Apr 2021 11:05:32 +0200 Subject: [PATCH 066/123] Added scale parameter (m / mm) --- tools/virtual_scanner.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index cda5149a59a..be4d9abe326 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -116,6 +116,7 @@ main (int argc, char** argv) " -view_point : set the camera viewpoint from where the acquisition will take place\n" " -target_point : the target point that the camera should look at (default: 0, 0, 0)\n" " -organized <0|1> : create an organized, grid-like point cloud of width x height (1), or keep it unorganized with height = 1 (0)\n" + " -scale : scaling factor to the points XYZ (default 1(m), 1000(mm))\n" " -noise <0|1> : add gaussian noise (1) or keep the model noiseless (0)\n" " -noise_std : use X times the standard deviation\n" ""); @@ -135,6 +136,9 @@ main (int argc, char** argv) console::parse_3x_arguments (argc, argv, "-target_point", tx, ty, tz); int organized = 0; console::parse_argument (argc, argv, "-organized", organized); + double scale = 1; + console::parse_argument (argc, argv, "-scale", scale); + if (organized) PCL_INFO ("Saving an organized dataset.\n"); else @@ -357,9 +361,9 @@ main (int argc, char** argv) pcl::PointWithViewpoint pt; if (object_coordinates) { - pt.x = static_cast (x[0]); - pt.y = static_cast (x[1]); - pt.z = static_cast (x[2]); + pt.x = static_cast (x[0] * scale); + pt.y = static_cast (x[1] * scale); + pt.z = static_cast (x[2] * scale); pt.vp_x = static_cast (eye[0]); pt.vp_y = static_cast (eye[1]); pt.vp_z = static_cast (eye[2]); @@ -369,9 +373,9 @@ main (int argc, char** argv) // z axis is the viewray // y axis is up // x axis is -right (negative because z*y=-x but viewray*up=right) - pt.x = static_cast (-right[0]*x[1] + up[0]*x[2] + viewray[0]*x[0] + eye[0]); - pt.y = static_cast (-right[1]*x[1] + up[1]*x[2] + viewray[1]*x[0] + eye[1]); - pt.z = static_cast (-right[2]*x[1] + up[2]*x[2] + viewray[2]*x[0] + eye[2]); + pt.x = static_cast ((-right[0]*x[1] + up[0]*x[2] + viewray[0]*x[0] + eye[0])* scale); + pt.y = static_cast ((-right[1]*x[1] + up[1]*x[2] + viewray[1]*x[0] + eye[1]) * scale); + pt.z = static_cast ((-right[2]*x[1] + up[2]*x[2] + viewray[2]*x[0] + eye[2]) * scale); pt.vp_x = pt.vp_y = pt.vp_z = 0.0f; } cloud.push_back (pt); From 842ff6770b27d6d1645e210979816eb33f9b03dc Mon Sep 17 00:00:00 2001 From: Yan Hang Date: Tue, 27 Apr 2021 03:07:51 +0800 Subject: [PATCH 067/123] Moved `PointXYZLAB` to common point types (#4706) * moved PointXYZLAB to common point types * fixed SEGFAULT in registration test * fixed format error from CI patch * made XYZRGB2XYZLAB templated and added array header * Update common/include/pcl/point_types_conversion.h * added constraint for XYZRGB2XYZLAB template function Co-authored-by: Kunal Tyagi * added constraint for XYZRGB2XYZLAB template function * removed some redundant codes & tidied headers * fixed format error in gicp6d.cpp Co-authored-by: Kunal Tyagi --- common/include/pcl/common/colors.h | 1 + common/include/pcl/common/impl/intensity.hpp | 34 +++++++++ common/include/pcl/impl/point_types.hpp | 47 ++++++++++++ common/include/pcl/point_types.h | 5 ++ common/include/pcl/point_types_conversion.h | 53 +++++++++++++ common/src/point_types.cpp | 7 ++ .../include/pcl/registration/gicp6d.h | 32 -------- registration/src/gicp6d.cpp | 75 +++---------------- 8 files changed, 157 insertions(+), 97 deletions(-) diff --git a/common/include/pcl/common/colors.h b/common/include/pcl/common/colors.h index 50599a7a402..7c1fc883c66 100644 --- a/common/include/pcl/common/colors.h +++ b/common/include/pcl/common/colors.h @@ -41,6 +41,7 @@ #include #include // for is_floating_point +#include // for std::array especially in Clang Darwin and MSVC namespace pcl { diff --git a/common/include/pcl/common/impl/intensity.hpp b/common/include/pcl/common/impl/intensity.hpp index 526bcd94a17..687d934c40b 100644 --- a/common/include/pcl/common/impl/intensity.hpp +++ b/common/include/pcl/common/impl/intensity.hpp @@ -276,6 +276,40 @@ namespace pcl } }; + template<> + struct IntensityFieldAccessor + { + inline float + operator () (const pcl::PointXYZLAB &p) const + { + return (p.L); + } + + inline void + get (const pcl::PointXYZLAB &p, float &intensity) const + { + intensity = p.L; + } + + inline void + set (pcl::PointXYZLAB &p, float intensity) const + { + p.L = intensity; + } + + inline void + demean (pcl::PointXYZLAB& p, float value) const + { + p.L -= value; + } + + inline void + add (pcl::PointXYZLAB& p, float value) const + { + p.L += value; + } + }; + template<> struct IntensityFieldAccessor { diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 7b57a62ed5f..021f63cab4e 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -68,6 +68,7 @@ (pcl::PointXYZRGBA) \ (pcl::PointXYZRGB) \ (pcl::PointXYZRGBL) \ + (pcl::PointXYZLAB) \ (pcl::PointXYZHSV) \ (pcl::PointXY) \ (pcl::InterestPoint) \ @@ -125,6 +126,7 @@ (pcl::PointXYZRGBA) \ (pcl::PointXYZRGB) \ (pcl::PointXYZRGBL) \ + (pcl::PointXYZLAB) \ (pcl::PointXYZHSV) \ (pcl::InterestPoint) \ (pcl::PointNormal) \ @@ -690,6 +692,41 @@ namespace pcl }; + struct EIGEN_ALIGN16 _PointXYZLAB + { + PCL_ADD_POINT4D; // this adds the members x,y,z + union + { + struct + { + float L; + float a; + float b; + }; + float data_lab[4]; + }; + PCL_MAKE_ALIGNED_OPERATOR_NEW + }; + + PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointXYZLAB& p); + /** \brief A point structure representing Euclidean xyz coordinates, and the CIELAB color. + * \ingroup common + */ + struct PointXYZLAB : public _PointXYZLAB + { + inline PointXYZLAB() + { + x = y = z = 0.0f; + data[3] = 1.0f; // important for homogeneous coordinates + L = a = b = 0.0f; + data_lab[3] = 0.0f; + } + + friend std::ostream& operator << (std::ostream& os, const PointXYZLAB& p); + PCL_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct EIGEN_ALIGN16 _PointXYZHSV { PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) @@ -1882,6 +1919,16 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBL, ) POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBL, pcl::_PointXYZRGBL) +POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZLAB, + (float, x, x) + (float, y, y) + (float, z, z) + (float, L, L) + (float, a, a) + (float, b, b) +) +POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZLAB, pcl::_PointXYZLAB) + POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZHSV, (float, x, x) (float, y, y) diff --git a/common/include/pcl/point_types.h b/common/include/pcl/point_types.h index 1d47ba2edb0..b1f20e0bd5c 100644 --- a/common/include/pcl/point_types.h +++ b/common/include/pcl/point_types.h @@ -111,6 +111,11 @@ namespace pcl */ struct PointXYZRGBL; + /** \brief Members: float x, y, z, L, a, b + * \ingroup common + */ + struct PointXYZLAB; + /** \brief Members: float x, y, z, h, s, v * \ingroup common */ diff --git a/common/include/pcl/point_types_conversion.h b/common/include/pcl/point_types_conversion.h index a220e6060e7..231b5f20108 100644 --- a/common/include/pcl/point_types_conversion.h +++ b/common/include/pcl/point_types_conversion.h @@ -43,6 +43,8 @@ #include #include +#include // for RGB2sRGB_LUT + namespace pcl { // r,g,b, i values are from 0 to 255 @@ -134,6 +136,57 @@ namespace pcl if (out.h < 0.f) out.h += 360.f; } + /** \brief Convert a XYZRGB-based point type to a XYZLAB + * \param[in] in the input XYZRGB(XYZRGBA, XYZRGBL, etc.) point + * \param[out] out the output XYZLAB point + */ + template = true> + inline void + PointXYZRGBtoXYZLAB (const PointT& in, + PointXYZLAB& out) + { + out.x = in.x; + out.y = in.y; + out.z = in.z; + out.data[3] = 1.0; // important for homogeneous coordinates + + // convert sRGB to CIELAB + // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2 + // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7 + // an overview at: https://www.comp.nus.edu.sg/~leowwk/papers/colordiff.pdf + + const auto& sRGB_LUT = RGB2sRGB_LUT(); + + const double R = sRGB_LUT[in.r]; + const double G = sRGB_LUT[in.g]; + const double B = sRGB_LUT[in.b]; + + // linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees + const double X = R * 0.4124 + G * 0.3576 + B * 0.1805; + const double Y = R * 0.2126 + G * 0.7152 + B * 0.0722; + const double Z = R * 0.0193 + G * 0.1192 + B * 0.9505; + + // normalize X, Y, Z with tristimulus values for Xn, Yn, Zn + float f[3] = {static_cast(X), static_cast(Y), static_cast(Z)}; + f[0] /= 0.95047; + f[1] /= 1; + f[2] /= 1.08883; + + // CIEXYZ -> CIELAB + for (int i = 0; i < 3; ++i) { + if (f[i] > 0.008856) { + f[i] = std::pow(f[i], 1.0 / 3.0); + } + else { + f[i] = 7.787 * f[i] + 16.0 / 116.0; + } + } + + out.L = 116.0f * f[1] - 16.0f; + out.a = 500.0f * (f[0] - f[1]); + out.b = 200.0f * (f[1] - f[2]); + } + /** \brief Convert a XYZRGBA point type to a XYZHSV * \param[in] in the input XYZRGBA point * \param[out] out the output XYZHSV point diff --git a/common/src/point_types.cpp b/common/src/point_types.cpp index 03d8f7984f4..e3ab796fa79 100644 --- a/common/src/point_types.cpp +++ b/common/src/point_types.cpp @@ -130,6 +130,13 @@ namespace pcl return (os); } + std::ostream& + operator << (std::ostream& os, const PointXYZLAB& p) + { + os << "(" << p.x << "," << p.y << "," << p.z << " - " << p.L << " , " << p.a << " , " << p.b << ")"; + return (os); + } + std::ostream& operator << (std::ostream& os, const PointXYZHSV& p) { diff --git a/registration/include/pcl/registration/gicp6d.h b/registration/include/pcl/registration/gicp6d.h index bc96ecd06fc..2718344bd4a 100644 --- a/registration/include/pcl/registration/gicp6d.h +++ b/registration/include/pcl/registration/gicp6d.h @@ -46,38 +46,6 @@ #include #include -namespace pcl { -struct EIGEN_ALIGN16 _PointXYZLAB { - PCL_ADD_POINT4D; // this adds the members x,y,z - union { - struct { - float L; - float a; - float b; - }; - float data_lab[4]; - }; - PCL_MAKE_ALIGNED_OPERATOR_NEW -}; - -/** \brief A custom point type for position and CIELAB color value */ -struct PointXYZLAB : public _PointXYZLAB { - inline PointXYZLAB() - { - x = y = z = 0.0f; - data[3] = 1.0f; // important for homogeneous coordinates - L = a = b = 0.0f; - data_lab[3] = 0.0f; - } -}; -} // namespace pcl - -// register the custom point type in PCL -POINT_CLOUD_REGISTER_POINT_STRUCT( - pcl::_PointXYZLAB, - (float, x, x)(float, y, y)(float, z, z)(float, L, L)(float, a, a)(float, b, b)) -POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZLAB, pcl::_PointXYZLAB) - namespace pcl { /** \brief GeneralizedIterativeClosestPoint6D integrates L*a*b* color space information * into the Generalized Iterative Closest Point (GICP) algorithm. diff --git a/registration/src/gicp6d.cpp b/registration/src/gicp6d.cpp index 27afd8ccab4..815ac71b93d 100644 --- a/registration/src/gicp6d.cpp +++ b/registration/src/gicp6d.cpp @@ -36,72 +36,11 @@ * */ -#include // for RGB2sRGB_LUT, XYZ2LAB_LUT #include -#include // for pcl::make_shared +#include // for pcl::make_shared +#include // for PointXYZRGBtoXYZLAB namespace pcl { -// convert sRGB to CIELAB -Eigen::Vector3f -RGB2Lab(const Eigen::Vector3i& colorRGB) -{ - // for sRGB -> CIEXYZ see http://www.easyrgb.com/index.php?X=MATH&H=02#text2 - // for CIEXYZ -> CIELAB see http://www.easyrgb.com/index.php?X=MATH&H=07#text7 - // an overview at: https://www.comp.nus.edu.sg/~leowwk/papers/colordiff.pdf - - const auto& sRGB_LUT = RGB2sRGB_LUT(); - - const double R = sRGB_LUT[colorRGB[0]]; - const double G = sRGB_LUT[colorRGB[1]]; - const double B = sRGB_LUT[colorRGB[2]]; - - // linear sRGB -> CIEXYZ, D65 illuminant, observer at 2 degrees - const double X = R * 0.4124 + G * 0.3576 + B * 0.1805; - const double Y = R * 0.2126 + G * 0.7152 + B * 0.0722; - const double Z = R * 0.0193 + G * 0.1192 + B * 0.9505; - - // normalize X, Y, Z with tristimulus values for Xn, Yn, Zn - float f[3] = {static_cast(X), static_cast(Y), static_cast(Z)}; - f[0] /= 0.95047; - f[1] /= 1; - f[2] /= 1.08883; - - // CIEXYZ -> CIELAB - for (int i = 0; i < 3; ++i) { - if (f[i] > 0.008856) { - f[i] = std::pow(f[i], 1.0 / 3.0); - } - else { - f[i] = 7.787 * f[i] + 16.0 / 116.0; - } - } - - Eigen::Vector3f colorLab; - colorLab[0] = 116.0f * f[1] - 16.0f; - colorLab[1] = 500.0f * (f[0] - f[1]); - colorLab[2] = 200.0f * (f[1] - f[2]); - - return colorLab; -} - -// convert a PointXYZRGBA cloud to a PointXYZLAB cloud -void -convertRGBAToLAB(const PointCloud& in, PointCloud& out) -{ - out.resize(in.size()); - - for (std::size_t i = 0; i < in.size(); ++i) { - out[i].x = in[i].x; - out[i].y = in[i].y; - out[i].z = in[i].z; - out[i].data[3] = 1.0; // important for homogeneous coordinates - - Eigen::Vector3f lab = RGB2Lab(in[i].getRGBVector3i()); - out[i].L = lab[0]; - out[i].a = lab[1]; - out[i].b = lab[2]; - } -} GeneralizedIterativeClosestPoint6D::GeneralizedIterativeClosestPoint6D(float lab_weight) : cloud_lab_(new pcl::PointCloud) @@ -121,7 +60,10 @@ GeneralizedIterativeClosestPoint6D::setInputSource( GeneralizedIterativeClosestPoint::setInputSource(cloud); // in addition, convert colors of the cloud to CIELAB - convertRGBAToLAB(*cloud, *cloud_lab_); + cloud_lab_->resize(cloud->size()); + for (std::size_t point_idx = 0; point_idx < cloud->size(); ++point_idx) { + PointXYZRGBtoXYZLAB((*cloud)[point_idx], (*cloud_lab_)[point_idx]); + } } void @@ -132,7 +74,10 @@ GeneralizedIterativeClosestPoint6D::setInputTarget( GeneralizedIterativeClosestPoint::setInputTarget(target); // in addition, convert colors of the cloud to CIELAB... - convertRGBAToLAB(*target, *target_lab_); + target_lab_->resize(target->size()); + for (std::size_t point_idx = 0; point_idx < target->size(); ++point_idx) { + PointXYZRGBtoXYZLAB((*target)[point_idx], (*target_lab_)[point_idx]); + } // ...and build 6d-tree target_tree_lab_.setInputCloud(target_lab_); From cad5d08d9e71ed2aa838cbd73ce103d37b11143f Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 23 Apr 2021 22:51:11 +0200 Subject: [PATCH 068/123] Fix addition of Carriage Return to PCD files. --- io/include/pcl/io/impl/pcd_io.hpp | 4 ++-- io/src/pcd_io.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/io/include/pcl/io/impl/pcd_io.hpp b/io/include/pcl/io/impl/pcd_io.hpp index 84fb0120200..ad551f79514 100644 --- a/io/include/pcl/io/impl/pcd_io.hpp +++ b/io/include/pcl/io/impl/pcd_io.hpp @@ -447,7 +447,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud< } std::ofstream fs; - fs.open (file_name.c_str ()); // Open file + fs.open (file_name.c_str (), std::ios::binary); // Open file if (!fs.is_open () || fs.fail ()) { @@ -730,7 +730,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, } std::ofstream fs; - fs.open (file_name.c_str ()); // Open file + fs.open (file_name.c_str (), std::ios::binary); // Open file if (!fs.is_open () || fs.fail ()) { throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!"); diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 31254677533..d329ef56aa8 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -1128,7 +1128,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo std::ofstream fs; fs.precision (precision); fs.imbue (std::locale::classic ()); - fs.open (file_name.c_str ()); // Open file + fs.open (file_name.c_str (), std::ios::binary); // Open file if (!fs.is_open () || fs.fail ()) { PCL_ERROR("[pcl::PCDWriter::writeASCII] Could not open file '%s' for writing! Error : %s\n", file_name.c_str (), strerror(errno)); From 51b8652042db59648a3fd58937f58b578cb692e5 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 29 Apr 2021 22:40:39 +0200 Subject: [PATCH 069/123] [GPU] Export and template extract clusters (#4196) * Make gpu_extract_clusters templated. --- gpu/segmentation/CMakeLists.txt | 3 +- .../gpu/segmentation/gpu_extract_clusters.h | 21 +++++----- .../gpu_extract_labeled_clusters.h | 9 ++--- .../gpu_seeded_hue_segmentation.h | 7 ++-- .../impl/gpu_extract_clusters.hpp | 40 +++++++++++++------ .../impl/gpu_extract_labeled_clusters.hpp | 4 +- gpu/segmentation/src/extract_clusters.cpp | 3 ++ 7 files changed, 50 insertions(+), 37 deletions(-) diff --git a/gpu/segmentation/CMakeLists.txt b/gpu/segmentation/CMakeLists.txt index f8f3cbb5e4e..9a99a620367 100644 --- a/gpu/segmentation/CMakeLists.txt +++ b/gpu/segmentation/CMakeLists.txt @@ -6,6 +6,7 @@ set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build "${SUBSYS_NAME}" DEPS ${SUBSYS_DEPS}) +PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_ADD_DOC("${SUBSYS_NAME}") @@ -33,7 +34,7 @@ set(impl_incs set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs}) -target_link_libraries("${LIB_NAME}" pcl_gpu_octree pcl_gpu_utils pcl_gpu_containers) +target_link_libraries("${LIB_NAME}" pcl_common pcl_gpu_octree pcl_gpu_utils pcl_gpu_containers) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) # Install include files diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h index 5e2ecde9051..3738663ff42 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h @@ -50,8 +50,8 @@ namespace pcl { namespace gpu { - void - extractEuclideanClusters (const pcl::PointCloud::Ptr &host_cloud_, + template void + extractEuclideanClusters (const typename pcl::PointCloud::Ptr &host_cloud_, const pcl::gpu::Octree::Ptr &tree, float tolerance, std::vector &clusters, @@ -62,13 +62,13 @@ namespace pcl * \author Koen Buys, Radu Bogdan Rusu * \ingroup segmentation */ + template class EuclideanClusterExtraction { public: - using PointType = pcl::PointXYZ; - using PointCloudHost = pcl::PointCloud; - using PointCloudHostPtr = PointCloudHost::Ptr; - using PointCloudHostConstPtr = PointCloudHost::ConstPtr; + using PointCloudHost = pcl::PointCloud; + using PointCloudHostPtr = typename PointCloudHost::Ptr; + using PointCloudHostConstPtr = typename PointCloudHost::ConstPtr; using PointIndicesPtr = PointIndices::Ptr; using PointIndicesConstPtr = PointIndices::ConstPtr; @@ -80,8 +80,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - EuclideanClusterExtraction () : min_pts_per_cluster_ (1), max_pts_per_cluster_ (std::numeric_limits::max ()) - {}; + EuclideanClusterExtraction () = default; /** \brief the destructor */ /* ~EuclideanClusterExtraction () @@ -143,13 +142,13 @@ namespace pcl GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_; + double cluster_tolerance_ {0}; /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */ - int min_pts_per_cluster_; + int min_pts_per_cluster_ {1}; /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */ - int max_pts_per_cluster_; + int max_pts_per_cluster_ {std::numeric_limits::max()}; /** \brief Class getName method. */ virtual std::string getClassName () const { return ("gpu::EuclideanClusterExtraction"); } diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h index bf5b5e2b558..65fc71cc22f 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h @@ -80,8 +80,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - EuclideanLabeledClusterExtraction () : min_pts_per_cluster_ (1), max_pts_per_cluster_ (std::numeric_limits::max ()) - {}; + EuclideanLabeledClusterExtraction () = default; /** \brief Provide a pointer to the search object. * \param tree a pointer to the spatial search object. @@ -137,13 +136,13 @@ namespace pcl GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_; + double cluster_tolerance_ {0}; /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */ - int min_pts_per_cluster_; + int min_pts_per_cluster_ {1}; /** \brief The maximum number of points that a cluster needs to contain in order to be considered valid (default = MAXINT). */ - int max_pts_per_cluster_; + int max_pts_per_cluster_ {std::numeric_limits::max()}; /** \brief Class getName method. */ virtual std::string getClassName () const { return ("gpu::EuclideanLabeledClusterExtraction"); } diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h index 373f904cbad..b6c974dfae3 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h @@ -74,8 +74,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - SeededHueSegmentation () : delta_hue_ (0.0) - {}; + SeededHueSegmentation () = default; /** \brief Provide a pointer to the search object. * \param tree a pointer to the spatial search object. @@ -126,10 +125,10 @@ namespace pcl GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_; + double cluster_tolerance_ {0}; /** \brief The allowed difference on the hue*/ - float delta_hue_; + float delta_hue_ {0.0}; /** \brief Class getName method. */ virtual std::string getClassName () const { return ("gpu::SeededHueSegmentation"); } diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp b/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp index b5055e02c5c..ae8ccd9fc57 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp +++ b/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp @@ -36,13 +36,12 @@ * @author: Koen Buys */ -#ifndef PCL_GPU_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ -#define PCL_GPU_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ - +#pragma once +#include #include -void -pcl::gpu::extractEuclideanClusters (const pcl::PointCloud::Ptr &host_cloud_, +template void +pcl::gpu::extractEuclideanClusters (const typename pcl::PointCloud::Ptr &host_cloud_, const pcl::gpu::Octree::Ptr &tree, float tolerance, std::vector &clusters, @@ -80,9 +79,14 @@ pcl::gpu::extractEuclideanClusters (const pcl::PointCloud::Ptr & // Create the query queue on the device, point based not indices pcl::gpu::Octree::Queries queries_device; // Create the query queue on the host - pcl::PointCloud::VectorType queries_host; + pcl::PointCloud::VectorType queries_host; + + // Buffer in a new PointXYZ type + PointXYZ p; + pcl::copyPoint((*host_cloud_)[i], p); + // Push the starting point in the vector - queries_host.push_back ((*host_cloud_)[i]); + queries_host.push_back (p); // Clear vector r.indices.clear(); // Push the starting point in @@ -123,7 +127,12 @@ pcl::gpu::extractEuclideanClusters (const pcl::PointCloud::Ptr & if(processed[data[i]]) continue; processed[data[i]] = true; - queries_host.push_back ((*host_cloud_)[data[i]]); + + // Buffer in a new PointXYZ type + PointXYZ p; + pcl::copyPoint((*host_cloud_)[data[i]], p); + + queries_host.push_back (p); found_points++; r.indices.push_back(data[i]); } @@ -153,7 +162,11 @@ pcl::gpu::extractEuclideanClusters (const pcl::PointCloud::Ptr & if(processed[data[qp_r + qp * max_answers]]) continue; processed[data[qp_r + qp * max_answers]] = true; - queries_host.push_back ((*host_cloud_)[data[qp_r + qp * max_answers]]); + // Buffer in a new PointXYZ type + PointXYZ p; + pcl::copyPoint((*host_cloud_)[data[qp_r + qp * max_answers]], p); + + queries_host.push_back (p); found_points++; r.indices.push_back(data[qp_r + qp * max_answers]); } @@ -176,8 +189,8 @@ pcl::gpu::extractEuclideanClusters (const pcl::PointCloud::Ptr & } } -void -pcl::gpu::EuclideanClusterExtraction::extract (std::vector &clusters) +template void +pcl::gpu::EuclideanClusterExtraction::extract (std::vector &clusters) { /* // Initialize the GPU search tree @@ -200,10 +213,11 @@ pcl::gpu::EuclideanClusterExtraction::extract (std::vector &c } */ // Extract the actual clusters - extractEuclideanClusters (host_cloud_, tree_, cluster_tolerance_, clusters, min_pts_per_cluster_, max_pts_per_cluster_); + extractEuclideanClusters (host_cloud_, tree_, cluster_tolerance_, clusters, min_pts_per_cluster_, max_pts_per_cluster_); std::cout << "INFO: end of extractEuclideanClusters " << std::endl; // Sort the clusters based on their size (largest one first) //std::sort (clusters.rbegin (), clusters.rend (), comparePointClusters); } -#endif //PCL_GPU_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_ +#define PCL_INSTANTIATE_extractEuclideanClusters(T) template void PCL_EXPORTS pcl::gpu::extractEuclideanClusters (const typename pcl::PointCloud::Ptr &, const pcl::gpu::Octree::Ptr &,float, std::vector &, unsigned int, unsigned int); +#define PCL_INSTANTIATE_EuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::gpu::EuclideanClusterExtraction; diff --git a/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_labeled_clusters.hpp b/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_labeled_clusters.hpp index cbee62f93e0..af518d99492 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_labeled_clusters.hpp +++ b/gpu/segmentation/include/pcl/gpu/segmentation/impl/gpu_extract_labeled_clusters.hpp @@ -36,8 +36,7 @@ * */ -#ifndef PCL_GPU_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_ -#define PCL_GPU_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_ +#pragma once #include @@ -176,4 +175,3 @@ pcl::gpu::EuclideanLabeledClusterExtraction::extract (std::vector (const typename pcl::PointCloud::Ptr &, const pcl::gpu::Octree::Ptr &,float, std::vector &, unsigned int, unsigned int); #define PCL_INSTANTIATE_EuclideanLabeledClusterExtraction(T) template class PCL_EXPORTS pcl::gpu::EuclideanLabeledClusterExtraction; -#endif //PCL_GPU_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_ diff --git a/gpu/segmentation/src/extract_clusters.cpp b/gpu/segmentation/src/extract_clusters.cpp index fd41feb6146..4f4ddb1db9b 100644 --- a/gpu/segmentation/src/extract_clusters.cpp +++ b/gpu/segmentation/src/extract_clusters.cpp @@ -38,8 +38,11 @@ #include #include //#include +#include #include // Instantiations of specific point types +PCL_INSTANTIATE(extractEuclideanClusters, PCL_XYZ_POINT_TYPES); +PCL_INSTANTIATE(EuclideanClusterExtraction, PCL_XYZ_POINT_TYPES); PCL_INSTANTIATE(extractLabeledEuclideanClusters, PCL_XYZL_POINT_TYPES); PCL_INSTANTIATE(EuclideanLabeledClusterExtraction, PCL_XYZL_POINT_TYPES); From 490ce4119cb8eaa636556b9d734f971b54e33d3b Mon Sep 17 00:00:00 2001 From: Kunal Tyagi Date: Fri, 30 Apr 2021 06:04:23 +0900 Subject: [PATCH 070/123] [Fix] Add missing copy ctor for PointXYZLAB --- common/include/pcl/impl/point_types.hpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 021f63cab4e..609107e48cd 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -714,6 +714,12 @@ namespace pcl */ struct PointXYZLAB : public _PointXYZLAB { + inline PointXYZLAB (const _PointXYZLAB &p) + { + x = p.x; y = p.y; z = p.z; data[3] = 1.0f; + L = p.L; a = p.a; b = p.b; + } + inline PointXYZLAB() { x = y = z = 0.0f; From 673cb7df805b4792656bc9ccf1b7fd5644b04881 Mon Sep 17 00:00:00 2001 From: mnobrecastro Date: Sat, 1 May 2021 19:59:26 +0200 Subject: [PATCH 071/123] Namespace in aligned_{malloc/free} (pcl_macros.h) solves Eigen lib's conflict. Fixes issue #4734. --- common/include/pcl/pcl_macros.h | 50 ++++++++++++++++++--------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index 6239707a869..dd1ccfbd32b 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -376,44 +376,48 @@ pcl_round (float number) #endif #endif +namespace pcl { + inline void* -aligned_malloc (std::size_t size) +aligned_malloc(std::size_t size) { - void *ptr; -#if defined (MALLOC_ALIGNED) - ptr = std::malloc (size); -#elif defined (HAVE_POSIX_MEMALIGN) - if (posix_memalign (&ptr, 16, size)) + void* ptr; +#if defined(MALLOC_ALIGNED) + ptr = std::malloc(size); +#elif defined(HAVE_POSIX_MEMALIGN) + if (posix_memalign(&ptr, 16, size)) ptr = 0; -#elif defined (HAVE_MM_MALLOC) - ptr = _mm_malloc (size, 16); -#elif defined (_MSC_VER) - ptr = _aligned_malloc (size, 16); -#elif defined (ANDROID) - ptr = memalign (16, size); +#elif defined(HAVE_MM_MALLOC) + ptr = _mm_malloc(size, 16); +#elif defined(_MSC_VER) + ptr = _aligned_malloc(size, 16); +#elif defined(ANDROID) + ptr = memalign(16, size); #else - #error aligned_malloc not supported on your platform +#error aligned_malloc not supported on your platform ptr = 0; #endif return (ptr); } inline void -aligned_free (void* ptr) +aligned_free(void* ptr) { -#if defined (MALLOC_ALIGNED) || defined (HAVE_POSIX_MEMALIGN) - std::free (ptr); -#elif defined (HAVE_MM_MALLOC) - _mm_free (ptr); -#elif defined (_MSC_VER) - _aligned_free (ptr); -#elif defined (ANDROID) - free (ptr); +#if defined(MALLOC_ALIGNED) || defined(HAVE_POSIX_MEMALIGN) + std::free(ptr); +#elif defined(HAVE_MM_MALLOC) + _mm_free(ptr); +#elif defined(_MSC_VER) + _aligned_free(ptr); +#elif defined(ANDROID) + free(ptr); #else - #error aligned_free not supported on your platform +#error aligned_free not supported on your platform #endif } +} // namespace pcl + /** * \brief Macro to add a no-op or a fallthrough attribute based on compiler feature * From f11cf55f7a6b48eec5de465e6b001da296d2172f Mon Sep 17 00:00:00 2001 From: Alexander Date: Tue, 4 May 2021 10:15:08 +0300 Subject: [PATCH 072/123] Add `constexpr` to static member functions for point types, add macro for `if constexpr` (#4735) * static mem functions returning constants made constexpr * static mem functions returning constants made constexpr * static mem functions returning constants made constexpr * static mem functions returning constants made constexpr --- common/include/pcl/impl/point_types.hpp | 36 ++++++++++++------------- common/include/pcl/pcl_macros.h | 6 +++++ 2 files changed, 24 insertions(+), 18 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 609107e48cd..64e6a80d62a 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -1307,7 +1307,7 @@ namespace pcl struct PFHSignature125 { float histogram[125] = {0.f}; - static int descriptorSize () { return 125; } + static constexpr int descriptorSize () { return 125; } inline PFHSignature125 () = default; @@ -1321,7 +1321,7 @@ namespace pcl struct PFHRGBSignature250 { float histogram[250] = {0.f}; - static int descriptorSize () { return 250; } + static constexpr int descriptorSize () { return 250; } inline PFHRGBSignature250 () = default; @@ -1408,7 +1408,7 @@ namespace pcl { float descriptor[1980] = {0.f}; float rf[9] = {0.f}; - static int descriptorSize () { return 1980; } + static constexpr int descriptorSize () { return 1980; } inline ShapeContext1980 () = default; @@ -1423,7 +1423,7 @@ namespace pcl { float descriptor[1960] = {0.f}; float rf[9] = {0.f}; - static int descriptorSize () { return 1960; } + static constexpr int descriptorSize () { return 1960; } inline UniqueShapeContext1960 () = default; @@ -1438,7 +1438,7 @@ namespace pcl { float descriptor[352] = {0.f}; float rf[9] = {0.f}; - static int descriptorSize () { return 352; } + static constexpr int descriptorSize () { return 352; } inline SHOT352 () = default; @@ -1454,7 +1454,7 @@ namespace pcl { float descriptor[1344] = {0.f}; float rf[9] = {0.f}; - static int descriptorSize () { return 1344; } + static constexpr int descriptorSize () { return 1344; } inline SHOT1344 () = default; @@ -1519,7 +1519,7 @@ namespace pcl struct FPFHSignature33 { float histogram[33] = {0.f}; - static int descriptorSize () { return 33; } + static constexpr int descriptorSize () { return 33; } inline FPFHSignature33 () = default; @@ -1533,7 +1533,7 @@ namespace pcl struct VFHSignature308 { float histogram[308] = {0.f}; - static int descriptorSize () { return 308; } + static constexpr int descriptorSize () { return 308; } inline VFHSignature308 () = default; @@ -1547,7 +1547,7 @@ namespace pcl struct GRSDSignature21 { float histogram[21] = {0.f}; - static int descriptorSize () { return 21; } + static constexpr int descriptorSize () { return 21; } inline GRSDSignature21 () = default; @@ -1563,7 +1563,7 @@ namespace pcl float scale = 0.f; float orientation = 0.f; unsigned char descriptor[64] = {0}; - static int descriptorSize () { return 64; } + static constexpr int descriptorSize () { return 64; } inline BRISKSignature512 () = default; @@ -1579,7 +1579,7 @@ namespace pcl struct ESFSignature640 { float histogram[640] = {0.f}; - static int descriptorSize () { return 640; } + static constexpr int descriptorSize () { return 640; } inline ESFSignature640 () = default; @@ -1593,7 +1593,7 @@ namespace pcl struct GASDSignature512 { float histogram[512] = {0.f}; - static int descriptorSize() { return 512; } + static constexpr int descriptorSize() { return 512; } inline GASDSignature512 () = default; @@ -1607,7 +1607,7 @@ namespace pcl struct GASDSignature984 { float histogram[984] = {0.f}; - static int descriptorSize() { return 984; } + static constexpr int descriptorSize() { return 984; } inline GASDSignature984 () = default; @@ -1621,7 +1621,7 @@ namespace pcl struct GASDSignature7992 { float histogram[7992] = {0.f}; - static int descriptorSize() { return 7992; } + static constexpr int descriptorSize() { return 7992; } inline GASDSignature7992 () = default; @@ -1635,7 +1635,7 @@ namespace pcl struct GFPFHSignature16 { float histogram[16] = {0.f}; - static int descriptorSize () { return 16; } + static constexpr int descriptorSize () { return 16; } inline GFPFHSignature16 () = default; @@ -1650,7 +1650,7 @@ namespace pcl { float x = 0.f, y = 0.f, z = 0.f, roll = 0.f, pitch = 0.f, yaw = 0.f; float descriptor[36] = {0.f}; - static int descriptorSize () { return 36; } + static constexpr int descriptorSize () { return 36; } inline Narf36 () = default; @@ -1712,7 +1712,7 @@ namespace pcl struct Histogram { float histogram[N]; - static int descriptorSize () { return N; } + static constexpr int descriptorSize () { return N; } }; struct EIGEN_ALIGN16 _PointWithScale @@ -1861,7 +1861,7 @@ namespace pcl operator << (std::ostream& os, const Histogram& p) { // make constexpr - if (N > 0) + PCL_IF_CONSTEXPR(N > 0) { os << "(" << p.histogram[0]; std::for_each(p.histogram + 1, std::end(p.histogram), diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index dd1ccfbd32b..a86497da87f 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -442,3 +442,9 @@ aligned_free(void* ptr) #else #define PCL_NODISCARD #endif + +#ifdef __cpp_if_constexpr + #define PCL_IF_CONSTEXPR(x) if constexpr(x) +#else + #define PCL_IF_CONSTEXPR(x) if (x) +#endif From 29936f76880261fd334e20242e12c03c11e8e909 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 25 Apr 2021 15:38:57 +0200 Subject: [PATCH 073/123] Optimize includes --- .../pc_source/registered_views_source.h | 2 +- .../include/pcl/apps/in_hand_scanner/icp.h | 2 -- .../pcl/apps/in_hand_scanner/in_hand_scanner.h | 3 +-- .../pcl/apps/in_hand_scanner/input_data_processing.h | 1 - .../pcl/apps/in_hand_scanner/offline_integration.h | 2 -- .../include/pcl/apps/in_hand_scanner/opengl_viewer.h | 2 -- .../pcl/apps/in_hand_scanner/visibility_confidence.h | 1 - apps/in_hand_scanner/src/input_data_processing.cpp | 1 - apps/in_hand_scanner/src/integration.cpp | 1 - apps/in_hand_scanner/src/visibility_confidence.cpp | 1 + apps/include/pcl/apps/nn_classification.h | 1 + apps/src/feature_matching.cpp | 1 - apps/src/openni_klt.cpp | 2 +- apps/src/openni_organized_edge_detection.cpp | 1 - apps/src/stereo_ground_segmentation.cpp | 1 + .../sources/iccv2011/src/build_all_object_models.cpp | 1 + .../sources/iccv2011/src/test_feature_estimation.cpp | 1 + .../sources/iccv2011/src/test_registration.cpp | 2 +- .../content/sources/iccv2011/src/test_surface.cpp | 1 + .../sources/iros2011/src/build_all_object_models.cpp | 1 + .../sources/iros2011/src/test_feature_estimation.cpp | 1 + .../sources/iros2011/src/test_registration.cpp | 2 +- .../content/sources/iros2011/src/test_surface.cpp | 1 + .../openni_narf_keypoint_extraction.cpp | 2 +- .../openni_range_image_visualization.cpp | 2 +- .../sources/pcl_visualizer/pcl_visualizer_demo.cpp | 2 +- .../range_image_visualization.cpp | 2 +- .../content/sources/tracking/tracking_sample.cpp | 11 +---------- .../content/sources/vfh_recognition/build_tree.cpp | 2 +- .../sources/vfh_recognition/nearest_neighbors.cpp | 4 ++-- filters/include/pcl/filters/crop_hull.h | 1 - geometry/include/pcl/geometry/mesh_indices.h | 2 +- gpu/features/test/test_fpfh.cpp | 1 - gpu/kinfu/tools/kinfu_app.cpp | 1 + gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 1 + gpu/people/tools/people_pcd_prob.cpp | 1 - io/include/pcl/io/ensenso_grabber.h | 1 - io/include/pcl/io/file_io.h | 3 ++- io/include/pcl/io/grabber.h | 2 +- io/include/pcl/io/impl/auto_io.hpp | 4 +--- io/include/pcl/io/impl/pcd_io.hpp | 2 +- io/include/pcl/io/oni_grabber.h | 1 - io/include/pcl/io/openni2_grabber.h | 1 - io/include/pcl/io/openni_grabber.h | 2 +- io/include/pcl/io/pcd_io.h | 1 + io/include/pcl/io/ply/byte_order.h | 1 + io/include/pcl/io/ply/ply.h | 1 + io/include/pcl/io/ply/ply_parser.h | 6 +++++- io/include/pcl/io/real_sense_2_grabber.h | 1 - io/include/pcl/io/robot_eye_grabber.h | 1 + io/src/ascii_io.cpp | 2 ++ io/src/hdl_grabber.cpp | 1 - io/src/ifs_io.cpp | 3 ++- io/src/image_grabber.cpp | 3 +++ io/src/obj_io.cpp | 4 +++- io/src/oni_grabber.cpp | 2 +- io/src/openni2_grabber.cpp | 2 +- io/src/openni_camera/openni_device_primesense.cpp | 1 - io/src/openni_camera/openni_device_xtion.cpp | 1 - io/src/openni_camera/openni_driver.cpp | 2 -- io/src/openni_grabber.cpp | 2 +- io/src/pcd_io.cpp | 3 ++- io/src/ply_io.cpp | 2 +- io/src/real_sense_2_grabber.cpp | 1 - io/tools/openni_grabber_example.cpp | 1 + io/tools/openni_pcd_recorder.cpp | 1 + io/tools/pcd_introduce_nan.cpp | 1 + outofcore/tools/outofcore_print.cpp | 1 + registration/include/pcl/registration/elch.h | 1 - registration/include/pcl/registration/impl/elch.hpp | 3 ++- registration/include/pcl/registration/impl/gicp.hpp | 1 - .../include/pcl/registration/impl/joint_icp.hpp | 1 - registration/include/pcl/registration/impl/ndt_2d.hpp | 2 -- registration/include/pcl/registration/lum.h | 1 - .../pcl/sample_consensus/impl/sac_model_circle.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_circle3d.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_cone.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_cylinder.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_sphere.hpp | 2 +- .../pcl/sample_consensus/sac_model_registration.h | 1 - .../pcl/segmentation/edge_aware_plane_comparator.h | 1 - .../pcl/segmentation/euclidean_cluster_comparator.h | 2 +- .../euclidean_plane_coefficient_comparator.h | 1 - .../pcl/segmentation/impl/min_cut_segmentation.hpp | 2 +- .../include/pcl/segmentation/min_cut_segmentation.h | 2 +- .../segmentation/rgb_plane_coefficient_comparator.h | 1 - .../include/pcl/segmentation/supervoxel_clustering.h | 2 +- simulation/tools/sim_viewer.cpp | 1 - test/io/test_grabbers.cpp | 2 ++ test/search/test_flann_search.cpp | 2 +- test/search/test_octree.cpp | 2 +- tools/concatenate_points_pcd.cpp | 1 - tools/fast_bilateral_filter.cpp | 2 ++ tools/grid_min.cpp | 2 ++ tools/hdl_viewer_simple.cpp | 1 - tools/image_grabber_saver.cpp | 1 + tools/image_grabber_viewer.cpp | 3 +-- tools/image_viewer.cpp | 2 -- tools/local_max.cpp | 2 ++ tools/morph.cpp | 2 ++ tools/normal_estimation.cpp | 2 ++ tools/octree_viewer.cpp | 1 - tools/oni_viewer_simple.cpp | 1 - tools/openni2_viewer.cpp | 1 - tools/openni_image.cpp | 2 +- tools/openni_save_image.cpp | 3 +-- tools/openni_viewer.cpp | 1 - tools/openni_viewer_simple.cpp | 1 - tools/passthrough_filter.cpp | 3 ++- tools/pcd2png.cpp | 1 + tools/pcd_grabber_viewer.cpp | 4 ++-- tools/pcd_viewer.cpp | 1 - tools/pcl_video.cpp | 4 +++- tools/png2pcd.cpp | 4 +++- tools/progressive_morphological_filter.cpp | 2 ++ tools/radius_filter.cpp | 2 ++ tools/sac_segmentation_plane.cpp | 2 ++ tools/tiff2pcd.cpp | 2 +- tools/unary_classifier_segment.cpp | 1 + tools/uniform_sampling.cpp | 1 - tools/vlp_viewer.cpp | 2 -- tools/xyz2pcd.cpp | 1 + .../include/pcl/visualization/common/actor_map.h | 3 ++- visualization/src/cloud_viewer.cpp | 1 - visualization/src/histogram_visualizer.cpp | 1 - visualization/src/pcl_visualizer.cpp | 3 ++- 126 files changed, 113 insertions(+), 115 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h index 690c6c59815..1699f85d96a 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/registered_views_source.h @@ -8,7 +8,7 @@ #pragma once #include -#include +#include #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h index 46991846e50..1448564fcbd 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/icp.h @@ -41,8 +41,6 @@ #pragma once #include -#include -#include #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h index b972e66893e..fa2c81db01a 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/in_hand_scanner.h @@ -43,10 +43,9 @@ #include #include #include -#include #include #include - +#include // for connection #include #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h index 63b9cc153e9..46362e9f0ad 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/input_data_processing.h @@ -41,7 +41,6 @@ #pragma once #include -#include #include #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h index cff11995d4b..895fe8a348f 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/offline_integration.h @@ -46,8 +46,6 @@ #include #include #include -#include -#include #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h index a684650c55a..46f73b215f3 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h @@ -44,9 +44,7 @@ #include #include #include -#include #include -#include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h index 086baacbf86..ef4ed2847dc 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/visibility_confidence.h @@ -45,7 +45,6 @@ #include #include #include -#include namespace pcl { diff --git a/apps/in_hand_scanner/src/input_data_processing.cpp b/apps/in_hand_scanner/src/input_data_processing.cpp index 1afbb53dff0..22df6626f9a 100644 --- a/apps/in_hand_scanner/src/input_data_processing.cpp +++ b/apps/in_hand_scanner/src/input_data_processing.cpp @@ -42,7 +42,6 @@ #include #include -#include //////////////////////////////////////////////////////////////////////////////// diff --git a/apps/in_hand_scanner/src/integration.cpp b/apps/in_hand_scanner/src/integration.cpp index 76fca477f30..a779afe127e 100644 --- a/apps/in_hand_scanner/src/integration.cpp +++ b/apps/in_hand_scanner/src/integration.cpp @@ -45,7 +45,6 @@ #include #include -#include #include #include diff --git a/apps/in_hand_scanner/src/visibility_confidence.cpp b/apps/in_hand_scanner/src/visibility_confidence.cpp index d0bda321ff8..fb2ff56f85d 100644 --- a/apps/in_hand_scanner/src/visibility_confidence.cpp +++ b/apps/in_hand_scanner/src/visibility_confidence.cpp @@ -39,6 +39,7 @@ */ #include +#include // for Isometry3f pcl::ihs::Dome::Dome () { diff --git a/apps/include/pcl/apps/nn_classification.h b/apps/include/pcl/apps/nn_classification.h index 701510a9ebb..e2977e90138 100644 --- a/apps/include/pcl/apps/nn_classification.h +++ b/apps/include/pcl/apps/nn_classification.h @@ -41,6 +41,7 @@ #include #include +#include // for FLT_MAX namespace pcl { diff --git a/apps/src/feature_matching.cpp b/apps/src/feature_matching.cpp index 3fda149b8c2..488af48cca1 100644 --- a/apps/src/feature_matching.cpp +++ b/apps/src/feature_matching.cpp @@ -11,7 +11,6 @@ #include #include #include -#include #include #include #include diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index e0adcdcb551..0c37dd93ae2 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -41,9 +41,9 @@ #include #include #include -#include #include +#include // for to_iso_string, local_time #include #define SHOW_FPS 1 diff --git a/apps/src/openni_organized_edge_detection.cpp b/apps/src/openni_organized_edge_detection.cpp index b06f8c2e4ec..2f4d07cb9cb 100644 --- a/apps/src/openni_organized_edge_detection.cpp +++ b/apps/src/openni_organized_edge_detection.cpp @@ -36,7 +36,6 @@ #include #include #include -#include #include #include diff --git a/apps/src/stereo_ground_segmentation.cpp b/apps/src/stereo_ground_segmentation.cpp index c320bc2c2ba..ba7a7f8de3d 100755 --- a/apps/src/stereo_ground_segmentation.cpp +++ b/apps/src/stereo_ground_segmentation.cpp @@ -49,6 +49,7 @@ #include #include #include +#include // for directory_iterator #include diff --git a/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp b/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp index 53ce73c889d..f82bbf2bd53 100644 --- a/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/build_all_object_models.cpp @@ -7,6 +7,7 @@ #include #include #include +#include // for split, is_any_of namespace bf = boost::filesystem; inline void diff --git a/doc/tutorials/content/sources/iccv2011/src/test_feature_estimation.cpp b/doc/tutorials/content/sources/iccv2011/src/test_feature_estimation.cpp index 0d98d57fd56..d3ceb67834a 100644 --- a/doc/tutorials/content/sources/iccv2011/src/test_feature_estimation.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/test_feature_estimation.cpp @@ -6,6 +6,7 @@ #include #include #include +#include // for split int main (int argc, char ** argv) diff --git a/doc/tutorials/content/sources/iccv2011/src/test_registration.cpp b/doc/tutorials/content/sources/iccv2011/src/test_registration.cpp index 33fb8c38c40..59348ce4c3a 100644 --- a/doc/tutorials/content/sources/iccv2011/src/test_registration.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/test_registration.cpp @@ -5,7 +5,7 @@ #include #include #include - +#include // for split #include "load_clouds.h" int diff --git a/doc/tutorials/content/sources/iccv2011/src/test_surface.cpp b/doc/tutorials/content/sources/iccv2011/src/test_surface.cpp index b704f65564b..d22ca6ab939 100644 --- a/doc/tutorials/content/sources/iccv2011/src/test_surface.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/test_surface.cpp @@ -4,6 +4,7 @@ #include #include #include +#include // for split int main (int argc, char ** argv) diff --git a/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp b/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp index 094c9e220da..81736542100 100644 --- a/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp +++ b/doc/tutorials/content/sources/iros2011/src/build_all_object_models.cpp @@ -7,6 +7,7 @@ #include #include #include +#include // for split, is_any_of namespace bf = boost::filesystem; inline void diff --git a/doc/tutorials/content/sources/iros2011/src/test_feature_estimation.cpp b/doc/tutorials/content/sources/iros2011/src/test_feature_estimation.cpp index 0df4ad0e1f0..3e27e60cf40 100644 --- a/doc/tutorials/content/sources/iros2011/src/test_feature_estimation.cpp +++ b/doc/tutorials/content/sources/iros2011/src/test_feature_estimation.cpp @@ -6,6 +6,7 @@ #include #include #include +#include // for split int main (int argc, char ** argv) diff --git a/doc/tutorials/content/sources/iros2011/src/test_registration.cpp b/doc/tutorials/content/sources/iros2011/src/test_registration.cpp index a1c8c92aac8..2fce34395c3 100644 --- a/doc/tutorials/content/sources/iros2011/src/test_registration.cpp +++ b/doc/tutorials/content/sources/iros2011/src/test_registration.cpp @@ -5,7 +5,7 @@ #include #include #include - +#include // for split #include "load_clouds.h" int diff --git a/doc/tutorials/content/sources/iros2011/src/test_surface.cpp b/doc/tutorials/content/sources/iros2011/src/test_surface.cpp index b704f65564b..d22ca6ab939 100644 --- a/doc/tutorials/content/sources/iros2011/src/test_surface.cpp +++ b/doc/tutorials/content/sources/iros2011/src/test_surface.cpp @@ -4,6 +4,7 @@ #include #include #include +#include // for split int main (int argc, char ** argv) diff --git a/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp b/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp index 6f0dd70d955..8e4d130ca95 100644 --- a/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp +++ b/doc/tutorials/content/sources/openni_narf_keypoint_extraction/openni_narf_keypoint_extraction.cpp @@ -4,7 +4,7 @@ #include #include #include -#include +#include // for pcl::getTime #include #include #include diff --git a/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp b/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp index a7cdbdb9da7..dabc5432c36 100644 --- a/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp +++ b/doc/tutorials/content/sources/openni_range_image_visualization/openni_range_image_visualization.cpp @@ -4,7 +4,7 @@ #include #include #include -#include +#include // for pcl::deg2rad #include #include #include diff --git a/doc/tutorials/content/sources/pcl_visualizer/pcl_visualizer_demo.cpp b/doc/tutorials/content/sources/pcl_visualizer/pcl_visualizer_demo.cpp index 376ebe9a620..99d98d58a37 100644 --- a/doc/tutorials/content/sources/pcl_visualizer/pcl_visualizer_demo.cpp +++ b/doc/tutorials/content/sources/pcl_visualizer/pcl_visualizer_demo.cpp @@ -3,7 +3,7 @@ #include #include -#include +#include // for pcl::deg2rad #include #include #include diff --git a/doc/tutorials/content/sources/range_image_visualization/range_image_visualization.cpp b/doc/tutorials/content/sources/range_image_visualization/range_image_visualization.cpp index 2d695b3a2f3..523c1ed2d04 100644 --- a/doc/tutorials/content/sources/range_image_visualization/range_image_visualization.cpp +++ b/doc/tutorials/content/sources/range_image_visualization/range_image_visualization.cpp @@ -1,6 +1,6 @@ #include -#include + #include #include #include diff --git a/doc/tutorials/content/sources/tracking/tracking_sample.cpp b/doc/tutorials/content/sources/tracking/tracking_sample.cpp index 672e6fa2ece..682b4bbc83c 100644 --- a/doc/tutorials/content/sources/tracking/tracking_sample.cpp +++ b/doc/tutorials/content/sources/tracking/tracking_sample.cpp @@ -1,31 +1,22 @@ #include #include #include -#include -#include #include +#include // for transformPointCloud #include #include #include #include -#include #include -#include -#include - -#include -#include - #include #include #include #include #include #include -#include #include #include diff --git a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp index 142d221d086..ecc6cf3e8a6 100644 --- a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp @@ -1,6 +1,5 @@ #include #include -#include #include #include #include @@ -8,6 +7,7 @@ #include #include + typedef std::pair > vfh_model; /** \brief Loads an n-D histogram file as a VFH signature diff --git a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp index 86995357e7c..de785b48269 100644 --- a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp @@ -1,7 +1,7 @@ #include #include #include -#include +#include // for compute3DCentroid #include #include #include @@ -10,7 +10,7 @@ #include #include #include - +#include // for replace_last typedef std::pair > vfh_model; /** \brief Loads an n-D histogram file as a VFH signature diff --git a/filters/include/pcl/filters/crop_hull.h b/filters/include/pcl/filters/crop_hull.h index a24133476d5..26c90654eb9 100644 --- a/filters/include/pcl/filters/crop_hull.h +++ b/filters/include/pcl/filters/crop_hull.h @@ -37,7 +37,6 @@ #pragma once -#include #include #include diff --git a/geometry/include/pcl/geometry/mesh_indices.h b/geometry/include/pcl/geometry/mesh_indices.h index 79cbddc8c9d..f21e1b83a41 100644 --- a/geometry/include/pcl/geometry/mesh_indices.h +++ b/geometry/include/pcl/geometry/mesh_indices.h @@ -40,7 +40,7 @@ #pragma once -#include +#include #include diff --git a/gpu/features/test/test_fpfh.cpp b/gpu/features/test/test_fpfh.cpp index 301468a0c1b..5d2dbb6ed60 100644 --- a/gpu/features/test/test_fpfh.cpp +++ b/gpu/features/test/test_fpfh.cpp @@ -43,7 +43,6 @@ #include #include #include "data_source.hpp" -#include using namespace pcl; using namespace pcl::gpu; diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 6eebd1b0ae8..a18d3dcaa15 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -44,6 +44,7 @@ #include #include +#include // for microsec_clock::local_time #include #include diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index b60dedcc36a..d96b6171de3 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -56,6 +56,7 @@ Work in progress: patch by Marco (AUG,19th 2012) #include #include +#include // for microsec_clock::local_time #include #include diff --git a/gpu/people/tools/people_pcd_prob.cpp b/gpu/people/tools/people_pcd_prob.cpp index a22247b2ef7..c29ac7717f0 100644 --- a/gpu/people/tools/people_pcd_prob.cpp +++ b/gpu/people/tools/people_pcd_prob.cpp @@ -48,7 +48,6 @@ #include #include #include -#include #include #include diff --git a/io/include/pcl/io/ensenso_grabber.h b/io/include/pcl/io/ensenso_grabber.h index f03fd6cd9aa..c25684858db 100644 --- a/io/include/pcl/io/ensenso_grabber.h +++ b/io/include/pcl/io/ensenso_grabber.h @@ -44,7 +44,6 @@ #include #include #include -#include #include #include diff --git a/io/include/pcl/io/file_io.h b/io/include/pcl/io/file_io.h index 54f0856a618..ddb6b7aa16e 100644 --- a/io/include/pcl/io/file_io.h +++ b/io/include/pcl/io/file_io.h @@ -40,10 +40,11 @@ #include // for fromPCLPointCloud2, toPCLPointCloud2 #include // for PointCloud #include // for PCLPointCloud2 -#include #include #include #include // for Quaternionf +#include // for numeric_cast +#include // for iequals namespace pcl { diff --git a/io/include/pcl/io/grabber.h b/io/include/pcl/io/grabber.h index 385ae501ebc..fdbd739c22a 100644 --- a/io/include/pcl/io/grabber.h +++ b/io/include/pcl/io/grabber.h @@ -46,8 +46,8 @@ #include #include #include -#include #include +#include // for connection, signal, ... namespace pcl { diff --git a/io/include/pcl/io/impl/auto_io.hpp b/io/include/pcl/io/impl/auto_io.hpp index 5c2ab7c96aa..6a1b50cf291 100644 --- a/io/include/pcl/io/impl/auto_io.hpp +++ b/io/include/pcl/io/impl/auto_io.hpp @@ -40,12 +40,10 @@ #ifndef PCL_IO_AUTO_IO_IMPL_H_ #define PCL_IO_AUTO_IO_IMPL_H_ -// #include -// #include #include #include #include -// #include +#include // for path namespace pcl { diff --git a/io/include/pcl/io/impl/pcd_io.hpp b/io/include/pcl/io/impl/pcd_io.hpp index 84fb0120200..7f012b4fc01 100644 --- a/io/include/pcl/io/impl/pcd_io.hpp +++ b/io/include/pcl/io/impl/pcd_io.hpp @@ -40,13 +40,13 @@ #ifndef PCL_IO_PCD_IO_IMPL_H_ #define PCL_IO_PCD_IO_IMPL_H_ +#include // for trim #include #include #include #include #include // for getFields, ... #include -#include #include #include diff --git a/io/include/pcl/io/oni_grabber.h b/io/include/pcl/io/oni_grabber.h index 150ca094e59..fa4e86a3ca4 100644 --- a/io/include/pcl/io/oni_grabber.h +++ b/io/include/pcl/io/oni_grabber.h @@ -44,7 +44,6 @@ #ifdef HAVE_OPENNI #include -#include #include #include #include diff --git a/io/include/pcl/io/openni2_grabber.h b/io/include/pcl/io/openni2_grabber.h index c4ce5f0bb9c..e0da353961b 100644 --- a/io/include/pcl/io/openni2_grabber.h +++ b/io/include/pcl/io/openni2_grabber.h @@ -46,7 +46,6 @@ #ifdef HAVE_OPENNI2 #include -#include #include #include #include diff --git a/io/include/pcl/io/openni_grabber.h b/io/include/pcl/io/openni_grabber.h index bbe1332c080..54e2251040e 100644 --- a/io/include/pcl/io/openni_grabber.h +++ b/io/include/pcl/io/openni_grabber.h @@ -45,7 +45,6 @@ #ifdef HAVE_OPENNI #include -#include #include #include #include @@ -54,6 +53,7 @@ #include #include #include +#include // for shared_array namespace pcl { diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index 23f71ef11a4..a3e22fb987d 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -43,6 +43,7 @@ #include #include #include +#include // for file_lock namespace pcl { diff --git a/io/include/pcl/io/ply/byte_order.h b/io/include/pcl/io/ply/byte_order.h index 61316ae07ea..8fb57817558 100644 --- a/io/include/pcl/io/ply/byte_order.h +++ b/io/include/pcl/io/ply/byte_order.h @@ -42,6 +42,7 @@ #include #include +#include // for swap namespace pcl { diff --git a/io/include/pcl/io/ply/ply.h b/io/include/pcl/io/ply/ply.h index 7f3fe1909c6..f658ed69a88 100644 --- a/io/include/pcl/io/ply/ply.h +++ b/io/include/pcl/io/ply/ply.h @@ -41,6 +41,7 @@ #pragma once #include +#include // for int8_t, int16_t, ... /** \file ply.h contains standard typedefs and generic type traits * \author Ares Lagae as part of libply, Nizar Sallem diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h index 55aee22f0c9..64159e6ab6d 100644 --- a/io/include/pcl/io/ply/ply_parser.h +++ b/io/include/pcl/io/ply/ply_parser.h @@ -40,7 +40,6 @@ #pragma once -#include #include #include #include @@ -50,6 +49,11 @@ #include #include #include +#include // for lexical_cast +#include // for inherit +#include // inherit_linearly +#include // for joint_view +#include // for transform namespace pcl { diff --git a/io/include/pcl/io/real_sense_2_grabber.h b/io/include/pcl/io/real_sense_2_grabber.h index f485a326146..6a1a5e6e844 100644 --- a/io/include/pcl/io/real_sense_2_grabber.h +++ b/io/include/pcl/io/real_sense_2_grabber.h @@ -40,7 +40,6 @@ #include #include -#include #include #include #include diff --git a/io/include/pcl/io/robot_eye_grabber.h b/io/include/pcl/io/robot_eye_grabber.h index 546b0d7d08a..6f7c7ec1ebe 100644 --- a/io/include/pcl/io/robot_eye_grabber.h +++ b/io/include/pcl/io/robot_eye_grabber.h @@ -45,6 +45,7 @@ #include #include #include +#include // for shared_array #include #include diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index 4a1971f1a65..ad5cd7fcd25 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -40,6 +40,8 @@ #include #include #include +#include // for lexical_cast +#include // for split #include ////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/hdl_grabber.cpp b/io/src/hdl_grabber.cpp index 8e116e51beb..3774f2f850b 100644 --- a/io/src/hdl_grabber.cpp +++ b/io/src/hdl_grabber.cpp @@ -39,7 +39,6 @@ #include #include -#include #include #include #include diff --git a/io/src/ifs_io.cpp b/io/src/ifs_io.cpp index 8b07c4a3d6e..a7a44db3a97 100644 --- a/io/src/ifs_io.cpp +++ b/io/src/ifs_io.cpp @@ -36,13 +36,14 @@ */ #include -#include #include #include #include #include #include +#include // for exists +#include // for mapped_file_source /////////////////////////////////////////////////////////////////////////////////////////// int diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 7e930ca83cc..ce9ac5521f5 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -41,6 +41,9 @@ #include #include #include +#include // for exists, basename, is_directory, ... +#include // for to_upper_copy +#include // for posix_time #ifdef PCL_BUILT_WITH_VTK #include diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 4bfb891347f..c6cba33c248 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -38,8 +38,10 @@ #include #include #include -#include #include +#include // for lexical_cast +#include // for exists +#include // for split pcl::MTLReader::MTLReader () { diff --git a/io/src/oni_grabber.cpp b/io/src/oni_grabber.cpp index 0dea4cca0ce..76746241fd2 100644 --- a/io/src/oni_grabber.cpp +++ b/io/src/oni_grabber.cpp @@ -42,7 +42,7 @@ #include #include #include -#include // for boost::shared_array +#include // for boost::shared_array #include // for dynamic_pointer_cast #include diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 0150db14aee..b81467f41f5 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -48,9 +48,9 @@ #include #include #include -#include #include #include +#include // for exists using namespace pcl::io::openni2; diff --git a/io/src/openni_camera/openni_device_primesense.cpp b/io/src/openni_camera/openni_device_primesense.cpp index aca1a8a0d36..20072c47cf7 100644 --- a/io/src/openni_camera/openni_device_primesense.cpp +++ b/io/src/openni_camera/openni_device_primesense.cpp @@ -45,7 +45,6 @@ #include #include -#include #include #include diff --git a/io/src/openni_camera/openni_device_xtion.cpp b/io/src/openni_camera/openni_device_xtion.cpp index cd06198ca13..56925743cf3 100644 --- a/io/src/openni_camera/openni_device_xtion.cpp +++ b/io/src/openni_camera/openni_device_xtion.cpp @@ -44,7 +44,6 @@ #endif #include -#include #include #include diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index 070c6b810e0..65382c39218 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -57,8 +57,6 @@ #ifndef _WIN32 #include -#else -#include #endif ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index cd28989079f..50844d4a794 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -44,10 +44,10 @@ #include #include #include -#include #include #include #include +#include // for exists using namespace std::chrono_literals; diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 31254677533..5e1a2466582 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -41,7 +41,6 @@ #include #include #include -#include #include // pcl::utils::ignore #include #include @@ -51,6 +50,8 @@ #include #include +#include // for permissions +#include // for split /////////////////////////////////////////////////////////////////////////////////////////// void diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 775860cefd9..c0bf7c3bf2d 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include #include @@ -49,6 +48,7 @@ // https://www.boost.org/doc/libs/1_70_0/libs/filesystem/doc/index.htm#Coding-guidelines #define BOOST_FILESYSTEM_NO_DEPRECATED #include +#include // for split namespace fs = boost::filesystem; diff --git a/io/src/real_sense_2_grabber.cpp b/io/src/real_sense_2_grabber.cpp index 1e1febbffe7..f5dd3ff9566 100644 --- a/io/src/real_sense_2_grabber.cpp +++ b/io/src/real_sense_2_grabber.cpp @@ -35,7 +35,6 @@ * */ -#include #include #include #include diff --git a/io/tools/openni_grabber_example.cpp b/io/tools/openni_grabber_example.cpp index 28ddb5b5597..32448bfb2f4 100644 --- a/io/tools/openni_grabber_example.cpp +++ b/io/tools/openni_grabber_example.cpp @@ -40,6 +40,7 @@ #include #include #include +#include // for setprecision class SimpleOpenNIProcessor { diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp index 6d30feecb70..a8f7e6f8388 100644 --- a/io/tools/openni_pcd_recorder.cpp +++ b/io/tools/openni_pcd_recorder.cpp @@ -37,6 +37,7 @@ #include #include #include +#include // for to_iso_string, local_time #include #include #include diff --git a/io/tools/pcd_introduce_nan.cpp b/io/tools/pcd_introduce_nan.cpp index 744339988fe..cedebda3662 100644 --- a/io/tools/pcd_introduce_nan.cpp +++ b/io/tools/pcd_introduce_nan.cpp @@ -36,6 +36,7 @@ */ #include +#include // for lexical_cast /** @brief PCL point object */ using PointT = pcl::PointXYZRGBA; diff --git a/outofcore/tools/outofcore_print.cpp b/outofcore/tools/outofcore_print.cpp index 62538b9435d..d8a13a5eb54 100644 --- a/outofcore/tools/outofcore_print.cpp +++ b/outofcore/tools/outofcore_print.cpp @@ -56,6 +56,7 @@ #include #include #include +#include // for replace_first namespace ba = boost::accumulators; diff --git a/registration/include/pcl/registration/elch.h b/registration/include/pcl/registration/elch.h index 736ce6397b6..981b153c23c 100644 --- a/registration/include/pcl/registration/elch.h +++ b/registration/include/pcl/registration/elch.h @@ -40,7 +40,6 @@ #pragma once -#include #include #include #include diff --git a/registration/include/pcl/registration/impl/elch.hpp b/registration/include/pcl/registration/impl/elch.hpp index 011024a3a6e..647386cf880 100644 --- a/registration/include/pcl/registration/impl/elch.hpp +++ b/registration/include/pcl/registration/impl/elch.hpp @@ -42,9 +42,10 @@ #define PCL_REGISTRATION_IMPL_ELCH_H_ #include -#include #include +#include // for dijkstra_shortest_paths + #include #include #include diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index ef039547082..3d03d497cba 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -41,7 +41,6 @@ #ifndef PCL_REGISTRATION_IMPL_GICP_HPP_ #define PCL_REGISTRATION_IMPL_GICP_HPP_ -#include #include namespace pcl { diff --git a/registration/include/pcl/registration/impl/joint_icp.hpp b/registration/include/pcl/registration/impl/joint_icp.hpp index 3fa9a50f9a4..edab731bf9a 100644 --- a/registration/include/pcl/registration/impl/joint_icp.hpp +++ b/registration/include/pcl/registration/impl/joint_icp.hpp @@ -40,7 +40,6 @@ #define PCL_REGISTRATION_IMPL_JOINT_ICP_HPP_ #include -#include #include namespace pcl { diff --git a/registration/include/pcl/registration/impl/ndt_2d.hpp b/registration/include/pcl/registration/impl/ndt_2d.hpp index 687320b3675..6b1ac8800ae 100644 --- a/registration/include/pcl/registration/impl/ndt_2d.hpp +++ b/registration/include/pcl/registration/impl/ndt_2d.hpp @@ -41,8 +41,6 @@ #ifndef PCL_NDT_2D_IMPL_H_ #define PCL_NDT_2D_IMPL_H_ -#include - #include // for SelfAdjointEigenSolver, EigenSolver #include diff --git a/registration/include/pcl/registration/lum.h b/registration/include/pcl/registration/lum.h index fbc64acf2f1..97d2df64408 100644 --- a/registration/include/pcl/registration/lum.h +++ b/registration/include/pcl/registration/lum.h @@ -41,7 +41,6 @@ #pragma once #include -#include #include #include #include diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle.hpp index 58c39b707df..b2607bdea06 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle.hpp @@ -41,7 +41,7 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CIRCLE_H_ -#include +#include // for LevenbergMarquardt #include #include diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp index d93362e92b0..32ccbda77ea 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_circle3d.hpp @@ -41,7 +41,7 @@ #include // for DBL_MAX -#include +#include // for LevenbergMarquardt #include #include diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp index c8c4fed704f..65280ce7823 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cone.hpp @@ -39,7 +39,7 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ -#include +#include // for LevenbergMarquardt #include #include // for getAngle3D #include diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp index 533e7c65931..d21e1a691c6 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_cylinder.hpp @@ -41,7 +41,7 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ -#include +#include // for LevenbergMarquardt #include #include // for getAngle3D #include diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_sphere.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_sphere.hpp index 4def914a2c7..fdb7bb924b1 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_sphere.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_sphere.hpp @@ -41,7 +41,7 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ -#include +#include // for LevenbergMarquardt #include ////////////////////////////////////////////////////////////////////////// diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h b/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h index 51b9b13ea5c..43c15c91fac 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_registration.h @@ -43,7 +43,6 @@ #include #include #include -#include #include #include #include diff --git a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h index c2a4a5eb468..848dd6e8d5b 100644 --- a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h +++ b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h @@ -39,7 +39,6 @@ #pragma once -#include #include namespace pcl diff --git a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h index 4e410519c3d..300fb20f073 100644 --- a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h @@ -39,10 +39,10 @@ #pragma once +#include // for std::set #include #include #include -#include #include diff --git a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h index 29e486d2bb5..b752ac0b6d2 100644 --- a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h @@ -39,7 +39,6 @@ #pragma once -#include #include namespace pcl diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index abdfb81093a..6d0b85ef3c7 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -39,7 +39,7 @@ #ifndef PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ #define PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ -#include +#include // for boykov_kolmogorov_max_flow #include #include #include diff --git a/segmentation/include/pcl/segmentation/min_cut_segmentation.h b/segmentation/include/pcl/segmentation/min_cut_segmentation.h index f2a26897790..d75d2f8ccb7 100644 --- a/segmentation/include/pcl/segmentation/min_cut_segmentation.h +++ b/segmentation/include/pcl/segmentation/min_cut_segmentation.h @@ -38,7 +38,6 @@ #pragma once -#include #include #include #include @@ -47,6 +46,7 @@ #include #include #include +#include // for adjacency_list namespace pcl { diff --git a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h index 263ad8c15b7..5c5c5a926d3 100644 --- a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h @@ -39,7 +39,6 @@ #pragma once -#include #include namespace pcl diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index c3aa569afbb..02377111d23 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -51,7 +51,7 @@ #include #include #include -#include +#include // for ptr_list diff --git a/simulation/tools/sim_viewer.cpp b/simulation/tools/sim_viewer.cpp index d92ee326839..52a73683295 100644 --- a/simulation/tools/sim_viewer.cpp +++ b/simulation/tools/sim_viewer.cpp @@ -53,7 +53,6 @@ #include #include #include -#include #include #include #include diff --git a/test/io/test_grabbers.cpp b/test/io/test_grabbers.cpp index 4394e944317..a7c794aad00 100644 --- a/test/io/test_grabbers.cpp +++ b/test/io/test_grabbers.cpp @@ -7,6 +7,8 @@ #include #include #include +#include // for directory_iterator, extension +#include // for to_upper_copy using namespace std::chrono_literals; diff --git a/test/search/test_flann_search.cpp b/test/search/test_flann_search.cpp index 663157f194e..8d1786c023b 100644 --- a/test/search/test_flann_search.cpp +++ b/test/search/test_flann_search.cpp @@ -41,7 +41,7 @@ #include // for copyPointCloud #include #include -#include +#include // for pcl::search::KdTree #include #include #include diff --git a/test/search/test_octree.cpp b/test/search/test_octree.cpp index 215d9186951..19d320efdce 100644 --- a/test/search/test_octree.cpp +++ b/test/search/test_octree.cpp @@ -40,7 +40,7 @@ #include #include #include -#include +#include // for pcl::search::Octree using namespace pcl; using namespace octree; diff --git a/tools/concatenate_points_pcd.cpp b/tools/concatenate_points_pcd.cpp index 9a9364ab732..f96125f9893 100644 --- a/tools/concatenate_points_pcd.cpp +++ b/tools/concatenate_points_pcd.cpp @@ -47,7 +47,6 @@ #include #include #include -#include Eigen::Vector4f translation; Eigen::Quaternionf orientation; diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index e05998738d8..4bf9835cf0f 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -41,6 +41,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/grid_min.cpp b/tools/grid_min.cpp index 9174164bdc0..3ca8d011aad 100644 --- a/tools/grid_min.cpp +++ b/tools/grid_min.cpp @@ -44,6 +44,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/hdl_viewer_simple.cpp b/tools/hdl_viewer_simple.cpp index 48c3fa55d72..8ae390867db 100644 --- a/tools/hdl_viewer_simple.cpp +++ b/tools/hdl_viewer_simple.cpp @@ -43,7 +43,6 @@ #include #include #include -#include #include #include diff --git a/tools/image_grabber_saver.cpp b/tools/image_grabber_saver.cpp index b327fe78188..764e672d8f9 100644 --- a/tools/image_grabber_saver.cpp +++ b/tools/image_grabber_saver.cpp @@ -40,6 +40,7 @@ #include #include #include +#include // for exists using pcl::console::print_error; using pcl::console::print_info; diff --git a/tools/image_grabber_viewer.cpp b/tools/image_grabber_viewer.cpp index 4ce088b8942..e7117baffc6 100644 --- a/tools/image_grabber_viewer.cpp +++ b/tools/image_grabber_viewer.cpp @@ -40,13 +40,12 @@ #include #include #include -#include #include #include -#include #include #include +#include // for exists using namespace std::chrono_literals; using pcl::console::print_error; diff --git a/tools/image_viewer.cpp b/tools/image_viewer.cpp index f8840eff140..94e048f8562 100644 --- a/tools/image_viewer.cpp +++ b/tools/image_viewer.cpp @@ -38,11 +38,9 @@ #include #include -#include //fps calculations #include #include #include -#include #include int diff --git a/tools/local_max.cpp b/tools/local_max.cpp index 775f66f54b9..b7f1392e7e1 100644 --- a/tools/local_max.cpp +++ b/tools/local_max.cpp @@ -44,6 +44,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/morph.cpp b/tools/morph.cpp index f75090be3b4..1fb9bd15fce 100644 --- a/tools/morph.cpp +++ b/tools/morph.cpp @@ -44,6 +44,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index f3f1403b160..34401a8bcb2 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -45,6 +45,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/octree_viewer.cpp b/tools/octree_viewer.cpp index 8b7bbe95b28..8b40f6c28ae 100644 --- a/tools/octree_viewer.cpp +++ b/tools/octree_viewer.cpp @@ -40,7 +40,6 @@ #include #include #include -#include #include #include diff --git a/tools/oni_viewer_simple.cpp b/tools/oni_viewer_simple.cpp index dcb577895c8..fcf331d6f23 100644 --- a/tools/oni_viewer_simple.cpp +++ b/tools/oni_viewer_simple.cpp @@ -42,7 +42,6 @@ #include //fps calculations #include #include -#include #include #include diff --git a/tools/openni2_viewer.cpp b/tools/openni2_viewer.cpp index 2427af083a3..a6ecabd01f9 100644 --- a/tools/openni2_viewer.cpp +++ b/tools/openni2_viewer.cpp @@ -41,7 +41,6 @@ #include #include #include -#include #include #include #include diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index eff110c069e..356858f5c0f 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -39,7 +39,6 @@ #include //fps calculations #include #include -#include #include #include #include @@ -47,6 +46,7 @@ #include #include +#include // for ptime, to_iso_string, ... #include #include diff --git a/tools/openni_save_image.cpp b/tools/openni_save_image.cpp index f579e4ca4ef..e7cad451778 100644 --- a/tools/openni_save_image.cpp +++ b/tools/openni_save_image.cpp @@ -46,11 +46,10 @@ #include #include -#include "boost.h" - #include #include #include +#include // for to_iso_string, local_time #define SHOW_FPS 1 diff --git a/tools/openni_viewer.cpp b/tools/openni_viewer.cpp index 6853be295e3..f35543f6525 100644 --- a/tools/openni_viewer.cpp +++ b/tools/openni_viewer.cpp @@ -39,7 +39,6 @@ #include //fps calculations #include #include -#include #include #include #include diff --git a/tools/openni_viewer_simple.cpp b/tools/openni_viewer_simple.cpp index 7236603ff42..0599ebdb868 100644 --- a/tools/openni_viewer_simple.cpp +++ b/tools/openni_viewer_simple.cpp @@ -46,7 +46,6 @@ #include #include #include -#include #include #include diff --git a/tools/passthrough_filter.cpp b/tools/passthrough_filter.cpp index 32791c75209..87c976f4b9c 100644 --- a/tools/passthrough_filter.cpp +++ b/tools/passthrough_filter.cpp @@ -37,12 +37,13 @@ */ #include -#include #include #include #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/pcd2png.cpp b/tools/pcd2png.cpp index 3e8d9f8a399..4254098addf 100644 --- a/tools/pcd2png.cpp +++ b/tools/pcd2png.cpp @@ -49,6 +49,7 @@ #include #include #include +#include // for lexical_cast using namespace pcl; using namespace pcl::io; diff --git a/tools/pcd_grabber_viewer.cpp b/tools/pcd_grabber_viewer.cpp index d75525d0a42..3dd923b9be8 100644 --- a/tools/pcd_grabber_viewer.cpp +++ b/tools/pcd_grabber_viewer.cpp @@ -39,10 +39,10 @@ #include #include #include -#include #include #include - +#include // for exists, extension, ... +#include // for to_upper_copy #include #include diff --git a/tools/pcd_viewer.cpp b/tools/pcd_viewer.cpp index 175e66d811c..e8cdf1248c6 100644 --- a/tools/pcd_viewer.cpp +++ b/tools/pcd_viewer.cpp @@ -44,7 +44,6 @@ #include #include #include -#include #include #include #include diff --git a/tools/pcl_video.cpp b/tools/pcl_video.cpp index 7c84aed0784..b9dbf4939f9 100644 --- a/tools/pcl_video.cpp +++ b/tools/pcl_video.cpp @@ -52,7 +52,9 @@ #include #include #include -#include "boost.h" +#include // for date +#include // for local_time +#include // for time_duration using namespace std::chrono_literals; namespace bpt = boost::posix_time; diff --git a/tools/png2pcd.cpp b/tools/png2pcd.cpp index c519a414b91..e0c4e47699a 100644 --- a/tools/png2pcd.cpp +++ b/tools/png2pcd.cpp @@ -51,7 +51,9 @@ #include #include #include -#include +#include // for vtkImageData +#include // for vtkSmartPointer +#include // for vtkPNGReader #define RED_MULTIPLIER 0.299 #define GREEN_MULTIPLIER 0.587 diff --git a/tools/progressive_morphological_filter.cpp b/tools/progressive_morphological_filter.cpp index 8f8c6275c41..b6ea2d002e9 100644 --- a/tools/progressive_morphological_filter.cpp +++ b/tools/progressive_morphological_filter.cpp @@ -46,6 +46,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/radius_filter.cpp b/tools/radius_filter.cpp index 39371899887..60cb56fb855 100644 --- a/tools/radius_filter.cpp +++ b/tools/radius_filter.cpp @@ -40,6 +40,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using PointType = pcl::PointXYZ; diff --git a/tools/sac_segmentation_plane.cpp b/tools/sac_segmentation_plane.cpp index 1a7a1edb059..335eb910155 100644 --- a/tools/sac_segmentation_plane.cpp +++ b/tools/sac_segmentation_plane.cpp @@ -43,6 +43,8 @@ #include #include #include +#include // for path, exists, ... +#include // for to_upper_copy using namespace pcl; using namespace pcl::io; diff --git a/tools/tiff2pcd.cpp b/tools/tiff2pcd.cpp index 0d862c26fa7..8602f859c51 100644 --- a/tools/tiff2pcd.cpp +++ b/tools/tiff2pcd.cpp @@ -48,7 +48,7 @@ #include #include -#include +#include // for vtkImageData #include #include #include diff --git a/tools/unary_classifier_segment.cpp b/tools/unary_classifier_segment.cpp index c7972ec17a2..1a9c6e06fb5 100644 --- a/tools/unary_classifier_segment.cpp +++ b/tools/unary_classifier_segment.cpp @@ -45,6 +45,7 @@ #include // for removeNaNFromPointCloud #include +#include // for path, exists, ... using namespace pcl; using namespace pcl::io; diff --git a/tools/uniform_sampling.cpp b/tools/uniform_sampling.cpp index 48e15f82ed7..2d92fd41f24 100644 --- a/tools/uniform_sampling.cpp +++ b/tools/uniform_sampling.cpp @@ -44,7 +44,6 @@ #include #include #include -#include using namespace pcl; using namespace pcl::io; diff --git a/tools/vlp_viewer.cpp b/tools/vlp_viewer.cpp index 5d281a3df11..e823ece668b 100644 --- a/tools/vlp_viewer.cpp +++ b/tools/vlp_viewer.cpp @@ -44,9 +44,7 @@ #include #include #include -#include #include -#include #include diff --git a/tools/xyz2pcd.cpp b/tools/xyz2pcd.cpp index 2ade40cc9dd..40848038391 100644 --- a/tools/xyz2pcd.cpp +++ b/tools/xyz2pcd.cpp @@ -38,6 +38,7 @@ #include #include #include +#include // for split using namespace pcl; using namespace pcl::io; diff --git a/visualization/include/pcl/visualization/common/actor_map.h b/visualization/include/pcl/visualization/common/actor_map.h index acd9fd247f5..68025d919b1 100644 --- a/visualization/include/pcl/visualization/common/actor_map.h +++ b/visualization/include/pcl/visualization/common/actor_map.h @@ -37,7 +37,8 @@ #pragma once -#include +#include // for PointCloudGeometryHandler +#include // for PointCloudColorHandler #include #include diff --git a/visualization/src/cloud_viewer.cpp b/visualization/src/cloud_viewer.cpp index d670dbb7ec2..002134f69d6 100644 --- a/visualization/src/cloud_viewer.cpp +++ b/visualization/src/cloud_viewer.cpp @@ -37,7 +37,6 @@ #include #include -#include #include #include diff --git a/visualization/src/histogram_visualizer.cpp b/visualization/src/histogram_visualizer.cpp index 090e8b5d67b..9d7b7ef7c26 100644 --- a/visualization/src/histogram_visualizer.cpp +++ b/visualization/src/histogram_visualizer.cpp @@ -42,7 +42,6 @@ #include #include #include -#include #include #include diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 0a110ee5763..370d5ed2243 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -58,7 +58,6 @@ #include #include -#include #include #include @@ -100,12 +99,14 @@ #include #include #include +#include // for BOOST_VERSION #if (BOOST_VERSION >= 106600) #include #else #include #endif #include +#include // for split #include // pcl::utils::ignore #include From c9f35621b582ed80949ae822f9161c674f92ea16 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 26 Apr 2021 18:51:17 +0200 Subject: [PATCH 074/123] Update line numbers in tutorial --- doc/tutorials/content/tracking.rst | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/doc/tutorials/content/tracking.rst b/doc/tutorials/content/tracking.rst index a9ba99d8505..8625bfc3b7e 100644 --- a/doc/tutorials/content/tracking.rst +++ b/doc/tutorials/content/tracking.rst @@ -60,40 +60,40 @@ Now, let's break down the code piece by piece. .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 227-242 + :lines: 219-234 First, in main function, these lines set the parameters for tracking. .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 246-257 + :lines: 237-249 Here, we set likelihood function which tracker use when calculate weights. You can add more likelihood function as you like. By default, there are normals likelihood and color likelihood functions. When you want to add other likelihood function, all you have to do is initialize new Coherence Class and add the Coherence instance to coherence variable with addPointCoherence function. .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 259-272 + :lines: 251-264 In this part, we set the point cloud loaded from pcd file as reference model to tracker and also set model's transform values. .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 173-180 + :lines: 165-172 Until the counter variable become equal to 10, we ignore the input point cloud, because the point cloud at first few frames often have noise. After counter variable reach to 10 frame, at each loop, we set downsampled input point cloud to tracker and the tracker will compute particles movement. .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 82-82 + :lines: 74-74 In drawParticles function, you can get particles's positions by calling getParticles(). .. literalinclude:: sources/tracking/tracking_sample.cpp :language: cpp - :lines: 116-117 + :lines: 108-109 From ed0c79eeb7a1c2296d5ec7132bbc6f11f81bd096 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 26 Apr 2021 19:09:01 +0200 Subject: [PATCH 075/123] Deprecate unneeded headers --- apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h | 2 +- apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h | 2 +- io/include/pcl/io/boost.h | 2 +- io/include/pcl/io/io.h | 2 +- registration/include/pcl/registration/boost.h | 2 +- registration/include/pcl/registration/transforms.h | 2 +- sample_consensus/include/pcl/sample_consensus/eigen.h | 2 +- segmentation/include/pcl/segmentation/boost.h | 2 +- 8 files changed, 8 insertions(+), 8 deletions(-) diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h index 5575dccbd68..68491e6ff07 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h @@ -43,6 +43,6 @@ #ifdef __GNUC__ # pragma GCC system_header #endif - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") #include #include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h index 7c1208e399b..ccbefab4d34 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h @@ -43,7 +43,7 @@ #ifdef __GNUC__ # pragma GCC system_header #endif - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") #include #include #include diff --git a/io/include/pcl/io/boost.h b/io/include/pcl/io/boost.h index 685b36ae8e7..be19192f2f6 100644 --- a/io/include/pcl/io/boost.h +++ b/io/include/pcl/io/boost.h @@ -36,7 +36,7 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") #if defined __GNUC__ # pragma GCC system_header #endif diff --git a/io/include/pcl/io/io.h b/io/include/pcl/io/io.h index e579aab7aa0..ab579c77a80 100644 --- a/io/include/pcl/io/io.h +++ b/io/include/pcl/io/io.h @@ -38,5 +38,5 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/io.h directly.") #include diff --git a/registration/include/pcl/registration/boost.h b/registration/include/pcl/registration/boost.h index f5aa5b814a6..6a6f17d115d 100644 --- a/registration/include/pcl/registration/boost.h +++ b/registration/include/pcl/registration/boost.h @@ -38,7 +38,7 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") #if defined __GNUC__ #pragma GCC system_header #endif diff --git a/registration/include/pcl/registration/transforms.h b/registration/include/pcl/registration/transforms.h index 3101974d530..2f4bfb79cfa 100644 --- a/registration/include/pcl/registration/transforms.h +++ b/registration/include/pcl/registration/transforms.h @@ -39,5 +39,5 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/transforms.h directly.") #include diff --git a/sample_consensus/include/pcl/sample_consensus/eigen.h b/sample_consensus/include/pcl/sample_consensus/eigen.h index 6d4f64900b5..63d733321cc 100644 --- a/sample_consensus/include/pcl/sample_consensus/eigen.h +++ b/sample_consensus/include/pcl/sample_consensus/eigen.h @@ -38,7 +38,7 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") #if defined __GNUC__ # pragma GCC system_header #endif diff --git a/segmentation/include/pcl/segmentation/boost.h b/segmentation/include/pcl/segmentation/boost.h index 40c3aac5f77..6ef50c3865b 100644 --- a/segmentation/include/pcl/segmentation/boost.h +++ b/segmentation/include/pcl/segmentation/boost.h @@ -39,7 +39,7 @@ */ #pragma once - +PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") #ifdef __GNUC__ #pragma GCC system_header #endif From 78dc48d6a4836d1ecee9dd1ceedefe8a3b6877be Mon Sep 17 00:00:00 2001 From: Hang Yan Date: Wed, 5 May 2021 19:48:28 +0800 Subject: [PATCH 076/123] Fixed `PCL_WARNINGS_ARE_ERRORS` option and some compile warnings (#4695) * fixed PCL_WARNINGS_ARE_ERRORS option in CMakeLists * fixed -Werror=class-memaccess in pcl/common/include/pcl/common/impl/io.hpp fixed compile error like this, when using -Werror: pcl/common/include/pcl/common/impl/io.hpp:139:12: error: 'void* memcpy(void*, const void*, size_t)' copying an object of non-trivial type 'struct pcl::PointNormal' from an array of 'const struct pcl::PointXYZ' [-Werror=class-memaccess] * fixed some memset on non-POD types * fixed new errors * restored 3rd opennurbs modification * added compile flags for 3rd party & fixed deprecated copy * fixed errors & set copy functions to default * Update surface/include/pcl/surface/impl/convex_hull.hpp fixed redundancy code with already defined data type Co-authored-by: Kunal Tyagi * fixed hull size in convex_hull.hpp * added type AlignedVector for pcl/types.h * fixed include library of Eigen::aligned_allocator * fixed noexcept-type errors & added exclusive rules in CMakeLists * resolved conflicts with master * added inline comments * added rules and fixed codes for compile on GPU * made unsigned declaration more explict * fixed noexcept-type error in test_common.cpp * Moved for-loop into empty templated function * Moved copyPointCloudMemcpy into detail namespace Co-authored-by: Kunal Tyagi --- CMakeLists.txt | 7 ++-- .../in_hand_scanner/impl/common_types.hpp | 2 ++ .../pcl/apps/point_cloud_editor/selection.h | 5 +++ common/include/pcl/common/impl/io.hpp | 34 +++++++++++++------ common/include/pcl/types.h | 8 +++++ common/src/parse.cpp | 10 ++++-- cuda/CMakeLists.txt | 4 ++- cuda/io/src/debayering.cu | 4 +-- .../pcl/features/impl/integral_image2D.hpp | 4 +-- gpu/CMakeLists.txt | 6 +++- outofcore/CMakeLists.txt | 9 +++++ surface/CMakeLists.txt | 15 ++++++++ .../include/pcl/surface/impl/convex_hull.hpp | 9 +++-- test/common/test_common.cpp | 2 +- test/gpu/octree/perfomance.cpp | 5 +-- visualization/CMakeLists.txt | 6 ++++ 16 files changed, 101 insertions(+), 29 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index beb00c8e4b5..1ff0cd718e1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -105,9 +105,10 @@ if(CMAKE_COMPILER_IS_GNUCXX) string(APPEND CMAKE_CXX_FLAGS " -Wabi") endif() string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS}") - if(PCL_WARNINGS_ARE_ERRORS) - string(APPEND CMAKE_CXX_FLAGS " -Werror") - endif() + endif() + + if(PCL_WARNINGS_ARE_ERRORS) + string(APPEND CMAKE_CXX_FLAGS " -Werror -fno-strict-aliasing") endif() if("${CMAKE_SHARED_LINKER_FLAGS}" STREQUAL "" AND NOT CMAKE_SYSTEM_NAME STREQUAL "Darwin") diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/impl/common_types.hpp b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/impl/common_types.hpp index 76f82bc3036..a0e5a1ebb38 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/impl/common_types.hpp +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/impl/common_types.hpp @@ -99,6 +99,8 @@ namespace pcl this->directions = other.directions; } + inline PointIHS& operator=(const PointIHS& other) = default; + inline PointIHS (const pcl::PointXYZRGBNormal& other, const float weight) { this->x = other.x; diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selection.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selection.h index 3e744e30e88..7855e1711cf 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selection.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selection.h @@ -60,6 +60,11 @@ class Selection : public Statistics registerStats(); } + /// @brief Copy constructor. + /// @param selection a const reference to a selection object whose + /// properties will be copied. + Selection (const Selection& selection) = default; + /// @brief Equal operator /// @param selection a const reference to a selection object whose /// properties will be copied. diff --git a/common/include/pcl/common/impl/io.hpp b/common/include/pcl/common/impl/io.hpp index 4a147385f5b..d6d93aaff12 100644 --- a/common/include/pcl/common/impl/io.hpp +++ b/common/include/pcl/common/impl/io.hpp @@ -117,6 +117,28 @@ getFieldsList (const pcl::PointCloud &) return (result); } +namespace detail +{ + + template void + copyPointCloudMemcpy (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out) + { + // Iterate over each point, if the point types of two clouds are different + for (std::size_t i = 0; i < cloud_in.size (); ++i) + copyPoint (cloud_in[i], cloud_out[i]); + } + + + template void + copyPointCloudMemcpy (const pcl::PointCloud &cloud_in, + pcl::PointCloud &cloud_out) + { + // Use std::copy directly, if the point types of two clouds are same + std::copy (&cloud_in[0], (&cloud_in[0]) + cloud_in.size (), &cloud_out[0]); + } + +} // namespace detail template void copyPointCloud (const pcl::PointCloud &cloud_in, @@ -131,16 +153,8 @@ copyPointCloud (const pcl::PointCloud &cloud_in, cloud_out.sensor_origin_ = cloud_in.sensor_origin_; cloud_out.resize (cloud_in.size ()); - if (cloud_in.empty ()) - return; - - if (isSamePointType ()) - // Copy the whole memory block - memcpy (&cloud_out[0], &cloud_in[0], cloud_in.size () * sizeof (PointInT)); - else - // Iterate over each point - for (std::size_t i = 0; i < cloud_in.size (); ++i) - copyPoint (cloud_in[i], cloud_out[i]); + if (!cloud_in.empty ()) + detail::copyPointCloudMemcpy (cloud_in, cloud_out); } diff --git a/common/include/pcl/types.h b/common/include/pcl/types.h index ca2e8e69e9a..06cfb6a577d 100644 --- a/common/include/pcl/types.h +++ b/common/include/pcl/types.h @@ -49,6 +49,8 @@ #include +#include + namespace pcl { namespace detail { @@ -129,5 +131,11 @@ namespace pcl * \brief Type used for indices in PCL */ using Indices = IndicesAllocator<>; + + /** + * \brief Type used for aligned vector of Eigen objects in PCL + */ + template + using AlignedVector = std::vector>; } // namespace pcl diff --git a/common/src/parse.cpp b/common/src/parse.cpp index b6d67eeb9d7..1d8d9d63e91 100644 --- a/common/src/parse.cpp +++ b/common/src/parse.cpp @@ -181,14 +181,20 @@ parse_argument (int argc, const char * const * argv, const char * str, T &val) n int pcl::console::parse_argument (int argc, const char * const * argv, const char * str, double &val) { - return parse_generic(strtod, argc, argv, str, val); + // added lambda wrapper for `strtod` to handle noexcept-type warning in GCC 7, + // refer to: https://stackoverflow.com/questions/46798456/handling-gccs-noexcept-type-warning + const auto strtod_l = [](const char *str, char **str_end){ return strtod(str, str_end); }; + return parse_generic(strtod_l, argc, argv, str, val); } //////////////////////////////////////////////////////////////////////////////// int pcl::console::parse_argument (int argc, const char * const * argv, const char * str, float &val) { - return parse_generic(strtof, argc, argv, str, val); + // added lambda wrapper for `strtof` to handle noexcept-type warning in GCC 7, + // refer to: https://stackoverflow.com/questions/46798456/handling-gccs-noexcept-type-warning + const auto strtof_l = [](const char *str, char **str_end){ return strtof(str, str_end); }; + return parse_generic(strtof_l, argc, argv, str, val); } //////////////////////////////////////////////////////////////////////////////// diff --git a/cuda/CMakeLists.txt b/cuda/CMakeLists.txt index 72cbd38b772..c327f95e5dc 100644 --- a/cuda/CMakeLists.txt +++ b/cuda/CMakeLists.txt @@ -11,7 +11,9 @@ endif() if(CMAKE_COMPILER_IS_GNUCXX) string(REPLACE "-Wold-style-cast" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") string(REPLACE "-Wno-invalid-offsetof" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-conversion -Wno-unused-parameter -Wno-unused-variable -Wno-unused-function -Wno-unused-but-set-variable") + string(APPEND CMAKE_CXX_FLAGS " -Wno-conversion -Wno-unused-parameter -Wno-unused-variable -Wno-unused-function -Wno-unused-but-set-variable") + # allow deprecation warnings in Eigen(3.3.7)/Core, see here: https://gitlab.kitware.com/vtk/vtk/-/issues/17661 + string(APPEND CMAKE_CXX_FLAGS " -Wno-error=cpp") endif() collect_subproject_directory_names("${CMAKE_CURRENT_SOURCE_DIR}" "CMakeLists.txt" PCL_CUDA_MODULES_NAMES PCL_CUDA_MODULES_DIRS) diff --git a/cuda/io/src/debayering.cu b/cuda/io/src/debayering.cu index 9c0e55d9ac2..b9f23e95a7f 100644 --- a/cuda/io/src/debayering.cu +++ b/cuda/io/src/debayering.cu @@ -114,8 +114,8 @@ namespace pcl OpenNIRGB DebayerBilinear::operator () (int index) const { // get position - int xIdx = index % width; - int yIdx = index / width; + unsigned int xIdx = index % width; + unsigned int yIdx = index / width; OpenNIRGB result; diff --git a/features/include/pcl/features/impl/integral_image2D.hpp b/features/include/pcl/features/impl/integral_image2D.hpp index 653dfa2e3d2..a0f424807f4 100644 --- a/features/include/pcl/features/impl/integral_image2D.hpp +++ b/features/include/pcl/features/impl/integral_image2D.hpp @@ -158,7 +158,7 @@ IntegralImage2D::computeIntegralImages ( { ElementType* previous_row = &first_order_integral_image_[0]; ElementType* current_row = previous_row + (width_ + 1); - memset (previous_row, 0, sizeof (ElementType) * (width_ + 1)); + *previous_row = ElementType::Zero(width_ + 1); unsigned* count_previous_row = &finite_values_integral_image_[0]; unsigned* count_current_row = count_previous_row + (width_ + 1); @@ -189,7 +189,7 @@ IntegralImage2D::computeIntegralImages ( { SecondOrderType* so_previous_row = &second_order_integral_image_[0]; SecondOrderType* so_current_row = so_previous_row + (width_ + 1); - memset (so_previous_row, 0, sizeof (SecondOrderType) * (width_ + 1)); + *so_previous_row = SecondOrderType::Zero(width_ + 1); SecondOrderType so_element; for (unsigned rowIdx = 0; rowIdx < height_; ++rowIdx, data += row_stride, diff --git a/gpu/CMakeLists.txt b/gpu/CMakeLists.txt index 99f36bf6405..45daad5c6ef 100644 --- a/gpu/CMakeLists.txt +++ b/gpu/CMakeLists.txt @@ -11,7 +11,11 @@ endif() if(CMAKE_COMPILER_IS_GNUCXX) string(REPLACE "-Wold-style-cast" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") string(REPLACE "-Wno-invalid-offsetof" "" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-conversion -Wno-unused-parameter -Wno-unused-variable -Wno-unused-function -Wno-unused-but-set-variable") + string(APPEND CMAKE_CXX_FLAGS " -Wno-conversion -Wno-unused-parameter -Wno-unused-variable -Wno-unused-function -Wno-unused-but-set-variable") + # allow deprecation warnings in Eigen(3.3.7)/Core, see here: https://gitlab.kitware.com/vtk/vtk/-/issues/17661 + string(APPEND CMAKE_CXX_FLAGS " -Wno-error=cpp") + # allow maybe-uninitialized warnings from thrust library. + string(APPEND CMAKE_CXX_FLAGS " -Wno-error=maybe-uninitialized") endif() collect_subproject_directory_names("${CMAKE_CURRENT_SOURCE_DIR}" "CMakeLists.txt" PCL_GPU_MODULES_NAMES PCL_GPU_MODULES_DIRS) diff --git a/outofcore/CMakeLists.txt b/outofcore/CMakeLists.txt index 5860204bf5f..7d8073c2547 100644 --- a/outofcore/CMakeLists.txt +++ b/outofcore/CMakeLists.txt @@ -58,6 +58,15 @@ set(visualization_incs "include/pcl/${SUBSYS_NAME}/visualization/scene.h" "include/pcl/${SUBSYS_NAME}/visualization/viewport.h" ) + +# Code in subdirectory `visualization` may use deprecated declarations when using OpenGLv1 +# Add the GCC exclusive rules for -Werror only for OpenGLv1 compile to avoid build interruption +if(VTK_RENDERING_BACKEND_OPENGL_VERSION VERSION_LESS 2) + if(CMAKE_COMPILER_IS_GNUCXX) + add_compile_options("-Wno-error=deprecated-declarations") + endif() +endif() + set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index eae2d3ae011..d8a8566ea3b 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -49,6 +49,21 @@ endif() set(BUILD_surface_on_nurbs 0 CACHE BOOL "Fitting NURBS to point-clouds using openNURBS") if(BUILD_surface_on_nurbs) + # Add the GCC exclusive rules for -Werror only for 3rd party OpenNURBS compile + # -Wno-error = (deprecated-declarations, class-memaccess, deprecated-copy, uninitialized, parentheses) + # Note: class-memaccess warning added exactly in GCC 8.0, see here: https://www.gnu.org/software/gcc/gcc-8/changes.html + # deprecated-copy warning added exactly in GCC 9.1, see here: https://www.gnu.org/software/gcc/gcc-9/changes.html + # Since GCC8 and GCC9 are still widely-used, compile version check is required for the two options. + if(CMAKE_COMPILER_IS_GNUCXX) + add_compile_options("-Wno-error=deprecated-declarations" "-Wno-error=uninitialized" "-Wno-error=parentheses") + if (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 8.0) + add_compile_options("-Wno-error=class-memaccess") + endif() + if (CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 9.1) + add_compile_options("-Wno-error=deprecated-copy") + endif() + endif() + include(src/3rdparty/opennurbs/openNURBS.cmake) include(src/on_nurbs/on_nurbs.cmake) endif() diff --git a/surface/include/pcl/surface/impl/convex_hull.hpp b/surface/include/pcl/surface/impl/convex_hull.hpp index 3d911b7a0a4..b8cbb5f14fd 100644 --- a/surface/include/pcl/surface/impl/convex_hull.hpp +++ b/surface/include/pcl/surface/impl/convex_hull.hpp @@ -214,15 +214,14 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto } int num_vertices = qh num_vertices; - hull.resize (num_vertices); - memset (&hull.points[0], hull.size (), sizeof (PointInT)); + + hull.clear(); + hull.resize(num_vertices, PointInT{}); vertexT * vertex; int i = 0; - std::vector, Eigen::aligned_allocator > > idx_points (num_vertices); - idx_points.resize (hull.size ()); - memset (&idx_points[0], hull.size (), sizeof (std::pair)); + AlignedVector> idx_points (num_vertices); FORALLvertices { diff --git a/test/common/test_common.cpp b/test/common/test_common.cpp index 964bf2b0984..5829090bda6 100644 --- a/test/common/test_common.cpp +++ b/test/common/test_common.cpp @@ -503,7 +503,7 @@ TEST (PCL, computeMedian) EXPECT_EQ(median1, 3.5f); std::vector vector2{1.0, 25.0, 9.0, 4.0, 16.0}; - const auto median2 = computeMedian (vector2.begin (), vector2.end (), static_cast(std::sqrt)); + const auto median2 = computeMedian (vector2.begin (), vector2.end (), [](const double& x){ return std::sqrt(x); }); EXPECT_EQ(median2, 3.0); std::vector vector3{1.0, 2.0, 6.0, 5.0, 4.0, 3.0}; diff --git a/test/gpu/octree/perfomance.cpp b/test/gpu/octree/perfomance.cpp index 4e80d32d8d9..d8cbc40b178 100644 --- a/test/gpu/octree/perfomance.cpp +++ b/test/gpu/octree/perfomance.cpp @@ -223,8 +223,9 @@ TEST(PCL_OctreeGPU, performance) std::cout << "====== Approx nearest search =====" << std::endl; { - ScopeTime up("gpu-approx-nearest-batch-all"); - octree_device.approxNearestSearch(queries_device, result_device); + ScopeTime up("gpu-approx-nearest-batch-all"); + pcl::gpu::Octree::ResultSqrDists sqr_distance; + octree_device.approxNearestSearch(queries_device, result_device, sqr_distance); } { diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index ed2c4ca1b99..e676a202599 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -61,6 +61,12 @@ if(VTK_RENDERING_BACKEND_OPENGL_VERSION VERSION_LESS 2) "src/vtk/vtkVertexBufferObject.cxx" "src/vtk/vtkVertexBufferObjectMapper.cxx" ) + + # Code in this module may use deprecated declarations when using OpenGLv1 + # Add the GCC exclusive rules for -Werror only for OpenGLv1 compile to avoid build interruption + if(CMAKE_COMPILER_IS_GNUCXX) + add_compile_options("-Wno-error=deprecated-declarations") + endif() endif() if(NOT (${VTK_VERSION} VERSION_LESS 9.0)) From 11ab21b71c8e9fd3e35d86143743b35aaa6dcc71 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 18 Apr 2021 19:58:07 +0200 Subject: [PATCH 077/123] Add more output for sac test that sometimes fails --- test/sample_consensus/test_sample_consensus.cpp | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/test/sample_consensus/test_sample_consensus.cpp b/test/sample_consensus/test_sample_consensus.cpp index e81a8e3ae6c..5d56c571cb6 100644 --- a/test/sample_consensus/test_sample_consensus.cpp +++ b/test/sample_consensus/test_sample_consensus.cpp @@ -110,6 +110,16 @@ TYPED_TEST(SacTest, InfiniteLoop) SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere (cloud.makeShared ())); TypeParam sac (model, 0.03); + // This test sometimes fails for LMedS on azure, but always passes when run locally. + // Enable all output for LMedS, so that when it fails next time, we hopefully see why. + // This can be removed again when the failure reason is found and fixed. + int debug_verbosity_level = 0; + const auto previous_verbosity_level = pcl::console::getVerbosityLevel(); + if (std::is_same>::value) { + debug_verbosity_level = 2; + pcl::console::setVerbosityLevel(pcl::console::L_VERBOSE); + } + // Set up timed conditions std::condition_variable cv; std::mutex mtx; @@ -117,7 +127,7 @@ TYPED_TEST(SacTest, InfiniteLoop) // Create the RANSAC object std::thread thread ([&] () { - sac.computeModel (0); + sac.computeModel (debug_verbosity_level); // Notify things are done std::lock_guard lock (mtx); @@ -135,6 +145,8 @@ TYPED_TEST(SacTest, InfiniteLoop) // release lock to avoid deadlock lock.unlock(); thread.join (); + + pcl::console::setVerbosityLevel(previous_verbosity_level); // reset verbosity level } int From 28320f56ca66a44182666d43fc025957bfd36f47 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 18 Apr 2021 20:55:44 +0200 Subject: [PATCH 078/123] Improve test_organized_index - do not use geometry::distance. That is (partly) optimized for speed, but for the tests, accuracy is most important. Use custom point_distance function instead - store random seed and print it with SCOPED_TRACE, so that tests are reproducible --- test/search/test_organized_index.cpp | 48 +++++++++++++++++++--------- 1 file changed, 33 insertions(+), 15 deletions(-) diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index 2a5c3c56494..683e7476958 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -39,7 +39,6 @@ #include #include #include -#include #include #include #include @@ -49,6 +48,16 @@ using namespace pcl; std::string pcd_filename; +// Here we want a very precise distance function, speed is less important. So we use +// double precision, unlike euclideanDistance() in pcl/common/distances and distance() +// in pcl/common/geometry which use float (single precision) and possibly vectorization +template inline double +point_distance(const PointT& p1, const PointT& p2) +{ + const double x_diff = p1.x - p2.x, y_diff = p1.y - p2.y, z_diff = p1.z - p2.z; + return std::sqrt(x_diff * x_diff + y_diff * y_diff + z_diff * z_diff); +} + // helper class for priority queue class prioPointQueueEntry { @@ -79,7 +88,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search) // instantiate point cloud PointCloud::Ptr cloudIn (new PointCloud ()); - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); // create organized search search::OrganizedNeighbor organizedNeighborSearch; @@ -135,7 +146,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search) for (auto it = cloudIn->begin(); it != cloudIn->end(); ++it) { - const auto pointDist = geometry::distance(*it, searchPoint); + const auto pointDist = point_distance(*it, searchPoint); prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it)); pointCandidates.push (pointEntry); } @@ -174,7 +185,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search_Kinec // instantiate point cloud - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); // create organized search search::OrganizedNeighbor organizedNeighborSearch; @@ -226,7 +239,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search_Kinec // push all points and their distance to the search point into a priority queue - bruteforce approach. for (auto it = cloudIn->begin(); it != cloudIn->end(); ++it) { - const auto pointDist = geometry::distance(*it, searchPoint); + const auto pointDist = point_distance(*it, searchPoint); prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it)); pointCandidates.push (pointEntry); } @@ -251,7 +264,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) { constexpr unsigned int test_runs = 10; - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); search::OrganizedNeighbor organizedNeighborSearch; std::vector k_indices; @@ -299,7 +314,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) { - const auto pointDist = geometry::distance(*it, searchPoint); + const auto pointDist = point_distance(*it, searchPoint); if (pointDist <= searchRadius) { @@ -319,7 +334,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) // check if result from organized radius search can be also found in bruteforce search for (const auto it : cloudNWRSearch) { - auto const pointDist = geometry::distance((*cloudIn)[it], searchPoint); + const auto pointDist = point_distance((*cloudIn)[it], searchPoint); ASSERT_LE (pointDist, searchRadius); } @@ -327,7 +342,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) // check if bruteforce result from organized radius search can be also found in bruteforce search for (const auto it : cloudSearchBruteforce) { - const auto pointDist = geometry::distance((*cloudIn)[it], searchPoint); + const auto pointDist = point_distance((*cloudIn)[it], searchPoint); ASSERT_LE (pointDist, searchRadius); } @@ -344,7 +359,8 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_Benchmark_Test) { constexpr unsigned int test_runs = 10; - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); search::OrganizedNeighbor organizedNeighborSearch; @@ -396,7 +412,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) { - const auto pointDist = geometry::distance(*it, searchPoint); + const auto pointDist = point_distance(*it, searchPoint); if (pointDist <= searchRadius) { @@ -436,7 +452,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ return; } constexpr unsigned int test_runs = 10; - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); search::OrganizedNeighbor organizedNeighborSearch; @@ -510,7 +528,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) { - const auto pointDist = geometry::distance(*it, searchPoint); + const auto pointDist = point_distance(*it, searchPoint); if (pointDist <= searchRadius) { @@ -522,7 +540,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ // check if result from organized radius search can be also found in bruteforce search for (const auto it : cloudNWRSearch) { - double pointDist = geometry::distance((*cloudIn)[it], searchPoint); + const auto pointDist = point_distance((*cloudIn)[it], searchPoint); ASSERT_LE (pointDist, searchRadius); } @@ -530,7 +548,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ // check if bruteforce result from organized radius search can be also found in bruteforce search for (const auto it : cloudSearchBruteforce) { - double pointDist = geometry::distance((*cloudIn)[it], searchPoint); + const auto pointDist = point_distance((*cloudIn)[it], searchPoint); ASSERT_LE (pointDist, searchRadius); } From 75f06c3d37e86816d0370b5b15ebc8c5f8e089bb Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 26 Apr 2021 20:43:36 +0200 Subject: [PATCH 079/123] Add SCOPED_TRACE to more tests --- test/search/test_octree.cpp | 12 +++++++++--- test/search/test_organized.cpp | 8 ++++++-- 2 files changed, 15 insertions(+), 5 deletions(-) diff --git a/test/search/test_octree.cpp b/test/search/test_octree.cpp index 215d9186951..54159107274 100644 --- a/test/search/test_octree.cpp +++ b/test/search/test_octree.cpp @@ -76,7 +76,9 @@ TEST (PCL, Octree_Pointcloud_Nearest_K_Neighbour_Search) // instantiate point cloud PointCloud::Ptr cloudIn (new PointCloud ()); - srand (static_cast (time (nullptr))); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); std::priority_queue::VectorType> pointCandidates; @@ -173,7 +175,9 @@ TEST (PCL, Octree_Pointcloud_Approx_Nearest_Neighbour_Search) // instantiate point cloud PointCloud::Ptr cloudIn (new PointCloud ()); - srand (time (NULL)); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); double voxelResolution = 0.1; @@ -275,7 +279,9 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search) PointCloud::Ptr cloudIn (new PointCloud ()); PointCloud::Ptr cloudOut (new PointCloud ()); - srand (static_cast (time (nullptr))); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); for (unsigned int test_id = 0; test_id < test_runs; test_id++) { diff --git a/test/search/test_organized.cpp b/test/search/test_organized.cpp index ae2dcb4697c..c974b3e7179 100644 --- a/test/search/test_organized.cpp +++ b/test/search/test_organized.cpp @@ -79,7 +79,9 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) // instantiate point cloud PointCloud::Ptr cloudIn (new PointCloud ()); - srand (int (time (nullptr))); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); // create organized search search::OrganizedNeighbor organizedNeighborSearch; @@ -180,7 +182,9 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search) { constexpr unsigned int test_runs = 10; - srand (int (time (nullptr))); + const unsigned int seed = time (nullptr); + srand (seed); + SCOPED_TRACE("seed=" + std::to_string(seed)); search::OrganizedNeighbor organizedNeighborSearch; From 10190eb94701205485d07bde5e0c1f03ddf12a6a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 30 Apr 2021 18:46:47 +0200 Subject: [PATCH 080/123] Add more output to (k)fpcs test --- registration/include/pcl/registration/impl/ia_fpcs.hpp | 9 +++++++-- test/registration/test_kfpcs_ia.cpp | 3 +++ 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index 61f610523b9..d089c8a0bca 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -178,7 +178,10 @@ pcl::registration::FPCSInitialAlignment(std::time(NULL)) ^ omp_get_thread_num()); + const unsigned int seed = + static_cast(std::time(NULL)) ^ omp_get_thread_num(); + std::srand(seed); + PCL_DEBUG("[%s::computeTransformation] Using seed=%u\n", reg_name_.c_str(), seed); #pragma omp for schedule(dynamic) #endif for (int i = 0; i < max_iterations_; i++) { @@ -236,7 +239,9 @@ bool pcl::registration::FPCSInitialAlignment:: initCompute() { - std::srand(static_cast(std::time(nullptr))); + const unsigned int seed = std::time(nullptr); + std::srand(seed); + PCL_DEBUG("[%s::initCompute] Using seed=%u\n", reg_name_.c_str(), seed); // basic pcl initialization if (!pcl::PCLBase::initCompute()) diff --git a/test/registration/test_kfpcs_ia.cpp b/test/registration/test_kfpcs_ia.cpp index 81cda560b03..3fe305164d5 100644 --- a/test/registration/test_kfpcs_ia.cpp +++ b/test/registration/test_kfpcs_ia.cpp @@ -52,6 +52,8 @@ PointCloud cloud_source, cloud_target; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, KFPCSInitialAlignment) { + const auto previous_verbosity_level = pcl::console::getVerbosityLevel(); + pcl::console::setVerbosityLevel(pcl::console::L_VERBOSE); // create shared pointers PointCloud::Ptr cloud_source_ptr, cloud_target_ptr; cloud_source_ptr = cloud_source.makeShared (); @@ -93,6 +95,7 @@ TEST (PCL, KFPCSInitialAlignment) EXPECT_EQ (cloud_source_aligned.size (), cloud_source.size ()); EXPECT_NEAR (angle3d, 0.f, max_angle3d); EXPECT_NEAR (translation3d, 0.f, max_translation3d); + pcl::console::setVerbosityLevel(previous_verbosity_level); // reset verbosity level } From db76e0c5f627acdacf9b7a0422342ebe89ae8eee Mon Sep 17 00:00:00 2001 From: Kosmas Tsiakas Date: Fri, 7 May 2021 17:06:32 +0300 Subject: [PATCH 081/123] Fix typo in kdtree_search.cpp tutorial source (#1) NKN changed to KNN. --- .../sources/kdtree_search/kdtree_search.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp b/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp index d2b99cfa2ef..c53e3f5f268 100644 --- a/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp +++ b/doc/tutorials/content/sources/kdtree_search/kdtree_search.cpp @@ -38,21 +38,21 @@ main () int K = 10; - std::vector pointIdxNKNSearch(K); - std::vector pointNKNSquaredDistance(K); + std::vector pointIdxKNNSearch(K); + std::vector pointKNNSquaredDistance(K); std::cout << "K nearest neighbor search at (" << searchPoint.x << " " << searchPoint.y << " " << searchPoint.z << ") with K=" << K << std::endl; - if ( kdtree.nearestKSearch (searchPoint, K, pointIdxNKNSearch, pointNKNSquaredDistance) > 0 ) + if ( kdtree.nearestKSearch (searchPoint, K, pointIdxKNNSearch, pointKNNSquaredDistance) > 0 ) { - for (std::size_t i = 0; i < pointIdxNKNSearch.size (); ++i) - std::cout << " " << (*cloud)[ pointIdxNKNSearch[i] ].x - << " " << (*cloud)[ pointIdxNKNSearch[i] ].y - << " " << (*cloud)[ pointIdxNKNSearch[i] ].z - << " (squared distance: " << pointNKNSquaredDistance[i] << ")" << std::endl; + for (std::size_t i = 0; i < pointIdxKNNSearch.size (); ++i) + std::cout << " " << (*cloud)[ pointIdxKNNSearch[i] ].x + << " " << (*cloud)[ pointIdxKNNSearch[i] ].y + << " " << (*cloud)[ pointIdxKNNSearch[i] ].z + << " (squared distance: " << pointKNNSquaredDistance[i] << ")" << std::endl; } // Neighbors within radius search From a380379f282ce8f762a973b1df7c4d54e6a418ac Mon Sep 17 00:00:00 2001 From: Jacob Seibert Date: Fri, 7 May 2021 20:07:17 +0200 Subject: [PATCH 082/123] Fix missing verb in sample_consensus doc --- doc/tutorials/content/walkthrough.rst | 2 +- sample_consensus/sample_consensus.doxy | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index 8f3a9baa6c8..03ea403e3b2 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -376,7 +376,7 @@ Sample Consensus **Background** - The *sample_consensus* library holds SAmple Consensus (SAC) methods like RANSAC and models like planes and cylinders. These can combined freely in order to detect specific models and their parameters in point clouds. + The *sample_consensus* library holds SAmple Consensus (SAC) methods like RANSAC and models like planes and cylinders. These can be combined freely in order to detect specific models and their parameters in point clouds. A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial `_ diff --git a/sample_consensus/sample_consensus.doxy b/sample_consensus/sample_consensus.doxy index aeaf62d401b..a73462a99ca 100644 --- a/sample_consensus/sample_consensus.doxy +++ b/sample_consensus/sample_consensus.doxy @@ -4,7 +4,7 @@ \section secSampleConsensusPresentation Overview The pcl_sample_consensus library holds SAmple Consensus (SAC) methods like - RANSAC and models like planes and cylinders. These can + RANSAC and models like planes and cylinders. These can be combined freely in order to detect specific models and their parameters in point clouds. Some of the models implemented in this library include: lines, planes, cylinders, and spheres. Plane fitting From 52c3d73fc1ea3c65bbccdd5db066314d510e65cf Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 25 Nov 2020 12:38:33 +0100 Subject: [PATCH 083/123] Fix ensenso_grabber --- io/src/ensenso_grabber.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/io/src/ensenso_grabber.cpp b/io/src/ensenso_grabber.cpp index 06cdabadf49..53263e8a469 100644 --- a/io/src/ensenso_grabber.cpp +++ b/io/src/ensenso_grabber.cpp @@ -123,9 +123,17 @@ pcl::EnsensoGrabber::enumDevices () const for (int n = 0; n < cams.count (); ++n) { +#if NXLIB_VERSION_MAJOR > 2 PCL_INFO ("%s %s %s\n", cams[n][itmSerialNumber].asString ().c_str (), cams[n][itmModelName].asString ().c_str (), - cams[n][itmStatus].asString ().c_str ()); + cams[n][itmStatus][itmOpen].asBool() + ? "Open" + : (cams[n][itmStatus][itmAvailable].asBool() ? "Available" : "In Use")); +#else + PCL_INFO ("%s %s %s\n", cams[n][itmSerialNumber].asString().c_str(), + cams[n][itmModelName].asString().c_str(), + cams[n][itmStatus].asString().c_str()); +#endif } PCL_INFO ("\n"); } From 84b7abfcc9c8dc5c8a6840420983e3ca4f159e4d Mon Sep 17 00:00:00 2001 From: Heiko Thiel Date: Sun, 9 May 2021 11:19:36 +0200 Subject: [PATCH 084/123] Remove definition of QT_NO_DEBUG as it will be automatically set since Qt 5.1.1 --- apps/cloud_composer/ComposerTool.cmake | 1 - 1 file changed, 1 deletion(-) diff --git a/apps/cloud_composer/ComposerTool.cmake b/apps/cloud_composer/ComposerTool.cmake index cfef108043d..fc92006faaa 100644 --- a/apps/cloud_composer/ComposerTool.cmake +++ b/apps/cloud_composer/ComposerTool.cmake @@ -16,7 +16,6 @@ function(define_composer_tool TOOL_NAME TOOL_SOURCES TOOL_HEADERS DEPS) endif() add_definitions(${QT_DEFINITIONS}) add_definitions(-DQT_PLUGIN) - target_compile_definitions(${TOOL_TARGET} PUBLIC $<$:-DQT_NO_DEBUG>) add_definitions(-DQT_SHARED) target_link_libraries(${TOOL_TARGET} pcl_cc_tool_interface pcl_common pcl_io ${DEPS} Qt5::Widgets) From 82f4f07da04769058ff54a916ea6eb5a335439b3 Mon Sep 17 00:00:00 2001 From: Heiko Thiel Date: Sun, 9 May 2021 23:03:34 +0200 Subject: [PATCH 085/123] Fix compile issue due to missing include under MSVC 2019 --- .../include/pcl/outofcore/outofcore_breadth_first_iterator.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h b/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h index 86d84297570..14efd5a1ae0 100644 --- a/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h +++ b/outofcore/include/pcl/outofcore/outofcore_breadth_first_iterator.h @@ -39,6 +39,9 @@ #pragma once #include + +#include + namespace pcl { namespace outofcore From 77c27c35e14e3e2a753d97639eb591336a8c6ce6 Mon Sep 17 00:00:00 2001 From: Hang Yan Date: Tue, 11 May 2021 20:17:54 +0800 Subject: [PATCH 086/123] Use range-based for & `std::find` to modernize codes in `segmentation` (#4738) Co-authored-by: Lars Glud --- .../pcl/segmentation/extract_clusters.h | 8 +-- .../pcl/segmentation/impl/region_growing.hpp | 19 +++---- .../segmentation/impl/region_growing_rgb.hpp | 50 +++++++------------ .../segmentation/impl/unary_classifier.hpp | 15 +++--- 4 files changed, 34 insertions(+), 58 deletions(-) diff --git a/segmentation/include/pcl/segmentation/extract_clusters.h b/segmentation/include/pcl/segmentation/extract_clusters.h index 6e4b2108158..d7234ade46f 100644 --- a/segmentation/include/pcl/segmentation/extract_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_clusters.h @@ -251,16 +251,16 @@ namespace pcl Indices nn_indices; std::vector nn_distances; // Process all points in the indices vector - for (std::size_t i = 0; i < indices.size (); ++i) + for (const auto& point_idx : indices) { - if (processed[indices[i]]) + if (processed[point_idx]) continue; Indices seed_queue; int sq_idx = 0; - seed_queue.push_back (indices[i]); + seed_queue.push_back (point_idx); - processed[indices[i]] = true; + processed[point_idx] = true; while (sq_idx < static_cast (seed_queue.size ())) { diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index b14c5b42f5d..d4787ab94e5 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -611,20 +611,13 @@ pcl::RegionGrowing::getSegmentFromPoint (pcl::index_t index, pc // to which this point belongs for (const auto& i_segment : clusters_) { - bool segment_was_found = false; - for (const auto& i_point : (i_segment.indices)) - { - if (i_point == index) - { - segment_was_found = true; - cluster.indices.clear (); - cluster.indices.reserve (i_segment.indices.size ()); - std::copy (i_segment.indices.begin (), i_segment.indices.end (), std::back_inserter (cluster.indices)); - break; - } - } - if (segment_was_found) + const auto it = std::find (i_segment.indices.cbegin (), i_segment.indices.cend (), index); + if (it != i_segment.indices.cend()) { + // if segment was found + cluster.indices.clear (); + cluster.indices.reserve (i_segment.indices.size ()); + std::copy (i_segment.indices.begin (), i_segment.indices.end (), std::back_inserter (cluster.indices)); break; } }// next segment diff --git a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp index 718c5e96ce9..8d6520a5a2e 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp @@ -482,24 +482,19 @@ pcl::RegionGrowingRGB::applyRegionMergingAlgorithm () num_seg_in_homogeneous_region[i_reg] = 0; final_segment_number -= 1; - int nghbr_number = static_cast (region_neighbours[reg_index].size ()); - for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) + for (auto& nghbr : region_neighbours[reg_index]) { - if ( segment_labels_[ region_neighbours[reg_index][i_nghbr].second ] == reg_index ) + if ( segment_labels_[ nghbr.second ] == reg_index ) { - region_neighbours[reg_index][i_nghbr].first = std::numeric_limits::max (); - region_neighbours[reg_index][i_nghbr].second = 0; + nghbr.first = std::numeric_limits::max (); + nghbr.second = 0; } } - nghbr_number = static_cast (region_neighbours[i_reg].size ()); - for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) + for (const auto& nghbr : region_neighbours[i_reg]) { - if ( segment_labels_[ region_neighbours[i_reg][i_nghbr].second ] != reg_index ) + if ( segment_labels_[ nghbr.second ] != reg_index ) { - std::pair pair; - pair.first = region_neighbours[i_reg][i_nghbr].first; - pair.second = region_neighbours[i_reg][i_nghbr].second; - region_neighbours[reg_index].push_back (pair); + region_neighbours[reg_index].push_back (nghbr); } } region_neighbours[i_reg].clear (); @@ -533,11 +528,9 @@ pcl::RegionGrowingRGB::findRegionNeighbours (std::vector< std:: for (int i_reg = 0; i_reg < region_number; i_reg++) { - int segment_num = static_cast (regions_in[i_reg].size ()); - neighbours_out[i_reg].reserve (segment_num * region_neighbour_number_); - for (int i_seg = 0; i_seg < segment_num; i_seg++) + neighbours_out[i_reg].reserve (regions_in[i_reg].size () * region_neighbour_number_); + for (const auto& curr_segment : regions_in[i_reg]) { - int curr_segment = regions_in[i_reg][i_seg]; int nghbr_number = static_cast (segment_neighbours_[curr_segment].size ()); std::pair pair; for (int i_nghbr = 0; i_nghbr < nghbr_number; i_nghbr++) @@ -571,10 +564,8 @@ pcl::RegionGrowingRGB::assembleRegions (std::vector counter; counter.resize (num_regions, 0); - int point_number = static_cast (indices_->size ()); - for (int i_point = 0; i_point < point_number; i_point++) + for (const auto& point_index : (*indices_)) { - int point_index = (*indices_)[i_point]; int index = point_labels_[point_index]; index = segment_labels_[index]; clusters_[index].indices[ counter[index] ] = point_index; @@ -735,22 +726,15 @@ pcl::RegionGrowingRGB::getSegmentFromPoint (pcl::index_t index, } // if we have already made the segmentation, then find the segment // to which this point belongs - for (auto i_segment = clusters_.cbegin (); i_segment != clusters_.cend (); i_segment++) + for (const auto& i_segment : clusters_) { - bool segment_was_found = false; - for (std::size_t i_point = 0; i_point < i_segment->indices.size (); i_point++) - { - if (i_segment->indices[i_point] == index) - { - segment_was_found = true; - cluster.indices.clear (); - cluster.indices.reserve (i_segment->indices.size ()); - std::copy (i_segment->indices.begin (), i_segment->indices.end (), std::back_inserter (cluster.indices)); - break; - } - } - if (segment_was_found) + const auto it = std::find (i_segment.indices.cbegin (), i_segment.indices.cend (), index); + if (it != i_segment.indices.cend()) { + // if segment was found + cluster.indices.clear (); + cluster.indices.reserve (i_segment.indices.size ()); + std::copy (i_segment.indices.begin (), i_segment.indices.end (), std::back_inserter (cluster.indices)); break; } }// next segment diff --git a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp index 133d27d28fd..354956f02ba 100644 --- a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp +++ b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp @@ -174,25 +174,24 @@ pcl::UnaryClassifier::getCloudWithLabel (typename pcl::PointCloud fields; int label_idx = -1; - pcl::PointCloud point; label_idx = pcl::getFieldIndex ("label", fields); if (label_idx != -1) { - for (std::size_t i = 0; i < in->size (); i++) + for (const auto& point : (*in)) { // get the 'label' field std::uint32_t label; - memcpy (&label, reinterpret_cast (&(*in)[i]) + fields[label_idx].offset, sizeof(std::uint32_t)); + memcpy (&label, reinterpret_cast (&point) + fields[label_idx].offset, sizeof(std::uint32_t)); if (static_cast (label) == label_num) { - pcl::PointXYZ point; + pcl::PointXYZ tmp; // X Y Z - point.x = (*in)[i].x; - point.y = (*in)[i].y; - point.z = (*in)[i].z; - out->points.push_back (point); + tmp.x = point.x; + tmp.y = point.y; + tmp.z = point.z; + out->push_back (tmp); } } out->width = out->size (); From 270e05128b5915057dc1cfd93ab2304051960a20 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Wed, 12 May 2021 10:30:57 +0200 Subject: [PATCH 087/123] Add formal documentation of PCD binary_compressed format (#4753) --- doc/tutorials/content/pcd_file_format.rst | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/content/pcd_file_format.rst b/doc/tutorials/content/pcd_file_format.rst index 210b37becf9..688da23b86f 100644 --- a/doc/tutorials/content/pcd_file_format.rst +++ b/doc/tutorials/content/pcd_file_format.rst @@ -151,7 +151,7 @@ As of version 0.7, the PCD header contains the following entries: * **DATA** - specifies the data type that the point cloud data is stored in. As - of version 0.7, two data types are supported: *ascii* and *binary*. See the + of version 0.7, three data types are supported: *ascii*, *binary*, and *binary_compressed*. See the next section for more details. @@ -178,7 +178,7 @@ As of version 0.7, the PCD header contains the following entries: Data storage types ------------------ -As of version 0.7, the **.PCD** file format uses two different modes for storing data: +As of version 0.7, the **.PCD** file format uses three different modes for storing data: * in **ASCII** form, with each point on a new line:: @@ -198,6 +198,8 @@ As of version 0.7, the **.PCD** file format uses two different modes for storing `pcl::PointCloud.points` array/vector. On Linux systems, we use `mmap`/`munmap` operations for the fastest possible read/write access to the data. +* in **binary_compressed** form. The body (everything after the header) starts with a 32 bit unsigned binary number which specifies the size in bytes of the data in *compressed* form. Next is another 32 bit unsigned binary number which specifies the size in bytes of the data in *uncompressed* form. Then follows the compressed data. The compression and decompression is done using Marc Lehmann's LZF algorithm. It is mediocre in terms of size reduction, but very fast. For typical point clouds, the compressed data has 30 to 60 percent of the original size. Before compressing, the data is reordered to improve compression, from the standard array-of-structures layout to a structure-of-arrays layout. So for example a cloud with three points and fields x, y, z would be reordered from xyzxyzxyz to xxxyyyzzz. + Storing point cloud data in both a simple ascii form with each point on a line, space or tab separated, without any other characters on it, as well as in a From 1ae76606d5cc266af282241f4a023372626eb604 Mon Sep 17 00:00:00 2001 From: "Taehong Jeong (Hugh)" Date: Fri, 14 May 2021 04:27:02 +0900 Subject: [PATCH 088/123] Fix `PolygonMesh::concatenate` and its unit test (#4745) * Update PolygonMesh.h * Update test_polygon_mesh.cpp ensure that each vertex id in a polygon is always in the correct range * Update test_polygon_mesh.cpp use EXPECT_EQ_VECTORS for simplicity * Update test_polygon_mesh.cpp fix for the lambda capture issue (https://dev.azure.com/PointCloudLibrary/pcl/_build/results?buildId=18956&view=logs&j=8042da28-3549-5cef-c93d-1a000d12f42a&t=118ad2c4-6739-5a83-709b-f149f9853975&l=192) * Update test_polygon_mesh.cpp - refectored to copy gnd truth for modification - added comments * Update test_polygon_mesh.cpp - moved the temp vector out of the loop - removed redundant comments * Update test_polygon_mesh.cpp - used assignment operator instead - put brackets in one-liner foreach loop Co-authored-by: duhuanxianzi --- common/include/pcl/PolygonMesh.h | 3 ++- test/common/test_polygon_mesh.cpp | 30 +++++++++++++++--------------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/common/include/pcl/PolygonMesh.h b/common/include/pcl/PolygonMesh.h index ae610dcc34f..55d69995ade 100644 --- a/common/include/pcl/PolygonMesh.h +++ b/common/include/pcl/PolygonMesh.h @@ -30,6 +30,8 @@ namespace pcl static bool concatenate (pcl::PolygonMesh &mesh1, const pcl::PolygonMesh &mesh2) { + const auto point_offset = mesh1.cloud.width * mesh1.cloud.height; + bool success = pcl::PCLPointCloud2::concatenate(mesh1.cloud, mesh2.cloud); if (success == false) { return false; @@ -37,7 +39,6 @@ namespace pcl // Make the resultant polygon mesh take the newest stamp mesh1.header.stamp = std::max(mesh1.header.stamp, mesh2.header.stamp); - const auto point_offset = mesh1.cloud.width * mesh1.cloud.height; std::transform(mesh2.polygons.begin (), mesh2.polygons.end (), std::back_inserter (mesh1.polygons), diff --git a/test/common/test_polygon_mesh.cpp b/test/common/test_polygon_mesh.cpp index 4f2d41a218d..d03038ab192 100644 --- a/test/common/test_polygon_mesh.cpp +++ b/test/common/test_polygon_mesh.cpp @@ -91,11 +91,13 @@ TEST(PolygonMesh, concatenate_cloud) TEST(PolygonMesh, concatenate_vertices) { + const std::size_t size = 15; + PolygonMesh test, dummy; - test.cloud.width = 10; - test.cloud.height = 5; + // The algorithm works regardless of the organization. + test.cloud.width = dummy.cloud.width = size; + test.cloud.height = dummy.cloud.height = 1; - const std::size_t size = 15; for (std::size_t i = 0; i < size; ++i) { dummy.polygons.emplace_back(); @@ -111,18 +113,16 @@ TEST(PolygonMesh, concatenate_vertices) EXPECT_EQ(2 * dummy.polygons.size(), test.polygons.size()); const auto cloud_size = test.cloud.width * test.cloud.height; - for (std::size_t i = 0; i < dummy.polygons.size(); ++i) - { - EXPECT_EQ(dummy.polygons[i].vertices.size(), test.polygons[i].vertices.size()); - EXPECT_EQ(dummy.polygons[i].vertices.size(), - test.polygons[i + dummy.polygons.size()].vertices.size()); - for (std::size_t j = 0; j < size; ++j) - { - EXPECT_EQ(dummy.polygons[i].vertices[j], - test.polygons[i].vertices[j]); - EXPECT_EQ(dummy.polygons[i].vertices[j] + cloud_size, - test.polygons[i + dummy.polygons.size()].vertices[j]); - } + for (const auto& polygon : test.polygons) + for (const auto& vertex : polygon.vertices) + EXPECT_LT(vertex, cloud_size); + + pcl::Indices vertices(size); + for (std::size_t i = 0; i < size; ++i) { + vertices = dummy.polygons[i].vertices; + EXPECT_EQ_VECTORS(vertices, test.polygons[i].vertices); + for (auto& vertex : vertices) { vertex += size; } + EXPECT_EQ_VECTORS(vertices, test.polygons[i + size].vertices); } } From 5d4625033784e1ed5f42f27fb5ab2cb01032d5d7 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 26 Mar 2020 14:32:31 +0100 Subject: [PATCH 089/123] Add windows container. --- .ci/azure-pipelines/azure-pipelines.yaml | 19 +++++++++++++------ .ci/azure-pipelines/build/windows.yaml | 20 ++++---------------- 2 files changed, 17 insertions(+), 22 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 69881c08317..6ddc39600e7 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -16,6 +16,10 @@ pr: resources: containers: + - container: winx86 + image: pointcloudlibrary/env:winx86 + - container: winx64 + image: pointcloudlibrary/env:winx64 - container: fmt image: pointcloudlibrary/fmt - container: env1804 @@ -140,24 +144,27 @@ stages: displayName: Build MSVC dependsOn: formatting jobs: - - job: vs2017 - displayName: Windows VS2017 Build + - job: Windows + displayName: Windows Build pool: - vmImage: 'vs2017-win2016' + vmImage: 'windows-2019' strategy: matrix: x86: + CONTAINER: winx86 PLATFORM: 'x86' ARCHITECTURE: 'x86' - GENERATOR: 'Visual Studio 15 2017' + GENERATOR: '"Visual Studio 16 2019" -A Win32' x64: + CONTAINER: winx64 PLATFORM: 'x64' ARCHITECTURE: 'x86_amd64' - GENERATOR: 'Visual Studio 15 2017 Win64' + GENERATOR: '"Visual Studio 16 2019" -A x64' + container: $[ variables['CONTAINER'] ] timeoutInMinutes: 0 variables: BUILD_DIR: 'c:\build' CONFIGURATION: 'Release' - VCPKG_ROOT: 'C:\vcpkg' + VCPKG_ROOT: 'c:\vcpkg' steps: - template: build/windows.yaml diff --git a/.ci/azure-pipelines/build/windows.yaml b/.ci/azure-pipelines/build/windows.yaml index 813089ce405..ab657dda4d2 100644 --- a/.ci/azure-pipelines/build/windows.yaml +++ b/.ci/azure-pipelines/build/windows.yaml @@ -2,22 +2,13 @@ steps: - checkout: self # find the commit hash on a quick non-forced update too fetchDepth: 10 - - pwsh: Get-PSDrive - displayName: "Check free space" - script: | - vcpkg.exe install eigen3 flann gtest qhull ^ - boost-date-time boost-filesystem boost-iostreams ^ - boost-property-tree boost-graph boost-interprocess ^ - boost-signals2 boost-sort boost-multi-array boost-asio ^ - boost-ptr-container ^ - --triplet %PLATFORM%-windows && vcpkg.exe list - displayName: 'Install C++ Dependencies Via Vcpkg' - - script: | - mkdir %BUILD_DIR% && cd %BUILD_DIR% + mkdir %BUILD_DIR% && cd %BUILD_DIR% && dir cmake $(Build.SourcesDirectory) ^ - -G"%GENERATOR%" ^ + -G%GENERATOR% ^ + -DVCPKG_TARGET_TRIPLET=%PLATFORM%-windows-rel ^ -DCMAKE_BUILD_TYPE="MinSizeRel" ^ - -DCMAKE_TOOLCHAIN_FILE=%VCPKG_ROOT%\scripts\buildsystems\vcpkg.cmake ^ + -DCMAKE_TOOLCHAIN_FILE="%VCPKG_ROOT%\scripts\buildsystems\vcpkg.cmake" ^ -DVCPKG_APPLOCAL_DEPS=ON ^ -DPCL_BUILD_WITH_BOOST_DYNAMIC_LINKING_WIN32=ON ^ -DPCL_BUILD_WITH_FLANN_DYNAMIC_LINKING_WIN32=ON ^ @@ -26,15 +17,12 @@ steps: -DBUILD_tools=OFF ^ -DBUILD_surface_on_nurbs=ON displayName: 'CMake Configuration' - workingDirectory: 'c:' - script: | cd %BUILD_DIR% && cmake --build . --config %CONFIGURATION% displayName: 'Build Library' - workingDirectory: 'c:' - script: | cd %BUILD_DIR% && cmake --build . --target tests --config %CONFIGURATION% displayName: 'Run Unit Tests' - workingDirectory: 'c:' - task: PublishTestResults@2 inputs: testResultsFormat: 'CTest' From 76cd5c86308e6d85ebc71e74e676f78fb94d953d Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 5 Apr 2021 22:33:12 +0200 Subject: [PATCH 090/123] Enable to exlude visualization tests --- .ci/azure-pipelines/build/windows.yaml | 3 ++- cmake/pcl_options.cmake | 3 +++ test/CMakeLists.txt | 14 +++++++++++++- 3 files changed, 18 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/build/windows.yaml b/.ci/azure-pipelines/build/windows.yaml index ab657dda4d2..8076d736924 100644 --- a/.ci/azure-pipelines/build/windows.yaml +++ b/.ci/azure-pipelines/build/windows.yaml @@ -15,7 +15,8 @@ steps: -DPCL_BUILD_WITH_QHULL_DYNAMIC_LINKING_WIN32=ON ^ -DBUILD_global_tests=ON ^ -DBUILD_tools=OFF ^ - -DBUILD_surface_on_nurbs=ON + -DBUILD_surface_on_nurbs=ON ^ + -DPCL_DISABLE_VISUALIZATION_TESTS=ON displayName: 'CMake Configuration' - script: | cd %BUILD_DIR% && cmake --build . --config %CONFIGURATION% diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index c8d0a6506dc..6570d75f166 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -89,3 +89,6 @@ endif() # (Used to prevent gpu tests from executing in CI where GPU hardware is unavailable) option(PCL_DISABLE_GPU_TESTS "Disable running GPU tests. If disabled, tests will still be built." OFF) +# Set whether visualizations tests should be run +# (Used to prevent visualizations tests from executing in CI where visualization is unavailable) +option(PCL_DISABLE_VISUALIZATION_TESTS "Disable running visualizations tests. If disabled, tests will still be built." OFF) diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index cc3043699c1..cb7f77530de 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -23,9 +23,21 @@ if(MSVC) set(PCL_CTEST_ARGUMENTS ${PCL_CTEST_ARGUMENTS} -C $<$:Debug>$<$:Release>) endif() +# Enables you to disable visualization tests. Used on CI. +if(PCL_DISABLE_VISUALIZATION_TESTS) + list(APPEND EXCLUDE_TESTS visualization) +endif() + # Enables you to disable GPU tests. Used on CI as it has no access to GPU hardware if(PCL_DISABLE_GPU_TESTS) - set(PCL_CTEST_ARGUMENTS ${PCL_CTEST_ARGUMENTS} -E gpu) + list(APPEND EXCLUDE_TESTS gpu) +endif() + +#Check if there are any tests to exclude +if(EXCLUDE_TESTS) + message(STATUS "Tests excluded: ${EXCLUDE_TESTS}") + string(REPLACE ";" "|" EXCLUDE_TESTS_REGEX "${EXCLUDE_TESTS}") + set(PCL_CTEST_ARGUMENTS ${PCL_CTEST_ARGUMENTS} -E "(${EXCLUDE_TESTS_REGEX})") endif() add_custom_target(tests "${CMAKE_CTEST_COMMAND}" ${PCL_CTEST_ARGUMENTS} -V -T Test VERBATIM) From 1903b0e11da7f9cf1aaae3920c57a4daaca2fc4a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 16 May 2021 19:03:33 +0200 Subject: [PATCH 091/123] Improve explanation what PassThrough filter does in tutorials --- .../content/sources/concave_hull_2d/concave_hull_2d.cpp | 2 +- doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp | 2 +- .../sources/cylinder_segmentation/cylinder_segmentation.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp b/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp index 9293d61a0a5..8e9ee14827a 100644 --- a/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp +++ b/doc/tutorials/content/sources/concave_hull_2d/concave_hull_2d.cpp @@ -17,7 +17,7 @@ main () pcl::PCDReader reader; reader.read ("table_scene_mug_stereo_textured.pcd", *cloud); - // Build a filter to remove spurious NaNs + // Build a filter to remove spurious NaNs and scene background pcl::PassThrough pass; pass.setInputCloud (cloud); pass.setFilterFieldName ("z"); diff --git a/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp b/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp index b2118533421..e12c7d19350 100644 --- a/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp +++ b/doc/tutorials/content/sources/convex_hull_2d/convex_hull_2d.cpp @@ -15,7 +15,7 @@ int pcl::PCDReader reader; reader.read ("table_scene_mug_stereo_textured.pcd", *cloud); - // Build a filter to remove spurious NaNs + // Build a filter to remove spurious NaNs and scene background pcl::PassThrough pass; pass.setInputCloud (cloud); pass.setFilterFieldName ("z"); diff --git a/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp b/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp index 1c2f7a4b2ff..326ebc3a5e5 100644 --- a/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp +++ b/doc/tutorials/content/sources/cylinder_segmentation/cylinder_segmentation.cpp @@ -36,7 +36,7 @@ main () reader.read ("table_scene_mug_stereo_textured.pcd", *cloud); std::cerr << "PointCloud has: " << cloud->size () << " data points." << std::endl; - // Build a passthrough filter to remove spurious NaNs + // Build a passthrough filter to remove spurious NaNs and scene background pass.setInputCloud (cloud); pass.setFilterFieldName ("z"); pass.setFilterLimits (0, 1.5); From cf988ddb3636706faf330e4b137516d0fba92d5b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 16 May 2021 20:52:40 +0200 Subject: [PATCH 092/123] Replace PassThrough with removeNaNFromPointCloud in 3 tutorials - and adapt corresponding rst files - the PassThrough was a bad choice because it removes (large) parts of the clouds that should be segmented - for region_growing_rgb_segmentation this messes up the whole tutorial - for region_growing_segmentation this would be a problem if the result of the PassThrough would not be discarded - removeNaNFromPointCloud is the right choice since it only removes the invalid points, and it still serves as an example that the segmentation classes can work with indices --- .../content/min_cut_segmentation.rst | 22 +++++++++---------- .../region_growing_rgb_segmentation.rst | 14 ++++++------ .../content/region_growing_segmentation.rst | 17 +++++++------- .../min_cut_segmentation.cpp | 8 ++----- .../region_growing_rgb_segmentation.cpp | 8 ++----- .../region_growing_segmentation.cpp | 10 +++------ 6 files changed, 33 insertions(+), 46 deletions(-) diff --git a/doc/tutorials/content/min_cut_segmentation.rst b/doc/tutorials/content/min_cut_segmentation.rst index f20774c0854..3fb1dd8823a 100644 --- a/doc/tutorials/content/min_cut_segmentation.rst +++ b/doc/tutorials/content/min_cut_segmentation.rst @@ -69,62 +69,62 @@ These lines are simply loading the cloud from the .pcd file. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 18-23 + :lines: 18-19 -This few lines are not necessary. Their only purpose is to show that ``pcl::MinCutSegmentation`` class can work with indices. +The purpose of these lines is to show that ``pcl::MinCutSegmentation`` class can work with indices. Here, only the valid points are chosen for segmentation. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 25-25 + :lines: 21-21 Here is the line where the instantiation of the ``pcl::MinCutSegmentation`` class takes place. It is the tamplate class that has only one parameter - PointT - which says what type of points will be used. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 26-27 + :lines: 22-23 These lines provide the algorithm with the cloud that must be segmented and the indices. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 29-35 + :lines: 25-31 As mentioned before, algorithm requires point that is known to be the objects center. These lines provide it. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 37-38 + :lines: 33-34 These lines set :math:`\sigma` and objects radius required for smooth cost calculation. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 39-39 + :lines: 35-35 This line tells how much neighbours to find when constructing the graph. The more neighbours is set, the more number of edges it will contain. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 40-40 + :lines: 36-36 Here is the line where foreground penalty is set. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 42-43 + :lines: 38-39 These lines are responsible for launching the algorithm. After the segmentation clusters will contain the result. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 45-45 + :lines: 41-41 You can easily access the flow value that was computed during the graph cut. This is exactly what happening here. .. literalinclude:: sources/min_cut_segmentation/min_cut_segmentation.cpp :language: cpp - :lines: 47-52 + :lines: 43-48 These lines simply create the instance of ``CloudViewer`` class for result visualization. diff --git a/doc/tutorials/content/region_growing_rgb_segmentation.rst b/doc/tutorials/content/region_growing_rgb_segmentation.rst index a32ccf6d951..bbb81c79039 100644 --- a/doc/tutorials/content/region_growing_rgb_segmentation.rst +++ b/doc/tutorials/content/region_growing_rgb_segmentation.rst @@ -39,7 +39,7 @@ They are simply loading the cloud from the .pcd file. Note that points must have .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 34-34 + :lines: 30-30 This line is responsible for ``pcl::RegionGrowingRGB`` instantiation. This class has two parameters: @@ -49,40 +49,40 @@ This line is responsible for ``pcl::RegionGrowingRGB`` instantiation. This class .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 35-37 + :lines: 31-33 These lines provide the instance with the input cloud, indices and search method. .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 38-38 + :lines: 34-34 Here the distance threshold is set. It is used to determine whether the point is neighbouring or not. If the point is located at a distance less than the given threshold, then it is considered to be neighbouring. It is used for clusters neighbours search. .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 39-39 + :lines: 35-35 This line sets the color threshold. Just as angle threshold is used for testing points normals in ``pcl::RegionGrowing`` to determine if the point belongs to cluster, this value is used for testing points colors. .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 40-40 + :lines: 36-36 Here the color threshold for clusters is set. This value is similar to the previous, but is used when the merging process takes place. .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 41-41 + :lines: 37-37 This value is similar to that which was used in the :ref:`region_growing_segmentation` tutorial. In addition to that, it is used for merging process mentioned in the beginning. If cluster has less points than was set through ``setMinClusterSize`` method, then it will be merged with the nearest neighbour. .. literalinclude:: sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp :language: cpp - :lines: 43-44 + :lines: 39-40 Here is the place where the algorithm is launched. It will return the array of clusters when the segmentation process will be over. diff --git a/doc/tutorials/content/region_growing_segmentation.rst b/doc/tutorials/content/region_growing_segmentation.rst index 65193dc009b..91c8fab370c 100644 --- a/doc/tutorials/content/region_growing_segmentation.rst +++ b/doc/tutorials/content/region_growing_segmentation.rst @@ -116,14 +116,13 @@ To learn more about how it is done you should take a look at the :ref:`normal_es .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 30-35 + :lines: 30-31 -These lines are given only for example. You can safely comment this part. Insofar as ``pcl::RegionGrowing`` is derived from ``pcl::PCLBase``, -it can work with indices. It means you can instruct that you only segment those points that are listed in the indices array instead of the whole point cloud. +Insofar as ``pcl::RegionGrowing`` is derived from ``pcl::PCLBase``, it can work with indices. It means you can instruct that you only segment those points that are listed in the indices array instead of the whole point cloud. Here, only the valid points are chosen for segmentation. .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 37-39 + :lines: 33-35 You have finally reached the part where ``pcl::RegionGrowing`` is instantiated. It is a template class that has two parameters: @@ -136,14 +135,14 @@ The default values for minimum and maximum are 1 and 'as much as possible' respe .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 40-44 + :lines: 36-40 The algorithm needs K nearest search in its internal structure, so here is the place where a search method is provided and number of neighbours is set. After that it receives the cloud that must be segmented, point indices and normals. .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 45-46 + :lines: 41-42 These two lines are the most important part in the algorithm initialization, because they are responsible for the mentioned smoothness constraint. First method sets the angle in radians that will be used as the allowable range for the normals deviation. @@ -154,20 +153,20 @@ And if this value is less than the curvature threshold then the algorithm will c .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 48-49 + :lines: 44-45 This method simply launches the segmentation algorithm. After its work it will return clusters array. .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 51-63 + :lines: 47-59 These lines are simple enough, so they won't be commented. They are intended for those who are not familiar with how to work with ``pcl::PointIndices`` and how to access its elements. .. literalinclude:: sources/region_growing_segmentation/region_growing_segmentation.cpp :language: cpp - :lines: 65-73 + :lines: 61-69 The ``pcl::RegionGrowing`` class provides a method that returns the colored cloud where each cluster has its own color. So in this part of code the ``pcl::visualization::CloudViewer`` is instantiated for viewing the result of the segmentation - the same colored cloud. diff --git a/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp b/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp index c3b23a3f378..5e4076aeb11 100644 --- a/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp +++ b/doc/tutorials/content/sources/min_cut_segmentation/min_cut_segmentation.cpp @@ -3,7 +3,7 @@ #include #include #include -#include +#include // for pcl::removeNaNFromPointCloud #include int main () @@ -16,11 +16,7 @@ int main () } pcl::IndicesPtr indices (new std::vector ); - pcl::PassThrough pass; - pass.setInputCloud (cloud); - pass.setFilterFieldName ("z"); - pass.setFilterLimits (0.0, 1.0); - pass.filter (*indices); + pcl::removeNaNFromPointCloud(*cloud, *indices); pcl::MinCutSegmentation seg; seg.setInputCloud (cloud); diff --git a/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp b/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp index 1066d52a9e1..fc1196df3ec 100644 --- a/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp +++ b/doc/tutorials/content/sources/region_growing_rgb_segmentation/region_growing_rgb_segmentation.cpp @@ -7,7 +7,7 @@ #include #include #include -#include +#include // for pcl::removeNaNFromPointCloud #include using namespace std::chrono_literals; @@ -25,11 +25,7 @@ main () } pcl::IndicesPtr indices (new std::vector ); - pcl::PassThrough pass; - pass.setInputCloud (cloud); - pass.setFilterFieldName ("z"); - pass.setFilterLimits (0.0, 1.0); - pass.filter (*indices); + pcl::removeNaNFromPointCloud (*cloud, *indices); pcl::RegionGrowingRGB reg; reg.setInputCloud (cloud); diff --git a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp index 2702b411036..f783f84e4d6 100644 --- a/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp +++ b/doc/tutorials/content/sources/region_growing_segmentation/region_growing_segmentation.cpp @@ -6,7 +6,7 @@ #include #include #include -#include +#include // for pcl::removeNaNFromPointCloud #include int @@ -28,11 +28,7 @@ main () normal_estimator.compute (*normals); pcl::IndicesPtr indices (new std::vector ); - pcl::PassThrough pass; - pass.setInputCloud (cloud); - pass.setFilterFieldName ("z"); - pass.setFilterLimits (0.0, 1.0); - pass.filter (*indices); + pcl::removeNaNFromPointCloud(*cloud, *indices); pcl::RegionGrowing reg; reg.setMinClusterSize (50); @@ -40,7 +36,7 @@ main () reg.setSearchMethod (tree); reg.setNumberOfNeighbours (30); reg.setInputCloud (cloud); - //reg.setIndices (indices); + reg.setIndices (indices); reg.setInputNormals (normals); reg.setSmoothnessThreshold (3.0 / 180.0 * M_PI); reg.setCurvatureThreshold (1.0); From 6cc233a04e4e00646d1b1ea4260f94f32bcdfceb Mon Sep 17 00:00:00 2001 From: Fabian Schuetze Date: Mon, 17 May 2021 04:46:12 +0200 Subject: [PATCH 093/123] Small container improvement (#4748) --- cmake/pcl_find_cuda.cmake | 2 +- gpu/containers/src/initialization.cpp | 19 +++++++++---------- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/cmake/pcl_find_cuda.cmake b/cmake/pcl_find_cuda.cmake index 58096b36b4a..ab1810a15cb 100644 --- a/cmake/pcl_find_cuda.cmake +++ b/cmake/pcl_find_cuda.cmake @@ -31,7 +31,7 @@ if(CUDA_FOUND) # https://docs.nvidia.com/cuda/cuda-toolkit-release-notes/index.html#deprecated-features if(NOT ${CUDA_VERSION_STRING} VERSION_LESS "11.0") - set(__cuda_arch_bin "3.5 3.7 5.0 5.2 5.3 6.0 6.1 6.2 7.0 7.2 7.5 8.0") + set(__cuda_arch_bin "3.5 3.7 5.0 5.2 5.3 6.0 6.1 6.2 7.0 7.2 7.5 8.0 8.6") elseif(NOT ${CUDA_VERSION_STRING} VERSION_LESS "10.0") set(__cuda_arch_bin "3.0 3.2 3.5 3.7 5.0 5.2 5.3 6.0 6.1 6.2 7.0 7.2 7.5") elseif(NOT ${CUDA_VERSION_STRING} VERSION_LESS "9.0") diff --git a/gpu/containers/src/initialization.cpp b/gpu/containers/src/initialization.cpp index 4a8ac185ddd..5ad20544d63 100644 --- a/gpu/containers/src/initialization.cpp +++ b/gpu/containers/src/initialization.cpp @@ -39,6 +39,7 @@ #include "cuda.h" #include +#include // replace c-style array with std::array #define HAVE_CUDA //#include @@ -115,16 +116,14 @@ namespace int Cores; }; - SMtoCores gpuArchCoresPerSM[] = { - {0x10, 8}, {0x11, 8}, {0x12, 8}, {0x13, 8}, {0x20, 32}, {0x21, 48}, {0x30, 192}, - {0x35, 192}, {0x50, 128}, {0x52, 128}, {0x53, 128}, {0x60, 64}, {0x61, 128}, {-1, -1} - }; - int index = 0; - while (gpuArchCoresPerSM[index].SM != -1) - { - if (gpuArchCoresPerSM[index].SM == ((major << 4) + minor) ) - return gpuArchCoresPerSM[index].Cores; - index++; + std::array gpuArchCoresPerSM = {{ + {0x30, 192}, {0x32, 192}, {0x35, 192}, {0x37, 192}, {0x50, 128}, {0x52, 128}, + {0x53, 128}, {0x60, 64}, {0x61, 128}, {0x62, 128}, {0x70, 64}, {0x72, 64}, + {0x75, 64}, {0x80, 64}, {0x86, 128} + }}; + for (const auto& sm2cores : gpuArchCoresPerSM) { + if (sm2cores.SM == ((major << 4) + minor) ) + return sm2cores.Cores; } printf("\nCan't determine number of cores. Unknown SM version %d.%d!\n", major, minor); return 0; From b19c99a5f45950c0e519e631d09adb0c5257596e Mon Sep 17 00:00:00 2001 From: Alexander Turkin Date: Tue, 18 May 2021 16:06:53 +0300 Subject: [PATCH 094/123] Add support for reentrant qhull (#4540) * using reentrant qhull by default, qhull calls edits * using reentrant qhull by default, qhull calls edits * using reentrant qhull by default, qhull calls edits * cmake for qhull fix * cmake for qhull fix * static libs made reentrant as well * turning surface tests on for 20.10 * typos fixes, using errfile for qh_zero second param * removing HAVE_QHULL_2011 and assuming its always true * removing QHULL_MAJOR_VERSION --- .ci/azure-pipelines/azure-pipelines.yaml | 2 - cmake/Modules/FindQhull.cmake | 12 ++-- pcl_config.h.in | 2 - surface/include/pcl/surface/convex_hull.h | 4 +- .../include/pcl/surface/impl/concave_hull.hpp | 49 +++++++------- .../include/pcl/surface/impl/convex_hull.hpp | 66 ++++++++++--------- surface/include/pcl/surface/qhull.h | 27 +++----- 7 files changed, 75 insertions(+), 87 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 6ddc39600e7..281540424c3 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -56,8 +56,6 @@ stages: CC: gcc CXX: g++ BUILD_GPU: OFF - # surface is not ready for re-entrant QHull - CMAKE_ARGS: '-DBUILD_tests_surface=OFF' container: $[ variables['CONTAINER'] ] timeoutInMinutes: 0 variables: diff --git a/cmake/Modules/FindQhull.cmake b/cmake/Modules/FindQhull.cmake index 7f3cf90dc11..f9f628452b8 100644 --- a/cmake/Modules/FindQhull.cmake +++ b/cmake/Modules/FindQhull.cmake @@ -9,14 +9,12 @@ # If QHULL_USE_STATIC is specified then look for static libraries ONLY else # look for shared ones -set(QHULL_MAJOR_VERSION 6) - if(QHULL_USE_STATIC) - set(QHULL_RELEASE_NAME qhullstatic) - set(QHULL_DEBUG_NAME qhullstatic_d) + set(QHULL_RELEASE_NAME qhullstatic_r) + set(QHULL_DEBUG_NAME qhullstatic_rd) else() - set(QHULL_RELEASE_NAME qhull_p qhull${QHULL_MAJOR_VERSION} qhull) - set(QHULL_DEBUG_NAME qhull_p_d qhull${QHULL_MAJOR_VERSION}_d qhull_d${QHULL_MAJOR_VERSION} qhull_d) + set(QHULL_RELEASE_NAME qhull_r qhull) + set(QHULL_DEBUG_NAME qhull_rd qhull_d) endif() find_file(QHULL_HEADER @@ -30,10 +28,8 @@ set(QHULL_HEADER "${QHULL_HEADER}" CACHE INTERNAL "QHull header" FORCE ) if(QHULL_HEADER) get_filename_component(qhull_header ${QHULL_HEADER} NAME_WE) if("${qhull_header}" STREQUAL "qhull") - set(HAVE_QHULL_2011 OFF) get_filename_component(QHULL_INCLUDE_DIR ${QHULL_HEADER} PATH) elseif("${qhull_header}" STREQUAL "libqhull") - set(HAVE_QHULL_2011 ON) get_filename_component(QHULL_INCLUDE_DIR ${QHULL_HEADER} PATH) get_filename_component(QHULL_INCLUDE_DIR ${QHULL_INCLUDE_DIR} PATH) endif() diff --git a/pcl_config.h.in b/pcl_config.h.in index 3eccb95c975..e41128d2dc5 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -42,8 +42,6 @@ #cmakedefine HAVE_QHULL 1 -#cmakedefine HAVE_QHULL_2011 1 - #cmakedefine HAVE_CUDA 1 #cmakedefine HAVE_ENSENSO 1 diff --git a/surface/include/pcl/surface/convex_hull.h b/surface/include/pcl/surface/convex_hull.h index d82bbf0b0ea..917b42c412f 100644 --- a/surface/include/pcl/surface/convex_hull.h +++ b/surface/include/pcl/surface/convex_hull.h @@ -88,11 +88,11 @@ namespace pcl using PointCloudConstPtr = typename PointCloud::ConstPtr; /** \brief Empty constructor. */ - ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0), + ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0), projection_angle_thresh_ (std::cos (0.174532925) ), qhull_flags ("qhull "), x_axis_ (1.0, 0.0, 0.0), y_axis_ (0.0, 1.0, 0.0), z_axis_ (0.0, 0.0, 1.0) { - }; + } /** \brief Empty destructor */ ~ConvexHull () {} diff --git a/surface/include/pcl/surface/impl/concave_hull.hpp b/surface/include/pcl/surface/impl/concave_hull.hpp index 50216d15512..0019b2d395f 100644 --- a/surface/include/pcl/surface/impl/concave_hull.hpp +++ b/surface/include/pcl/surface/impl/concave_hull.hpp @@ -194,8 +194,13 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: points[i * dim_ + 2] = static_cast (cloud_transformed[i].z); } + qhT qh_qh; + qhT* qh = &qh_qh; + QHULL_LIB_CHECK + qh_zero(qh, errfile); + // Compute concave hull - exitcode = qh_new_qhull (dim_, static_cast (cloud_transformed.size ()), points, ismalloc, flags, outfile, errfile); + exitcode = qh_new_qhull (qh, dim_, static_cast (cloud_transformed.size ()), points, ismalloc, flags, outfile, errfile); if (exitcode != 0) { @@ -227,16 +232,16 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: alpha_shape.width = alpha_shape.height = 0; polygons.resize (0); - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); return; } - qh_setvoronoi_all (); + qh_setvoronoi_all (qh); - int num_vertices = qh num_vertices; + int num_vertices = qh->num_vertices; alpha_shape.resize (num_vertices); vertexT *vertex; @@ -253,11 +258,11 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: ++max_vertex_id; std::vector qhid_to_pcidx (max_vertex_id); - int num_facets = qh num_facets; + int num_facets = qh->num_facets; if (dim_ == 3) { - setT *triangles_set = qh_settemp (4 * num_facets); + setT *triangles_set = qh_settemp (qh, 4 * num_facets); if (voronoi_centers_) voronoi_centers_->points.resize (num_facets); @@ -283,29 +288,29 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: if (r <= alpha_) { // all triangles in tetrahedron are good, add them all to the alpha shape (triangles_set) - qh_makeridges (facet); + qh_makeridges (qh, facet); facet->good = true; - facet->visitid = qh visit_id; + facet->visitid = qh->visit_id; ridgeT *ridge, **ridgep; FOREACHridge_ (facet->ridges) { facetT *neighb = otherfacet_ (ridge, facet); - if ((neighb->visitid != qh visit_id)) - qh_setappend (&triangles_set, ridge); + if ((neighb->visitid != qh->visit_id)) + qh_setappend (qh, &triangles_set, ridge); } } else { // consider individual triangles from the tetrahedron... facet->good = false; - facet->visitid = qh visit_id; - qh_makeridges (facet); + facet->visitid = qh->visit_id; + qh_makeridges (qh, facet); ridgeT *ridge, **ridgep; FOREACHridge_ (facet->ridges) { facetT *neighb; neighb = otherfacet_ (ridge, facet); - if ((neighb->visitid != qh visit_id)) + if ((neighb->visitid != qh->visit_id)) { // check if individual triangle is good and add it to triangles_set @@ -322,7 +327,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: double r = pcl::getCircumcircleRadius (a, b, c); if (r <= alpha_) - qh_setappend (&triangles_set, ridge); + qh_setappend (qh, &triangles_set, ridge); } } } @@ -354,7 +359,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: { polygons[triangles].vertices.resize (3); int vertex_n, vertex_i; - FOREACHvertex_i_ ((*ridge).vertices) //3 vertices per ridge! + FOREACHvertex_i_ (qh, (*ridge).vertices) //3 vertices per ridge! { if (!added_vertices[vertex->id]) { @@ -383,7 +388,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: { // Compute the alpha complex for the set of points // Filters the delaunay triangles - setT *edges_set = qh_settemp (3 * num_facets); + setT *edges_set = qh_settemp (qh, 3 * num_facets); if (voronoi_centers_) voronoi_centers_->points.resize (num_facets); @@ -403,12 +408,12 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: if (r <= alpha_) { pcl::Vertices facet_vertices; //TODO: is not used!! - qh_makeridges (facet); + qh_makeridges (qh, facet); facet->good = true; ridgeT *ridge, **ridgep; FOREACHridge_ (facet->ridges) - qh_setappend (&edges_set, ridge); + qh_setappend (qh, &edges_set, ridge); if (voronoi_centers_) { @@ -438,7 +443,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: std::vector pcd_indices; pcd_indices.resize (2); - FOREACHvertex_i_ ((*ridge).vertices) //in 2-dim, 2 vertices per ridge! + FOREACHvertex_i_ (qh, (*ridge).vertices) //in 2-dim, 2 vertices per ridge! { if (!added_vertices[vertex->id]) { @@ -540,9 +545,9 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: voronoi_centers_->points.resize (dd); } - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); Eigen::Affine3d transInverse = transform1.inverse (); pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse); diff --git a/surface/include/pcl/surface/impl/convex_hull.hpp b/surface/include/pcl/surface/impl/convex_hull.hpp index b8cbb5f14fd..aa36cdd9efb 100644 --- a/surface/include/pcl/surface/impl/convex_hull.hpp +++ b/surface/include/pcl/surface/impl/convex_hull.hpp @@ -136,10 +136,8 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto // output from qh_produce_output(), use NULL to skip qh_produce_output() FILE *outfile = nullptr; -#ifndef HAVE_QHULL_2011 if (compute_area_) outfile = stderr; -#endif // option flags for qhull, see qh_opt.htm const char* flags = qhull_flags.c_str (); @@ -180,18 +178,21 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto // This should only happen if we had invalid input PCL_ERROR ("[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ()); } + + qhT qh_qh; + qhT* qh = &qh_qh; + QHULL_LIB_CHECK + qh_zero(qh, errfile); // Compute convex hull - int exitcode = qh_new_qhull (dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); -#ifdef HAVE_QHULL_2011 + int exitcode = qh_new_qhull (qh, dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); if (compute_area_) { - qh_prepare_output(); + qh_prepare_output(qh); } -#endif // 0 if no error from qhull or it doesn't find any vertices - if (exitcode != 0 || qh num_vertices == 0) + if (exitcode != 0 || qh->num_vertices == 0) { PCL_ERROR ("[pcl::%s::performReconstrution2D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), indices_->size ()); @@ -199,9 +200,9 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto hull.width = hull.height = 0; polygons.resize (0); - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); return; } @@ -209,11 +210,11 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto // Qhull returns the area in volume for 2D if (compute_area_) { - total_area_ = qh totvol; + total_area_ = qh->totvol; total_volume_ = 0.0; } - int num_vertices = qh num_vertices; + int num_vertices = qh->num_vertices; hull.clear(); hull.resize(num_vertices, PointInT{}); @@ -225,8 +226,8 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto FORALLvertices { - hull[i] = (*input_)[(*indices_)[qh_pointid (vertex->point)]]; - idx_points[i].first = qh_pointid (vertex->point); + hull[i] = (*input_)[(*indices_)[qh_pointid (qh, vertex->point)]]; + idx_points[i].first = qh_pointid (qh, vertex->point); ++i; } @@ -273,9 +274,9 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto polygons[0].vertices[j] = static_cast (j); } - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); hull.width = hull.size (); hull.height = 1; @@ -298,10 +299,8 @@ pcl::ConvexHull::performReconstruction3D ( // output from qh_produce_output(), use NULL to skip qh_produce_output() FILE *outfile = nullptr; -#ifndef HAVE_QHULL_2011 if (compute_area_) outfile = stderr; -#endif // option flags for qhull, see qh_opt.htm const char *flags = qhull_flags.c_str (); @@ -319,14 +318,17 @@ pcl::ConvexHull::performReconstruction3D ( points[j + 2] = static_cast ((*input_)[(*indices_)[i]].z); } + qhT qh_qh; + qhT* qh = &qh_qh; + QHULL_LIB_CHECK + qh_zero(qh, errfile); + // Compute convex hull - int exitcode = qh_new_qhull (dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); -#ifdef HAVE_QHULL_2011 + int exitcode = qh_new_qhull (qh, dimension, static_cast (indices_->size ()), points, ismalloc, const_cast (flags), outfile, errfile); if (compute_area_) { - qh_prepare_output(); + qh_prepare_output(qh); } -#endif // 0 if no error from qhull if (exitcode != 0) @@ -340,18 +342,18 @@ pcl::ConvexHull::performReconstruction3D ( hull.width = hull.height = 0; polygons.resize (0); - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); return; } - qh_triangulate (); + qh_triangulate (qh); - int num_facets = qh num_facets; + int num_facets = qh->num_facets; - int num_vertices = qh num_vertices; + int num_vertices = qh->num_vertices; hull.resize (num_vertices); vertexT * vertex; @@ -374,7 +376,7 @@ pcl::ConvexHull::performReconstruction3D ( FORALLvertices { // Add vertices to hull point_cloud and store index - hull_indices_.indices.push_back ((*indices_)[qh_pointid (vertex->point)]); + hull_indices_.indices.push_back ((*indices_)[qh_pointid (qh, vertex->point)]); hull[i] = (*input_)[hull_indices_.indices.back ()]; qhid_to_pcidx[vertex->id] = i; // map the vertex id of qhull to the point cloud index @@ -383,8 +385,8 @@ pcl::ConvexHull::performReconstruction3D ( if (compute_area_) { - total_area_ = qh totarea; - total_volume_ = qh totvol; + total_area_ = qh->totarea; + total_volume_ = qh->totvol; } if (fill_polygon_data) @@ -399,16 +401,16 @@ pcl::ConvexHull::performReconstruction3D ( // Needed by FOREACHvertex_i_ int vertex_n, vertex_i; - FOREACHvertex_i_ ((*facet).vertices) + FOREACHvertex_i_ (qh, (*facet).vertices) //facet_vertices.vertices.push_back (qhid_to_pcidx[vertex->id]); polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id]; ++dd; } } // Deallocates memory (also the points) - qh_freeqhull (!qh_ALL); + qh_freeqhull (qh, !qh_ALL); int curlong, totlong; - qh_memfreeshort (&curlong, &totlong); + qh_memfreeshort (qh, &curlong, &totlong); hull.width = hull.size (); hull.height = 1; diff --git a/surface/include/pcl/surface/qhull.h b/surface/include/pcl/surface/qhull.h index 39eee73e401..da370497082 100644 --- a/surface/include/pcl/surface/qhull.h +++ b/surface/include/pcl/surface/qhull.h @@ -48,25 +48,14 @@ extern "C" { -#ifdef HAVE_QHULL_2011 -# include "libqhull/libqhull.h" -# include "libqhull/mem.h" -# include "libqhull/qset.h" -# include "libqhull/geom.h" -# include "libqhull/merge.h" -# include "libqhull/poly.h" -# include "libqhull/io.h" -# include "libqhull/stat.h" -#else -# include "qhull/qhull.h" -# include "qhull/mem.h" -# include "qhull/qset.h" -# include "qhull/geom.h" -# include "qhull/merge.h" -# include "qhull/poly.h" -# include "qhull/io.h" -# include "qhull/stat.h" -#endif +#include "libqhull_r/libqhull_r.h" +#include "libqhull_r/mem_r.h" +#include "libqhull_r/qset_r.h" +#include "libqhull_r/geom_r.h" +#include "libqhull_r/merge_r.h" +#include "libqhull_r/poly_r.h" +#include "libqhull_r/io_r.h" +#include "libqhull_r/stat_r.h" } #endif From 52aed361e13787ac9157da20bc54ef39277bb0c4 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 18 May 2021 16:33:31 +0200 Subject: [PATCH 095/123] Updated minimum required boost to 1.65.0. --- cmake/pcl_find_boost.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index f4eb87c54dd..e1b019eede4 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -24,14 +24,14 @@ set(Boost_ADDITIONAL_VERSIONS set(Boost_NO_BOOST_CMAKE ON) # Optional boost modules -find_package(Boost 1.55.0 QUIET COMPONENTS serialization mpi) +find_package(Boost 1.65.0 QUIET COMPONENTS serialization mpi) if(Boost_SERIALIZATION_FOUND) set(BOOST_SERIALIZATION_FOUND TRUE) endif() # Required boost modules set(BOOST_REQUIRED_MODULES filesystem date_time iostreams system) -find_package(Boost 1.55.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) +find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) if(Boost_FOUND) set(BOOST_FOUND TRUE) From 89fe1c7e82a520fb7b66b90fc827b04f25c855f2 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 21 May 2021 09:25:37 +0200 Subject: [PATCH 096/123] Update required FLANN --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1ff0cd718e1..78ec1a5923b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -306,7 +306,7 @@ find_package(Eigen 3.1 REQUIRED) include_directories(SYSTEM ${EIGEN_INCLUDE_DIRS}) # FLANN (required) -find_package(FLANN 1.7.0 REQUIRED) +find_package(FLANN 1.9.1 REQUIRED) if(NOT (${FLANN_LIBRARY_TYPE} MATCHES ${PCL_FLANN_REQUIRED_TYPE}) AND NOT (${PCL_FLANN_REQUIRED_TYPE} MATCHES "DONTCARE")) message(FATAL_ERROR "Flann was selected with ${PCL_FLANN_REQUIRED_TYPE} but found as ${FLANN_LIBRARY_TYPE}") endif() From 562ac9dd6d1b862da581f9d239ec362b69ee7ed6 Mon Sep 17 00:00:00 2001 From: tin1254 Date: Mon, 24 May 2021 02:55:22 +0200 Subject: [PATCH 097/123] Improve code style in documentation Update include guard to #pragma once, fix link to style guide --- doc/tutorials/content/writing_new_classes.rst | 42 ++++--------------- 1 file changed, 9 insertions(+), 33 deletions(-) diff --git a/doc/tutorials/content/writing_new_classes.rst b/doc/tutorials/content/writing_new_classes.rst index b9eccd49689..bca60f66fdd 100644 --- a/doc/tutorials/content/writing_new_classes.rst +++ b/doc/tutorials/content/writing_new_classes.rst @@ -160,7 +160,7 @@ Setting up the structure If you're not familiar with the PCL file structure already, please go ahead and read the `PCL C++ Programming Style Guide - `_ to + `_ to familiarize yourself with the concepts. There're two different ways we could set up the structure: i) set up the code @@ -193,8 +193,7 @@ skeleton: .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_H_ - #define PCL_FILTERS_BILATERAL_H_ + #pragma once #include @@ -206,8 +205,6 @@ skeleton: }; } - #endif // PCL_FILTERS_BILATERAL_H_ - bilateral.hpp ============= @@ -217,12 +214,9 @@ While we're at it, let's set up two skeleton *bilateral.hpp* and .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_IMPL_H_ - #define PCL_FILTERS_BILATERAL_IMPL_H_ + #pragma once #include - - #endif // PCL_FILTERS_BILATERAL_IMPL_H_ This should be straightforward. We haven't declared any methods for `BilateralFilter` yet, therefore there is no implementation. @@ -511,8 +505,7 @@ header file becomes: .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_H_ - #define PCL_FILTERS_BILATERAL_H_ + #pragma once #include #include @@ -584,8 +577,6 @@ header file becomes: }; } - #endif // PCL_FILTERS_BILATERAL_H_ - bilateral.hpp ============= @@ -651,8 +642,7 @@ entry for the class: .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_IMPL_H_ - #define PCL_FILTERS_BILATERAL_IMPL_H_ + #pragma once #include @@ -660,8 +650,6 @@ entry for the class: #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter; - #endif // PCL_FILTERS_BILATERAL_IMPL_H_ - One additional thing that we can do is error checking on: * whether the two `sigma_s_` and `sigma_r_` parameters have been given; @@ -709,8 +697,7 @@ The implementation file header thus becomes: .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_IMPL_H_ - #define PCL_FILTERS_BILATERAL_IMPL_H_ + #pragma once #include #include @@ -770,8 +757,6 @@ The implementation file header thus becomes: #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter; - #endif // PCL_FILTERS_BILATERAL_IMPL_H_ - Taking advantage of other PCL concepts -------------------------------------- @@ -824,8 +809,7 @@ The implementation file header thus becomes: .. code-block:: cpp :linenos: - #ifndef PCL_FILTERS_BILATERAL_IMPL_H_ - #define PCL_FILTERS_BILATERAL_IMPL_H_ + #pragma once #include #include @@ -885,8 +869,6 @@ The implementation file header thus becomes: #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter; - #endif // PCL_FILTERS_BILATERAL_IMPL_H_ - To make :pcl:`indices_` work without typing the full construct, we need to add a new line to *bilateral.h* that specifies the class where `indices_` is declared: @@ -1020,8 +1002,7 @@ class look like: * */ - #ifndef PCL_FILTERS_BILATERAL_H_ - #define PCL_FILTERS_BILATERAL_H_ + #pragma once #include #include @@ -1131,8 +1112,6 @@ class look like: }; } - #endif // PCL_FILTERS_BILATERAL_H_ - And the *bilateral.hpp* likes: .. code-block:: cpp @@ -1175,8 +1154,7 @@ And the *bilateral.hpp* likes: * */ - #ifndef PCL_FILTERS_BILATERAL_IMPL_H_ - #define PCL_FILTERS_BILATERAL_IMPL_H_ + #pragma once #include #include @@ -1249,8 +1227,6 @@ And the *bilateral.hpp* likes: #define PCL_INSTANTIATE_BilateralFilter(T) template class PCL_EXPORTS pcl::BilateralFilter; - #endif // PCL_FILTERS_BILATERAL_IMPL_H_ - Testing the new class --------------------- From d0ebd87d3650b2205222f4a254051d5f92124549 Mon Sep 17 00:00:00 2001 From: tin1254 Date: Mon, 24 May 2021 15:18:57 +0200 Subject: [PATCH 098/123] Update license in documentation --- doc/tutorials/content/writing_new_classes.rst | 132 ++++-------------- 1 file changed, 24 insertions(+), 108 deletions(-) diff --git a/doc/tutorials/content/writing_new_classes.rst b/doc/tutorials/content/writing_new_classes.rst index bca60f66fdd..4c53f0e72bb 100644 --- a/doc/tutorials/content/writing_new_classes.rst +++ b/doc/tutorials/content/writing_new_classes.rst @@ -900,42 +900,14 @@ file, as follows: .. code-block:: cpp :linenos: - /* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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. - * - */ + /* + * SPDX-License-Identifier: BSD-3-Clause + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception Inc. + * + * All rights reserved + */ An additional like can be inserted if additional copyright is needed (or the original copyright can be changed): @@ -965,42 +937,14 @@ class look like: .. code-block:: cpp :linenos: - /* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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. - * - */ + /* + * SPDX-License-Identifier: BSD-3-Clause + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception Inc. + * + * All rights reserved + */ #pragma once @@ -1117,42 +1061,14 @@ And the *bilateral.hpp* likes: .. code-block:: cpp :linenos: - /* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, 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 Willow Garage, Inc. 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. - * - */ + /* + * SPDX-License-Identifier: BSD-3-Clause + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2014-, Open Perception Inc. + * + * All rights reserved + */ #pragma once From 9427050881ce1d6c184d7faa10ac56f4cc021e3d Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Tue, 25 May 2021 18:28:41 +0200 Subject: [PATCH 099/123] Use more pcl::Indices (#4758) * Use more pcl::Indices and fix sign-compare warnings * Fixup * Fix some typos in test * Change pair type in region growing * Use more pcl::uindex_t in segmentation --- .../feature_wrapper/normal_estimator.h | 1 - .../tools/impl/organized_segmentation.hpp | 2 +- .../tools/euclidean_clustering.cpp | 2 +- apps/modeler/src/cloud_mesh.cpp | 4 +- apps/modeler/src/normal_estimation_worker.cpp | 2 +- apps/modeler/src/normals_actor_item.cpp | 2 +- apps/src/ni_linemod.cpp | 2 +- cuda/sample_consensus/src/sac_model.cu | 2 +- .../impl/organized_edge_detection.hpp | 4 +- .../include/pcl/filters/impl/bilateral.hpp | 6 +-- filters/include/pcl/filters/impl/crop_box.hpp | 4 +- filters/src/crop_box.cpp | 4 +- .../kinfu_large_scale/impl/world_model.hpp | 2 +- .../pcl/gpu/kinfu_large_scale/world_model.h | 2 +- .../include/pcl/gpu/people/label_tree.h | 4 +- .../include/pcl/gpu/people/people_detector.h | 2 +- gpu/people/src/people_detector.cpp | 6 +-- io/src/vtk_lib_io.cpp | 4 +- .../pcl/octree/impl/octree_pointcloud.hpp | 2 +- .../include/pcl/recognition/impl/hv/hv_go.hpp | 2 +- .../correspondence_rejection_features.h | 2 +- ...orrespondence_rejection_sample_consensus.h | 4 +- registration/include/pcl/registration/gicp.h | 16 ++++---- ...rrespondence_estimation_backprojection.hpp | 6 +-- ...pondence_rejection_sample_consensus_2d.hpp | 6 +-- .../include/pcl/registration/impl/gicp.hpp | 8 ++-- .../include/pcl/registration/impl/ia_fpcs.hpp | 18 ++++----- .../pcl/registration/impl/ia_ransac.hpp | 6 +-- .../impl/sample_consensus_prerejective.hpp | 4 +- ...estimation_point_to_plane_lls_weighted.hpp | 6 +-- ...ion_estimation_point_to_plane_weighted.hpp | 16 ++++---- .../transformation_validation_euclidean.hpp | 2 +- ...n_estimation_point_to_plane_lls_weighted.h | 6 +-- ...ation_estimation_point_to_plane_weighted.h | 10 ++--- registration/src/gicp6d.cpp | 4 +- .../impl/conditional_euclidean_clustering.hpp | 4 +- .../segmentation/impl/extract_clusters.hpp | 4 +- .../impl/grabcut_segmentation.hpp | 2 +- .../pcl/segmentation/impl/region_growing.hpp | 14 +++---- .../segmentation/impl/region_growing_rgb.hpp | 39 +++++++++---------- .../include/pcl/segmentation/region_growing.h | 14 +++---- .../pcl/segmentation/region_growing_rgb.h | 4 +- surface/include/pcl/surface/gp3.h | 28 ++++++------- surface/include/pcl/surface/impl/gp3.hpp | 14 +++---- test/gpu/octree/perfomance.cpp | 19 +++++---- test/gpu/octree/test_approx_nearest.cpp | 2 +- test/gpu/octree/test_host_radius_search.cpp | 7 ++-- test/gpu/octree/test_knn_search.cpp | 4 +- tools/obj_rec_ransac_result.cpp | 7 ++-- tools/octree_viewer.cpp | 2 +- .../pcl/visualization/impl/pcl_visualizer.hpp | 2 +- 51 files changed, 168 insertions(+), 171 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h index 0e2a86f8b55..a8f49baa622 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/feature_wrapper/normal_estimator.h @@ -32,7 +32,6 @@ class PreProcessorAndNormalEstimator { pcl::Indices nn_indices(9); std::vector nn_distances(9); - std::vector src_indices; float sum_distances = 0.0; std::vector avg_distances(input->size()); diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/impl/organized_segmentation.hpp b/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/impl/organized_segmentation.hpp index 1b32f201fe0..708ea1f34b1 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/impl/organized_segmentation.hpp +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/impl/organized_segmentation.hpp @@ -122,7 +122,7 @@ pcl::cloud_composer::OrganizedSegmentationTool::performTemplatedAction (const QL euclidean_segmentation.setInputCloud (input_cloud); euclidean_segmentation.segment (euclidean_labels, euclidean_label_indices); - pcl::IndicesPtr extracted_indices (new std::vector ()); + pcl::IndicesPtr extracted_indices (new pcl::Indices ()); for (std::size_t i = 0; i < euclidean_label_indices.size (); i++) { if (euclidean_label_indices[i].indices.size () >= (std::size_t) min_cluster_size) diff --git a/apps/cloud_composer/tools/euclidean_clustering.cpp b/apps/cloud_composer/tools/euclidean_clustering.cpp index 4a52dd75c1e..13f5d914dbb 100644 --- a/apps/cloud_composer/tools/euclidean_clustering.cpp +++ b/apps/cloud_composer/tools/euclidean_clustering.cpp @@ -69,7 +69,7 @@ pcl::cloud_composer::EuclideanClusteringTool::performAction (ConstItemList input Eigen::Vector4f source_origin = input_item->data (ItemDataRole::ORIGIN).value (); Eigen::Quaternionf source_orientation = input_item->data (ItemDataRole::ORIENTATION).value (); //Vector to accumulate the extracted indices - pcl::IndicesPtr extracted_indices (new std::vector ()); + pcl::IndicesPtr extracted_indices (new pcl::Indices ()); //Put found clusters into new cloud_items! qDebug () << "Found "<()); + pcl::IndicesPtr indices(new pcl::Indices()); pcl::removeNaNFromPointCloud(*cloud_, *indices); data->SetNumberOfValues(3 * indices->size()); @@ -203,7 +203,7 @@ pcl::modeler::CloudMesh::updateVtkPolygons() } } else { - pcl::IndicesPtr indices(new std::vector()); + pcl::IndicesPtr indices(new pcl::Indices()); pcl::removeNaNFromPointCloud(*cloud_, *indices); for (const auto& polygon : polygons_) { diff --git a/apps/modeler/src/normal_estimation_worker.cpp b/apps/modeler/src/normal_estimation_worker.cpp index 56fce622185..468d7362fea 100755 --- a/apps/modeler/src/normal_estimation_worker.cpp +++ b/apps/modeler/src/normal_estimation_worker.cpp @@ -112,7 +112,7 @@ pcl::modeler::NormalEstimationWorker::processImpl(CloudMeshItem* cloud_mesh_item pcl::NormalEstimation normal_estimator; normal_estimator.setInputCloud(cloud); - pcl::IndicesPtr indices(new std::vector()); + pcl::IndicesPtr indices(new pcl::Indices()); pcl::removeNaNFromPointCloud(*cloud, *indices); normal_estimator.setIndices(indices); diff --git a/apps/modeler/src/normals_actor_item.cpp b/apps/modeler/src/normals_actor_item.cpp index b9141fdafa5..6530c56095e 100644 --- a/apps/modeler/src/normals_actor_item.cpp +++ b/apps/modeler/src/normals_actor_item.cpp @@ -95,7 +95,7 @@ pcl::modeler::NormalsActorItem::createNormalLines() } } else { - pcl::IndicesPtr indices(new std::vector()); + pcl::IndicesPtr indices(new pcl::Indices()); pcl::removeNaNFromPointCloud(*cloud, *indices); vtkIdType nr_normals = static_cast((indices->size() - 1) / level_ + 1); diff --git a/apps/src/ni_linemod.cpp b/apps/src/ni_linemod.cpp index b4e04aa385d..52452ec0bd6 100644 --- a/apps/src/ni_linemod.cpp +++ b/apps/src/ni_linemod.cpp @@ -569,7 +569,7 @@ class NILinemod { bool first_frame_; // Segmentation - std::vector indices_fullset_; + pcl::Indices indices_fullset_; PointIndices::Ptr plane_indices_; CloudPtr plane_; IntegralImageNormalEstimation ne_; diff --git a/cuda/sample_consensus/src/sac_model.cu b/cuda/sample_consensus/src/sac_model.cu index adeee90922d..461e66f5922 100644 --- a/cuda/sample_consensus/src/sac_model.cu +++ b/cuda/sample_consensus/src/sac_model.cu @@ -57,7 +57,7 @@ namespace pcl template