From 75bd2d1931373fc7b21427220c0dd39c24384b02 Mon Sep 17 00:00:00 2001 From: Alexander Turkin Date: Tue, 8 Mar 2022 15:27:12 +0300 Subject: [PATCH 001/288] isSamePointType function made constexpr more tests for correspondence estimation to cover cases when source and target pointclouds have different point types --- .../registration/correspondence_estimation.h | 50 +++- ...orrespondence_estimation_normal_shooting.h | 14 +- .../impl/correspondence_estimation.hpp | 162 +++++----- ...rrespondence_estimation_backprojection.hpp | 237 +++++---------- ...respondence_estimation_normal_shooting.hpp | 278 ++++++------------ test/common/test_io.cpp | 23 -- .../test_correspondence_estimation.cpp | 98 ++++-- 7 files changed, 371 insertions(+), 491 deletions(-) diff --git a/registration/include/pcl/registration/correspondence_estimation.h b/registration/include/pcl/registration/correspondence_estimation.h index de46b3e7b67..3837e3ba5ea 100644 --- a/registration/include/pcl/registration/correspondence_estimation.h +++ b/registration/include/pcl/registration/correspondence_estimation.h @@ -72,9 +72,11 @@ class CorrespondenceEstimationBase : public PCLBase { using KdTree = pcl::search::KdTree; using KdTreePtr = typename KdTree::Ptr; + using KdTreeConstPtr = typename KdTree::ConstPtr; using KdTreeReciprocal = pcl::search::KdTree; - using KdTreeReciprocalPtr = typename KdTree::Ptr; + using KdTreeReciprocalPtr = typename KdTreeReciprocal::Ptr; + using KdTreeReciprocalConstPtr = typename KdTreeReciprocal::ConstPtr; using PointCloudSource = pcl::PointCloud; using PointCloudSourcePtr = typename PointCloudSource::Ptr; @@ -85,6 +87,8 @@ class CorrespondenceEstimationBase : public PCLBase { using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr; + using PointRepresentationReciprocalConstPtr = + typename KdTreeReciprocal::PointRepresentationConstPtr; /** \brief Empty constructor. */ CorrespondenceEstimationBase() @@ -275,8 +279,8 @@ class CorrespondenceEstimationBase : public PCLBase { pcl::Correspondences& correspondences, double max_distance = std::numeric_limits::max()) = 0; - /** \brief Provide a boost shared pointer to the PointRepresentation to be used - * when searching for nearest neighbors. + /** \brief Provide a boost shared pointer to the PointRepresentation for target cloud + * to be used when searching for nearest neighbors. * * \param[in] point_representation the PointRepresentation to be used by the * k-D tree for nearest neighbor search @@ -287,6 +291,19 @@ class CorrespondenceEstimationBase : public PCLBase { point_representation_ = point_representation; } + /** \brief Provide a boost shared pointer to the PointRepresentation for source cloud + * to be used when searching for nearest neighbors. + * + * \param[in] point_representation the PointRepresentation to be used by the + * k-D tree for nearest neighbor search + */ + inline void + setPointRepresentationReciprocal( + const PointRepresentationReciprocalConstPtr& point_representation_reciprocal) + { + point_representation_reciprocal_ = point_representation_reciprocal; + } + /** \brief Clone and cast to CorrespondenceEstimationBase */ virtual typename CorrespondenceEstimationBase::Ptr clone() const = 0; @@ -307,9 +324,12 @@ class CorrespondenceEstimationBase : public PCLBase { /** \brief The target point cloud dataset indices. */ IndicesPtr target_indices_; - /** \brief The point representation used (internal). */ + /** \brief The target point representation used (internal). */ PointRepresentationConstPtr point_representation_; + /** \brief The source point representation used (internal). */ + PointRepresentationReciprocalConstPtr point_representation_reciprocal_; + /** \brief The transformed input source point cloud dataset. */ PointCloudTargetPtr input_transformed_; @@ -396,8 +416,24 @@ class CorrespondenceEstimation using CorrespondenceEstimationBase::input_fields_; using PCLBase::deinitCompute; - using KdTree = pcl::search::KdTree; - using KdTreePtr = typename KdTree::Ptr; + using KdTree = + typename CorrespondenceEstimationBase::KdTree; + using KdTreePtr = typename CorrespondenceEstimationBase::KdTreePtr; + using KdTreeConstPtr = typename CorrespondenceEstimationBase::KdTreeConstPtr; + using KdTreeReciprocal = + typename CorrespondenceEstimationBase:: + KdTreeReciprocal; + using KdTreeReciprocalPtr = + typename CorrespondenceEstimationBase:: + KdTreeReciprocalPtr; + + using KdTreeReciprocalConstPtr = + typename CorrespondenceEstimationBase:: + KdTreeReciprocalConstPtr; using PointCloudSource = pcl::PointCloud; using PointCloudSourcePtr = typename PointCloudSource::Ptr; @@ -408,6 +444,8 @@ class CorrespondenceEstimation using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr; + using PointRepresentationReciprocalConstPtr = + typename KdTreeReciprocal::PointRepresentationConstPtr; /** \brief Empty constructor. */ CorrespondenceEstimation() { corr_name_ = "CorrespondenceEstimation"; } diff --git a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h index 0dc40ff1132..e0e8ab424b5 100644 --- a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h +++ b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h @@ -101,8 +101,18 @@ class CorrespondenceEstimationNormalShooting point_representation_; using CorrespondenceEstimationBase::target_indices_; - using KdTree = pcl::search::KdTree; - using KdTreePtr = typename KdTree::Ptr; + using typename CorrespondenceEstimationBase::KdTree; + using typename CorrespondenceEstimationBase:: + KdTreePtr; + using typename CorrespondenceEstimationBase:: + KdTreeConstPtr; + + using typename CorrespondenceEstimationBase:: + KdTreeReciprocal; + using typename CorrespondenceEstimationBase:: + KdTreeReciprocalPtr; + using typename CorrespondenceEstimationBase:: + KdTreeReciprocalConstPtr; using PointCloudSource = pcl::PointCloud; using PointCloudSourcePtr = typename PointCloudSource::Ptr; diff --git a/registration/include/pcl/registration/impl/correspondence_estimation.hpp b/registration/include/pcl/registration/impl/correspondence_estimation.hpp index 19cded5369a..50eb5b0fc66 100644 --- a/registration/include/pcl/registration/impl/correspondence_estimation.hpp +++ b/registration/include/pcl/registration/impl/correspondence_estimation.hpp @@ -98,8 +98,8 @@ CorrespondenceEstimationBase::initComputeRecip { // Only update source kd-tree if a new target cloud was set if (source_cloud_updated_ && !force_no_recompute_reciprocal_) { - if (point_representation_) - tree_reciprocal_->setPointRepresentation(point_representation_); + if (point_representation_reciprocal_) + tree_reciprocal_->setPointRepresentation(point_representation_reciprocal_); // If the target indices have been given via setIndicesTarget if (indices_) tree_reciprocal_->setInputCloud(getInputSource(), getIndicesSource()); @@ -112,6 +112,35 @@ CorrespondenceEstimationBase::initComputeRecip return (true); } +namespace detail { + +template < + typename PointTarget, + typename PointSource, + typename Index, + typename std::enable_if_t()>* = nullptr> +const PointSource& +pointCopyOrRef(typename pcl::PointCloud::ConstPtr& input, const Index& idx) +{ + return (*input)[idx]; +} + +template < + typename PointTarget, + typename PointSource, + typename Index, + typename std::enable_if_t()>* = nullptr> +PointTarget +pointCopyOrRef(typename pcl::PointCloud::ConstPtr& input, const Index& idx) +{ + // Copy the source data to a target PointTarget format so we can search in the tree + PointTarget pt; + copyPoint((*input)[idx], pt); + return pt; +} + +} // namespace detail + template void CorrespondenceEstimation::determineCorrespondences( @@ -120,50 +149,30 @@ CorrespondenceEstimation::determineCorresponde if (!initCompute()) return; - double max_dist_sqr = max_distance * max_distance; - correspondences.resize(indices_->size()); pcl::Indices index(1); std::vector distance(1); pcl::Correspondence corr; unsigned int nr_valid_correspondences = 0; + double max_dist_sqr = max_distance * max_distance; - // Check if the template types are the same. If true, avoid a copy. - // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT - // macro! - if (isSamePointType()) { - // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { - tree_->nearestKSearch((*input_)[idx], 1, index, distance); - if (distance[0] > max_dist_sqr) - continue; - - corr.index_query = idx; - corr.index_match = index[0]; - corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; - } - } - else { - PointTarget pt; - - // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx], pt); - - tree_->nearestKSearch(pt, 1, index, distance); - if (distance[0] > max_dist_sqr) - continue; - - corr.index_query = idx; - corr.index_match = index[0]; - corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; - } + // Iterate over the input set of source indices + for (const auto& idx : (*indices_)) { + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT + // macro! + const auto& pt = detail::pointCopyOrRef(input_, idx); + tree_->nearestKSearch(pt, 1, index, distance); + if (distance[0] > max_dist_sqr) + continue; + + corr.index_query = idx; + corr.index_match = index[0]; + corr.distance = distance[0]; + correspondences[nr_valid_correspondences++] = corr; } + correspondences.resize(nr_valid_correspondences); deinitCompute(); } @@ -192,59 +201,30 @@ CorrespondenceEstimation:: unsigned int nr_valid_correspondences = 0; int target_idx = 0; - // Check if the template types are the same. If true, avoid a copy. - // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT - // macro! - if (isSamePointType()) { - // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { - tree_->nearestKSearch((*input_)[idx], 1, index, distance); - if (distance[0] > max_dist_sqr) - continue; - - target_idx = index[0]; - - tree_reciprocal_->nearestKSearch( - (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal); - if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0]) - continue; - - corr.index_query = idx; - corr.index_match = index[0]; - corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; - } - } - else { - PointTarget pt_src; - PointSource pt_tgt; - - // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx], pt_src); - - tree_->nearestKSearch(pt_src, 1, index, distance); - if (distance[0] > max_dist_sqr) - continue; - - target_idx = index[0]; - - // Copy the target data to a target PointSource format so we can search in the - // tree_reciprocal - copyPoint((*target_)[target_idx], pt_tgt); - - tree_reciprocal_->nearestKSearch( - pt_tgt, 1, index_reciprocal, distance_reciprocal); - if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0]) - continue; - - corr.index_query = idx; - corr.index_match = index[0]; - corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; - } + // Iterate over the input set of source indices + for (const auto& idx : (*indices_)) { + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT + // macro! + + const auto& pt_src = detail::pointCopyOrRef(input_, idx); + + tree_->nearestKSearch(pt_src, 1, index, distance); + if (distance[0] > max_dist_sqr) + continue; + + target_idx = index[0]; + const auto& pt_tgt = + detail::pointCopyOrRef(target_, target_idx); + + tree_reciprocal_->nearestKSearch(pt_tgt, 1, index_reciprocal, distance_reciprocal); + if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0]) + continue; + + corr.index_query = idx; + corr.index_match = index[0]; + corr.distance = distance[0]; + correspondences[nr_valid_correspondences++] = corr; } correspondences.resize(nr_valid_correspondences); deinitCompute(); diff --git a/registration/include/pcl/registration/impl/correspondence_estimation_backprojection.hpp b/registration/include/pcl/registration/impl/correspondence_estimation_backprojection.hpp index 1970ed6cc26..66a33d957a1 100644 --- a/registration/include/pcl/registration/impl/correspondence_estimation_backprojection.hpp +++ b/registration/include/pcl/registration/impl/correspondence_estimation_backprojection.hpp @@ -81,82 +81,37 @@ CorrespondenceEstimationBackProjection()) { - PointTarget pt; - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - float min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - float cos_angle = (*source_normals_)[idx_i].normal_x * - (*target_normals_)[nn_indices[j]].normal_x + - (*source_normals_)[idx_i].normal_y * - (*target_normals_)[nn_indices[j]].normal_y + - (*source_normals_)[idx_i].normal_z * - (*target_normals_)[nn_indices[j]].normal_z; - float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); - - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } + // Iterate over the input set of source indices + for (const auto& idx_i : (*indices_)) { + const auto& pt = detail::pointCopyOrRef(input_, idx_i); + tree_->nearestKSearch(pt, k_, nn_indices, nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance + // to the normal + float min_dist = std::numeric_limits::max(); + + // Find the best correspondence + for (std::size_t j = 0; j < nn_indices.size(); j++) { + float cos_angle = (*source_normals_)[idx_i].normal_x * + (*target_normals_)[nn_indices[j]].normal_x + + (*source_normals_)[idx_i].normal_y * + (*target_normals_)[nn_indices[j]].normal_y + + (*source_normals_)[idx_i].normal_z * + (*target_normals_)[nn_indices[j]].normal_z; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) { + min_dist = dist; + min_index = static_cast(j); } - if (min_dist > max_distance) - continue; - - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; } - } - else { - PointTarget pt; - - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - float min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - PointSource pt_src; - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx_i], pt_src); + if (min_dist > max_distance) + continue; - float cos_angle = (*source_normals_)[idx_i].normal_x * - (*target_normals_)[nn_indices[j]].normal_x + - (*source_normals_)[idx_i].normal_y * - (*target_normals_)[nn_indices[j]].normal_y + - (*source_normals_)[idx_i].normal_z * - (*target_normals_)[nn_indices[j]].normal_z; - float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); - - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } - } - if (min_dist > max_distance) - continue; - - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; - } + corr.index_query = idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index]; // min_dist; + correspondences[nr_valid_correspondences++] = corr; } correspondences.resize(nr_valid_correspondences); deinitCompute(); @@ -188,98 +143,54 @@ CorrespondenceEstimationBackProjection()) { - PointTarget pt; - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - float min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - float cos_angle = (*source_normals_)[idx_i].normal_x * - (*target_normals_)[nn_indices[j]].normal_x + - (*source_normals_)[idx_i].normal_y * - (*target_normals_)[nn_indices[j]].normal_y + - (*source_normals_)[idx_i].normal_z * - (*target_normals_)[nn_indices[j]].normal_z; - float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); - - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } + // Iterate over the input set of source indices + for (const auto& idx_i : (*indices_)) { + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT + // macro! + tree_->nearestKSearch( + detail::pointCopyOrRef(input_, idx_i), + k_, + nn_indices, + nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance + // to the normal + float min_dist = std::numeric_limits::max(); + + // Find the best correspondence + for (std::size_t j = 0; j < nn_indices.size(); j++) { + float cos_angle = (*source_normals_)[idx_i].normal_x * + (*target_normals_)[nn_indices[j]].normal_x + + (*source_normals_)[idx_i].normal_y * + (*target_normals_)[nn_indices[j]].normal_y + + (*source_normals_)[idx_i].normal_z * + (*target_normals_)[nn_indices[j]].normal_z; + float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); + + if (dist < min_dist) { + min_dist = dist; + min_index = static_cast(j); } - if (min_dist > max_distance) - continue; - - // Check if the correspondence is reciprocal - target_idx = nn_indices[min_index]; - tree_reciprocal_->nearestKSearch( - (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal); - - if (idx_i != index_reciprocal[0]) - continue; - - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; - } - } - else { - PointTarget pt; - - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - float min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - PointSource pt_src; - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx_i], pt_src); - - float cos_angle = (*source_normals_)[idx_i].normal_x * - (*target_normals_)[nn_indices[j]].normal_x + - (*source_normals_)[idx_i].normal_y * - (*target_normals_)[nn_indices[j]].normal_y + - (*source_normals_)[idx_i].normal_z * - (*target_normals_)[nn_indices[j]].normal_z; - float dist = nn_dists[j] * (2.0f - cos_angle * cos_angle); - - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } - } - if (min_dist > max_distance) - continue; - - // Check if the correspondence is reciprocal - target_idx = nn_indices[min_index]; - tree_reciprocal_->nearestKSearch( - (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal); - - if (idx_i != index_reciprocal[0]) - continue; - - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch( + detail::pointCopyOrRef(target_, target_idx), + 1, + index_reciprocal, + distance_reciprocal); + + if (idx_i != index_reciprocal[0]) + continue; + + corr.index_query = idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index]; // min_dist; + correspondences[nr_valid_correspondences++] = corr; } correspondences.resize(nr_valid_correspondences); deinitCompute(); diff --git a/registration/include/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp b/registration/include/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp index 16f9daf0060..8668e4bd0eb 100644 --- a/registration/include/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp +++ b/registration/include/pcl/registration/impl/correspondence_estimation_normal_shooting.hpp @@ -81,92 +81,49 @@ CorrespondenceEstimationNormalShooting()) { - PointTarget pt; - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - double min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - // computing the distance between a point and a line in 3d. - // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html - pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x; - pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y; - pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z; - - const NormalT& normal = (*source_normals_)[idx_i]; - Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); - Eigen::Vector3d V(pt.x, pt.y, pt.z); - Eigen::Vector3d C = N.cross(V); - - // Check if we have a better correspondence - double dist = C.dot(C); - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } + PointTarget pt; + // Iterate over the input set of source indices + for (const auto& idx_i : (*indices_)) { + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT + // macro! + tree_->nearestKSearch( + detail::pointCopyOrRef(input_, idx_i), + k_, + nn_indices, + nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance + // to the normal + double min_dist = std::numeric_limits::max(); + + // Find the best correspondence + for (std::size_t j = 0; j < nn_indices.size(); j++) { + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x; + pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y; + pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z; + + const NormalT& normal = (*source_normals_)[idx_i]; + Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V(pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross(V); + + // Check if we have a better correspondence + double dist = C.dot(C); + if (dist < min_dist) { + min_dist = dist; + min_index = static_cast(j); } - if (min_dist > max_distance) - continue; - - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; } - } - else { - PointTarget pt; - - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - double min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - PointSource pt_src; - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx_i], pt_src); - - // computing the distance between a point and a line in 3d. - // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html - pt.x = (*target_)[nn_indices[j]].x - pt_src.x; - pt.y = (*target_)[nn_indices[j]].y - pt_src.y; - pt.z = (*target_)[nn_indices[j]].z - pt_src.z; - - const NormalT& normal = (*source_normals_)[idx_i]; - Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); - Eigen::Vector3d V(pt.x, pt.y, pt.z); - Eigen::Vector3d C = N.cross(V); - - // Check if we have a better correspondence - double dist = C.dot(C); - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } - } - if (min_dist > max_distance) - continue; + if (min_dist > max_distance) + continue; - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; - } + corr.index_query = idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index]; // min_dist; + correspondences[nr_valid_correspondences++] = corr; } correspondences.resize(nr_valid_correspondences); deinitCompute(); @@ -199,110 +156,61 @@ CorrespondenceEstimationNormalShooting()) { - PointTarget pt; - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - double min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - // computing the distance between a point and a line in 3d. - // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html - pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x; - pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y; - pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z; - - const NormalT& normal = (*source_normals_)[idx_i]; - Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); - Eigen::Vector3d V(pt.x, pt.y, pt.z); - Eigen::Vector3d C = N.cross(V); - - // Check if we have a better correspondence - double dist = C.dot(C); - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } - } - if (min_dist > max_distance) - continue; - - // Check if the correspondence is reciprocal - target_idx = nn_indices[min_index]; - tree_reciprocal_->nearestKSearch( - (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal); - - if (idx_i != index_reciprocal[0]) - continue; - - // Correspondence IS reciprocal, save it and continue - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; - } - } - else { - PointTarget pt; - - // Iterate over the input set of source indices - for (const auto& idx_i : (*indices_)) { - tree_->nearestKSearch((*input_)[idx_i], k_, nn_indices, nn_dists); - - // Among the K nearest neighbours find the one with minimum perpendicular distance - // to the normal - double min_dist = std::numeric_limits::max(); - - // Find the best correspondence - for (std::size_t j = 0; j < nn_indices.size(); j++) { - PointSource pt_src; - // Copy the source data to a target PointTarget format so we can search in the - // tree - copyPoint((*input_)[idx_i], pt_src); - - // computing the distance between a point and a line in 3d. - // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html - pt.x = (*target_)[nn_indices[j]].x - pt_src.x; - pt.y = (*target_)[nn_indices[j]].y - pt_src.y; - pt.z = (*target_)[nn_indices[j]].z - pt_src.z; - - const NormalT& normal = (*source_normals_)[idx_i]; - Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); - Eigen::Vector3d V(pt.x, pt.y, pt.z); - Eigen::Vector3d C = N.cross(V); - - // Check if we have a better correspondence - double dist = C.dot(C); - if (dist < min_dist) { - min_dist = dist; - min_index = static_cast(j); - } + PointTarget pt; + // Iterate over the input set of source indices + for (const auto& idx_i : (*indices_)) { + // Check if the template types are the same. If true, avoid a copy. + // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT + // macro! + tree_->nearestKSearch( + detail::pointCopyOrRef(input_, idx_i), + k_, + nn_indices, + nn_dists); + + // Among the K nearest neighbours find the one with minimum perpendicular distance + // to the normal + double min_dist = std::numeric_limits::max(); + + // Find the best correspondence + for (std::size_t j = 0; j < nn_indices.size(); j++) { + // computing the distance between a point and a line in 3d. + // Reference - http://mathworld.wolfram.com/Point-LineDistance3-Dimensional.html + pt.x = (*target_)[nn_indices[j]].x - (*input_)[idx_i].x; + pt.y = (*target_)[nn_indices[j]].y - (*input_)[idx_i].y; + pt.z = (*target_)[nn_indices[j]].z - (*input_)[idx_i].z; + + const NormalT& normal = (*source_normals_)[idx_i]; + Eigen::Vector3d N(normal.normal_x, normal.normal_y, normal.normal_z); + Eigen::Vector3d V(pt.x, pt.y, pt.z); + Eigen::Vector3d C = N.cross(V); + + // Check if we have a better correspondence + double dist = C.dot(C); + if (dist < min_dist) { + min_dist = dist; + min_index = static_cast(j); } - if (min_dist > max_distance) - continue; - - // Check if the correspondence is reciprocal - target_idx = nn_indices[min_index]; - tree_reciprocal_->nearestKSearch( - (*target_)[target_idx], 1, index_reciprocal, distance_reciprocal); - - if (idx_i != index_reciprocal[0]) - continue; - - // Correspondence IS reciprocal, save it and continue - corr.index_query = idx_i; - corr.index_match = nn_indices[min_index]; - corr.distance = nn_dists[min_index]; // min_dist; - correspondences[nr_valid_correspondences++] = corr; } + if (min_dist > max_distance) + continue; + + // Check if the correspondence is reciprocal + target_idx = nn_indices[min_index]; + tree_reciprocal_->nearestKSearch( + detail::pointCopyOrRef(target_, target_idx), + 1, + index_reciprocal, + distance_reciprocal); + + if (idx_i != index_reciprocal[0]) + continue; + + // Correspondence IS reciprocal, save it and continue + corr.index_query = idx_i; + corr.index_match = nn_indices[min_index]; + corr.distance = nn_dists[min_index]; // min_dist; + correspondences[nr_valid_correspondences++] = corr; } correspondences.resize(nr_valid_correspondences); deinitCompute(); diff --git a/test/common/test_io.cpp b/test/common/test_io.cpp index efdc8245b7b..ac34ad4351e 100644 --- a/test/common/test_io.cpp +++ b/test/common/test_io.cpp @@ -51,29 +51,6 @@ PointXYZRGBA pt_xyz_rgba, pt_xyz_rgba2; PointXYZRGB pt_xyz_rgb; PointXYZ pt_xyz; -/////////////////////////////////////////////////////////////////////////////////////////// -TEST (PCL, concatenateFields) -{ - bool status = isSamePointType (); - EXPECT_TRUE (status); - status = isSamePointType (); - EXPECT_FALSE (status); - status = isSamePointType (); - EXPECT_FALSE (status); - status = isSamePointType (); - EXPECT_TRUE (status); - status = isSamePointType (); - EXPECT_FALSE (status); - status = isSamePointType (); - EXPECT_TRUE (status); - - // Even though it's the "same" type, rgb != rgba - status = isSamePointType (); - EXPECT_FALSE (status); - status = isSamePointType (); - EXPECT_FALSE (status); -} - /////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, copyPointCloud) { diff --git a/test/registration/test_correspondence_estimation.cpp b/test/registration/test_correspondence_estimation.cpp index 2192f3d78c0..8a2602274ff 100644 --- a/test/registration/test_correspondence_estimation.cpp +++ b/test/registration/test_correspondence_estimation.cpp @@ -41,34 +41,88 @@ #include #include +#include + +namespace +{ + +template +PointT makeRandomPoint() +{ + return PointT{}; +} + +template <> +pcl::PointXYZ makeRandomPoint() +{ + return {float (rand()), float (rand()), float (rand())}; +} + +template <> +pcl::PointXYZI makeRandomPoint() +{ + return {float (rand()), float (rand()), float (rand()), float (rand())}; +} + +template +PointT makePointWithParams(Args... args) +{ + return PointT{ args... }; +} + +template <> +pcl::PointXYZ makePointWithParams(float x, float y, float z) +{ + return {x, y, z}; +} + +template <> +pcl::PointXYZI makePointWithParams(float x, float y, float z) +{ + return {x, y, z, float (rand())}; +} + +} + +template +class CorrespondenceEstimationTestSuite : public ::testing::Test { }; + +using PointTypesForCorrespondenceEstimationTest = + ::testing::Types, std::pair>; + +TYPED_TEST_SUITE(CorrespondenceEstimationTestSuite, PointTypesForCorrespondenceEstimationTest); + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting) +TYPED_TEST(CorrespondenceEstimationTestSuite, CorrespondenceEstimationNormalShooting) { - pcl::PointCloud::Ptr cloud1 (new pcl::PointCloud ()); - pcl::PointCloud::Ptr cloud2 (new pcl::PointCloud ()); + using PointSource = typename TypeParam::first_type; + using PointTarget = typename TypeParam::second_type; + + auto cloud1 (pcl::make_shared> ()); + auto cloud2 (pcl::make_shared> ()); // Defining two parallel planes differing only by the y co-ordinate - for (float i = 0.0f; i < 10.0f; i += 0.2f) + for (std::size_t i = 0; i < 50; ++i) { - for (float z = 0.0f; z < 5.0f; z += 0.2f) + for (std::size_t j = 0; j < 25; ++j) { - cloud1->points.emplace_back(i, 0, z); - cloud2->points.emplace_back(i, 2, z); // Ideally this should be the corresponding point to the point defined in the previous line + cloud1->push_back(makePointWithParams(i * 0.2f, 0.f, j * 0.2f)); + cloud2->push_back(makePointWithParams(i * 0.2f, 2.f, j * 0.2f)); // Ideally this should be the corresponding point to the point defined in the previous line } } - pcl::NormalEstimation ne; + pcl::NormalEstimation ne; ne.setInputCloud (cloud1); - pcl::search::KdTree::Ptr tree (new pcl::search::KdTree ()); + auto tree (pcl::make_shared> ()); ne.setSearchMethod (tree); - pcl::PointCloud::Ptr cloud1_normals (new pcl::PointCloud); + auto cloud1_normals (pcl::make_shared> ()); ne.setKSearch (5); ne.compute (*cloud1_normals); // All normals are perpendicular to the plane defined - pcl::CorrespondencesPtr corr (new pcl::Correspondences); - pcl::registration::CorrespondenceEstimationNormalShooting ce; + auto corr (pcl::make_shared ()); + pcl::registration::CorrespondenceEstimationNormalShooting ce; ce.setInputSource (cloud1); ce.setKSearch (10); ce.setSourceNormals (cloud1_normals); @@ -83,23 +137,25 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationNormalShooting) } ////////////////////////////////////////////////////////////////////////////////////// -TEST (CorrespondenceEstimation, CorrespondenceEstimationSetSearchMethod) +TYPED_TEST (CorrespondenceEstimationTestSuite, CorrespondenceEstimationSetSearchMethod) { + using PointSource = typename TypeParam::first_type; + using PointTarget = typename TypeParam::second_type; // Generating 3 random clouds - pcl::PointCloud::Ptr cloud1 (new pcl::PointCloud ()); - pcl::PointCloud::Ptr cloud2 (new pcl::PointCloud ()); - for ( std::size_t i = 0; i < 50; i++ ) + auto cloud1 (pcl::make_shared> ()); + auto cloud2 (pcl::make_shared> ()); + for (std::size_t i = 0; i < 50; i++) { - cloud1->points.emplace_back(float (rand()), float (rand()), float (rand())); - cloud2->points.emplace_back(float (rand()), float (rand()), float (rand())); + cloud1->push_back(makeRandomPoint()); + cloud2->push_back(makeRandomPoint()); } // Build a KdTree for each - pcl::search::KdTree::Ptr tree1 (new pcl::search::KdTree ()); + auto tree1 (pcl::make_shared> ()); tree1->setInputCloud (cloud1); - pcl::search::KdTree::Ptr tree2 (new pcl::search::KdTree ()); + auto tree2 (pcl::make_shared> ()); tree2->setInputCloud (cloud2); // Compute correspondences - pcl::registration::CorrespondenceEstimation ce; + pcl::registration::CorrespondenceEstimation ce; ce.setInputSource (cloud1); ce.setInputTarget (cloud2); pcl::Correspondences corr_orig; From 681be86444a877d9139700e8e1918950a5b6af72 Mon Sep 17 00:00:00 2001 From: SunBlack Date: Sun, 20 Nov 2022 19:33:34 +0100 Subject: [PATCH 002/288] Use jammy instead of focal as fallback for installing latest version of CMake on kinect --- .dev/docker/env/Dockerfile | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index 7ac070fc207..fb7012e3336 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -52,7 +52,14 @@ RUN apt-get update \ && if [ "$USE_LATEST_CMAKE" = true ] ; then \ cmake_ubuntu_version=$(lsb_release -cs) ; \ if ! wget -q --method=HEAD "https://apt.kitware.com/ubuntu/dists/$cmake_ubuntu_version/Release"; then \ - cmake_ubuntu_version="focal" ; \ + ubuntu_version=$(lsb_release -sr) ; \ + if dpkg --compare-versions ${ubuntu_version} ge 22.04; then \ + cmake_ubuntu_version="jammy" ; \ + elif dpkg --compare-versions ${ubuntu_version} ge 20.04; then \ + cmake_ubuntu_version="focal" ; \ + else \ + cmake_ubuntu_version="bionic" ; \ + fi ; \ fi ; \ wget -qO - https://apt.kitware.com/kitware-archive.sh | bash -s -- --release $cmake_ubuntu_version ; \ apt-get update ; \ From 3d575b3e6c5b2c78270003f85cc7973107d64c7a Mon Sep 17 00:00:00 2001 From: SunBlack Date: Mon, 21 Nov 2022 15:56:47 +0100 Subject: [PATCH 003/288] Remove leftover define of Intel Threading Building Blocks --- pcl_config.h.in | 2 -- 1 file changed, 2 deletions(-) diff --git a/pcl_config.h.in b/pcl_config.h.in index 4395043129a..b5ef2cbf9bf 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -34,8 +34,6 @@ #endif //PCL_MINOR_VERSION #endif -#cmakedefine HAVE_TBB 1 - #cmakedefine HAVE_OPENNI 1 #cmakedefine HAVE_OPENNI2 1 From 7517454f16da44174b54980fead50766b7c1a02a Mon Sep 17 00:00:00 2001 From: luz paz Date: Tue, 22 Nov 2022 06:26:00 -0500 Subject: [PATCH 004/288] Rename test/gpu/octree/perfomance.cpp to performance.cpp Fix typo in file name --- test/gpu/octree/CMakeLists.txt | 2 +- test/gpu/octree/{perfomance.cpp => performance.cpp} | 0 2 files changed, 1 insertion(+), 1 deletion(-) rename test/gpu/octree/{perfomance.cpp => performance.cpp} (100%) diff --git a/test/gpu/octree/CMakeLists.txt b/test/gpu/octree/CMakeLists.txt index 0c0ead83fb2..d351641a035 100644 --- a/test/gpu/octree/CMakeLists.txt +++ b/test/gpu/octree/CMakeLists.txt @@ -12,7 +12,7 @@ if(NOT build) return() endif() -PCL_ADD_TEST(gpu_octree_performance test_gpu_octree_perfomance FILES perfomance.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree) +PCL_ADD_TEST(gpu_octree_performance test_gpu_octree_performance FILES performance.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree) PCL_ADD_TEST(gpu_octree_approx_nearest test_gpu_approx_nearest FILES test_approx_nearest.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree pcl_gpu_utils) PCL_ADD_TEST(gpu_octree_bfrs test_gpu_bfrs FILES test_bfrs_gpu.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree) PCL_ADD_TEST(gpu_octree_host_radius test_gpu_host_radius_search FILES test_host_radius_search.cpp LINK_WITH pcl_gtest pcl_common pcl_octree pcl_gpu_octree) diff --git a/test/gpu/octree/perfomance.cpp b/test/gpu/octree/performance.cpp similarity index 100% rename from test/gpu/octree/perfomance.cpp rename to test/gpu/octree/performance.cpp From 0b06fcf7026dfceb6e00c758b371015dafd4bd19 Mon Sep 17 00:00:00 2001 From: Sanoronas <74266945+Sanoronas@users.noreply.github.com> Date: Mon, 28 Nov 2022 09:33:01 +0100 Subject: [PATCH 005/288] Fix Link to github in ensenso_cameras.rst --- doc/tutorials/content/ensenso_cameras.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/tutorials/content/ensenso_cameras.rst b/doc/tutorials/content/ensenso_cameras.rst index a69d75904aa..257c3648663 100644 --- a/doc/tutorials/content/ensenso_cameras.rst +++ b/doc/tutorials/content/ensenso_cameras.rst @@ -37,7 +37,7 @@ Compile and install PCL. Using the example ================= -The `pcl_ensenso_viewer `_ example shows how to +The `pcl_ensenso_viewer `_ example shows how to display a point cloud grabbed from an Ensenso device using the `EnsensoGrabber `_ class. Note that this program opens the TCP port of the nxLib tree, this allows you to open the nxLib tree with the nxTreeEdit program (port 24000). From 2b9e7a4e0737773fe7461a4c1a46cb1743781c02 Mon Sep 17 00:00:00 2001 From: SunBlack Date: Tue, 29 Nov 2022 15:28:55 +0100 Subject: [PATCH 006/288] Remove CUDA code for already unsupported CUDA versions --- gpu/kinfu/src/cuda/extract.cu | 10 ---------- gpu/kinfu/src/cuda/marching_cubes.cu | 14 +------------- gpu/kinfu_large_scale/src/cuda/extract.cu | 17 ----------------- .../src/cuda/marching_cubes.cu | 14 -------------- gpu/surface/src/cuda/convex_hull.cu | 14 +------------- 5 files changed, 2 insertions(+), 67 deletions(-) diff --git a/gpu/kinfu/src/cuda/extract.cu b/gpu/kinfu/src/cuda/extract.cu index 7610bf89dd4..9f4e3195524 100644 --- a/gpu/kinfu/src/cuda/extract.cu +++ b/gpu/kinfu/src/cuda/extract.cu @@ -86,14 +86,9 @@ namespace pcl int x = threadIdx.x + blockIdx.x * CTA_SIZE_X; int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y; -#if CUDART_VERSION >= 9000 if (__all_sync (__activemask (), x >= VOLUME_X) || __all_sync (__activemask (), y >= VOLUME_Y)) return; -#else - if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y)) - return; -#endif float3 V; V.x = (x + 0.5f) * cell_size.x; @@ -183,14 +178,9 @@ namespace pcl } /* if (W != 0 && F != 1.f) */ } /* if (x < VOLUME_X && y < VOLUME_Y) */ -#if CUDART_VERSION >= 9000 int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0)) + __popc (__ballot_sync (__activemask (), local_count > 1)) + __popc (__ballot_sync (__activemask (), local_count > 2)); -#else - ///not we fulfilled points array at current iteration - int total_warp = __popc (__ballot (local_count > 0)) + __popc (__ballot (local_count > 1)) + __popc (__ballot (local_count > 2)); -#endif if (total_warp > 0) { diff --git a/gpu/kinfu/src/cuda/marching_cubes.cu b/gpu/kinfu/src/cuda/marching_cubes.cu index ca4d10225d9..127f0509e28 100644 --- a/gpu/kinfu/src/cuda/marching_cubes.cu +++ b/gpu/kinfu/src/cuda/marching_cubes.cu @@ -138,14 +138,9 @@ namespace pcl int x = threadIdx.x + blockIdx.x * CTA_SIZE_X; int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y; -#if CUDART_VERSION >= 9000 if (__all_sync (__activemask (), x >= VOLUME_X) || __all_sync (__activemask (), y >= VOLUME_Y)) return; -#else - if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y)) - return; -#endif int ftid = Block::flattenedThreadId (); int warp_id = Warp::id(); @@ -164,11 +159,8 @@ namespace pcl // read number of vertices from texture numVerts = (cubeindex == 0 || cubeindex == 255) ? 0 : tex1Dfetch (numVertsTex, cubeindex); } -#if CUDART_VERSION >= 9000 + int total = __popc (__ballot_sync (__activemask (), numVerts > 0)); -#else - int total = __popc (__ballot (numVerts > 0)); -#endif if (total == 0) continue; @@ -179,11 +171,7 @@ namespace pcl } int old_global_voxels_count = warps_buffer[warp_id]; -#if CUDART_VERSION >= 9000 int offs = Warp::binaryExclScan (__ballot_sync (__activemask (), numVerts > 0)); -#else - int offs = Warp::binaryExclScan (__ballot (numVerts > 0)); -#endif if (old_global_voxels_count + offs < max_size && numVerts > 0) { diff --git a/gpu/kinfu_large_scale/src/cuda/extract.cu b/gpu/kinfu_large_scale/src/cuda/extract.cu index 4707dd897b7..d7db4bedeeb 100644 --- a/gpu/kinfu_large_scale/src/cuda/extract.cu +++ b/gpu/kinfu_large_scale/src/cuda/extract.cu @@ -104,14 +104,9 @@ namespace pcl int x = threadIdx.x + blockIdx.x * CTA_SIZE_X; int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y; - #if CUDART_VERSION >= 9000 if (__all_sync (__activemask (), x >= VOLUME_X) || __all_sync (__activemask (), y >= VOLUME_Y)) return; - #else - if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y)) - return; - #endif float3 V; V.x = (x + 0.5f) * cell_size.x; @@ -201,15 +196,9 @@ namespace pcl }/* if (W != 0 && F != 1.f) */ }/* if (x < VOLUME_X && y < VOLUME_Y) */ - - #if CUDART_VERSION >= 9000 int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0)) + __popc (__ballot_sync (__activemask (), local_count > 1)) + __popc (__ballot_sync (__activemask (), local_count > 2)); - #else - //not we fulfilled points array at current iteration - int total_warp = __popc (__ballot (local_count > 0)) + __popc (__ballot (local_count > 1)) + __popc (__ballot (local_count > 2)); - #endif if (total_warp > 0) { @@ -312,15 +301,9 @@ namespace pcl // local_count counts the number of zero crossing for the current thread. Now we need to merge this knowledge with the other threads // not we fulfilled points array at current iteration - #if CUDART_VERSION >= 9000 int total_warp = __popc (__ballot_sync (__activemask (), local_count > 0)) + __popc (__ballot_sync (__activemask (), local_count > 1)) + __popc (__ballot_sync (__activemask (), local_count > 2)); - #else - int total_warp = __popc (__ballot (local_count > 0)) - + __popc (__ballot (local_count > 1)) - + __popc (__ballot (local_count > 2)); - #endif if (total_warp > 0) ///more than 0 zero-crossings { diff --git a/gpu/kinfu_large_scale/src/cuda/marching_cubes.cu b/gpu/kinfu_large_scale/src/cuda/marching_cubes.cu index 3e89b4e03e0..b1c12de5c3c 100644 --- a/gpu/kinfu_large_scale/src/cuda/marching_cubes.cu +++ b/gpu/kinfu_large_scale/src/cuda/marching_cubes.cu @@ -146,14 +146,9 @@ namespace pcl int x = threadIdx.x + blockIdx.x * CTA_SIZE_X; int y = threadIdx.y + blockIdx.y * CTA_SIZE_Y; - #if CUDART_VERSION >= 9000 if (__all_sync (__activemask (), x >= VOLUME_X) || __all_sync (__activemask (), y >= VOLUME_Y)) return; - #else - if (__all (x >= VOLUME_X) || __all (y >= VOLUME_Y)) - return; - #endif int ftid = Block::flattenedThreadId (); int warp_id = Warp::id(); @@ -173,11 +168,7 @@ namespace pcl numVerts = (cubeindex == 0 || cubeindex == 255) ? 0 : tex1Dfetch (numVertsTex, cubeindex); } - #if CUDART_VERSION >= 9000 int total = __popc (__ballot_sync (__activemask (), numVerts > 0)); - #else - int total = __popc (__ballot (numVerts > 0)); - #endif if (total == 0) continue; @@ -187,12 +178,7 @@ namespace pcl warps_buffer[warp_id] = old; } int old_global_voxels_count = warps_buffer[warp_id]; - - #if CUDART_VERSION >= 9000 int offs = Warp::binaryExclScan (__ballot_sync (__activemask (), numVerts > 0)); - #else - int offs = Warp::binaryExclScan (__ballot (numVerts > 0)); - #endif if (old_global_voxels_count + offs < max_size && numVerts > 0) { diff --git a/gpu/surface/src/cuda/convex_hull.cu b/gpu/surface/src/cuda/convex_hull.cu index e4224f73564..c1f20234eba 100644 --- a/gpu/surface/src/cuda/convex_hull.cu +++ b/gpu/surface/src/cuda/convex_hull.cu @@ -460,13 +460,8 @@ namespace pcl { int idx = threadIdx.x + blockIdx.x * blockDim.x; -#if CUDART_VERSION >= 9000 if (__all_sync (__activemask (), idx >= facet_count)) return; -#else - if (__all (idx >= facet_count)) - return; -#endif int empty = 0; @@ -490,18 +485,11 @@ namespace pcl empty = 1; } -#if CUDART_VERSION >= 9000 int total = __popc (__ballot_sync (__activemask (), empty)); -#else - int total = __popc (__ballot (empty)); -#endif + if (total > 0) { -#if CUDART_VERSION >= 9000 int offset = Warp::binaryExclScan (__ballot_sync (__activemask (), empty)); -#else - int offset = Warp::binaryExclScan (__ballot (empty)); -#endif volatile __shared__ int wapr_buffer[WARPS]; From 9f99947267922cfaecf0e909385d41848d54f74d Mon Sep 17 00:00:00 2001 From: SunBlack Date: Fri, 2 Dec 2022 16:42:35 +0100 Subject: [PATCH 007/288] Fix unused-but-set-variable warnings of Clang 15 --- common/src/io.cpp | 5 ----- gpu/people/src/face_detector.cpp | 4 ---- io/src/obj_io.cpp | 2 -- io/src/ply/ply_parser.cpp | 7 ------- ml/src/svm.cpp | 6 ------ ml/src/svm_wrapper.cpp | 4 ---- .../include/pcl/recognition/face_detection/rf_face_utils.h | 2 -- .../include/pcl/segmentation/impl/cpc_segmentation.hpp | 3 --- .../include/pcl/segmentation/impl/lccp_segmentation.hpp | 2 -- surface/include/pcl/surface/impl/gp3.hpp | 6 +----- surface/include/pcl/surface/impl/grid_projection.hpp | 2 -- surface/src/on_nurbs/sequential_fitter.cpp | 2 -- tools/virtual_scanner.cpp | 6 ------ 13 files changed, 1 insertion(+), 50 deletions(-) diff --git a/common/src/io.cpp b/common/src/io.cpp index c59ef0099a8..46d9ca814ca 100644 --- a/common/src/io.cpp +++ b/common/src/io.cpp @@ -93,9 +93,6 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1, cloud_out.height = cloud2.height; cloud_out.is_bigendian = cloud2.is_bigendian; - //We need to find how many fields overlap between the two clouds - std::size_t total_fields = cloud2.fields.size (); - //for the non-matching fields in cloud1, we need to store the offset //from the beginning of the point std::vector cloud1_unique_fields; @@ -142,8 +139,6 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1, size = cloud1.point_step - cloud1_fields_sorted[i]->offset; field_sizes.push_back (size); - - total_fields++; } } diff --git a/gpu/people/src/face_detector.cpp b/gpu/people/src/face_detector.cpp index 37807be328f..8b396a835a3 100644 --- a/gpu/people/src/face_detector.cpp +++ b/gpu/people/src/face_detector.cpp @@ -120,8 +120,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string haar.bHasStumpsOnly = true; haar.bNeedsTiltedII = false; - Ncv32u cur_max_tree_depth; - std::vector host_temp_classifier_not_root_nodes; haar_stages.resize(0); haarClassifierNodes.resize(0); @@ -258,7 +256,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string { //root node haarClassifierNodes.push_back(current_node); - cur_max_tree_depth = 1; } else { @@ -266,7 +263,6 @@ pcl::gpu::people::FaceDetector::loadFromXML2(const std::string host_temp_classifier_not_root_nodes.push_back(current_node); // TODO replace with PCL_DEBUG in the future PCL_INFO("[pcl::gpu::people::FaceDetector::loadFromXML2] : (I) : Found non root node number %d", host_temp_classifier_not_root_nodes.size()); - cur_max_tree_depth++; } node_identifier++; } diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 81598a3c943..ac75b96069e 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -678,7 +678,6 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, try { std::size_t vn_idx = 0; - std::size_t vt_idx = 0; while (!fs.eof ()) { @@ -747,7 +746,6 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, coordinates.emplace_back(c[0], c[1]); else coordinates.emplace_back(c[0]/c[2], c[1]/c[2]); - ++vt_idx; } catch (const boost::bad_lexical_cast&) { diff --git a/io/src/ply/ply_parser.cpp b/io/src/ply/ply_parser.cpp index 28f7c485366..91011f8b6d0 100644 --- a/io/src/ply/ply_parser.cpp +++ b/io/src/ply/ply_parser.cpp @@ -52,9 +52,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) std::size_t number_of_format_statements = 0; std::size_t number_of_element_statements = 0; - std::size_t number_of_property_statements = 0; - std::size_t number_of_obj_info_statements = 0; - std::size_t number_of_comment_statements = 0; format_type format = pcl::io::ply::unknown; std::vector> elements; @@ -262,7 +259,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) error_callback_ (line_number_, "parse error: unknown type"); return false; } - ++number_of_property_statements; } else { @@ -418,7 +414,6 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) error_callback_ (line_number_, "parse error: unknown list size type"); return false; } - ++number_of_property_statements; } } @@ -426,14 +421,12 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) else if (keyword == "comment") { comment_callback_ (line); - ++number_of_comment_statements; } // obj_info else if (keyword == "obj_info") { obj_info_callback_ (line); - ++number_of_obj_info_statements; } // end_header diff --git a/ml/src/svm.cpp b/ml/src/svm.cpp index 072337f9ce6..6f0eb3db49a 100644 --- a/ml/src/svm.cpp +++ b/ml/src/svm.cpp @@ -3365,8 +3365,6 @@ svm_load_model(const char* model_file_name) model->sv_coef[k][i] = strtod(p, nullptr); } - int jj = 0; - while (true) { char* idx = strtok(nullptr, ":"); char* val = strtok(nullptr, " \t"); @@ -3378,10 +3376,6 @@ svm_load_model(const char* model_file_name) x_space[j].value = strtod(val, nullptr); - // printf("i=%d, j=%d, %f ,%d e %f\n",i,j,model->sv_coef[0][i], - // model->SV[i][jj].index, model->SV[i][jj].value); - jj++; - ++j; } diff --git a/ml/src/svm_wrapper.cpp b/ml/src/svm_wrapper.cpp index cbde3caba15..b6d1adb3c2b 100644 --- a/ml/src/svm_wrapper.cpp +++ b/ml/src/svm_wrapper.cpp @@ -680,8 +680,6 @@ pcl::SVMClassify::classification() getClassName().c_str()); } - // int correct = 0; - int total = 0; int svm_type = svm_get_svm_type(&model_); int nr_class = svm_get_nr_class(&model_); @@ -724,8 +722,6 @@ pcl::SVMClassify::classification() prediction_[ii].push_back(predict_label); } - ++total; - ii++; } diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h index 4fc967e484a..6b49b9c4f3b 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h @@ -368,7 +368,6 @@ namespace pcl std::vector < std::vector > positive_examples; positive_examples.resize (num_of_branches + 1); - std::size_t pos = 0; for (std::size_t example_index = 0; example_index < num_of_examples; ++example_index) { unsigned char branch_index; @@ -383,7 +382,6 @@ namespace pcl positive_examples[branch_index].push_back (examples[example_index]); positive_examples[num_of_branches].push_back (examples[example_index]); - pos++; } } diff --git a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp index 2f0f5a57a0a..05e8ff94214 100644 --- a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp @@ -199,7 +199,6 @@ pcl::CPCSegmentation::applyCuttingPlane (std::uint32_t depth_levels_left for (const auto &cluster_index : cluster_indices) { // get centroids of vertices - int cluster_concave_pts = 0; float cluster_score = 0; // std::cout << "Cluster has " << cluster_indices[cc].indices.size () << " points" << std::endl; for (const auto ¤t_index : cluster_index.indices) @@ -208,8 +207,6 @@ pcl::CPCSegmentation::applyCuttingPlane (std::uint32_t depth_levels_left if (use_directed_weights_) index_score *= 1.414 * (std::abs (plane_normal.dot (edge_cloud_cluster->at (current_index).getNormalVector3fMap ()))); cluster_score += index_score; - if (weights[current_index] > 0) - ++cluster_concave_pts; } // check if the score is below the threshold. If that is the case this segment should not be split cluster_score /= cluster_index.indices.size (); diff --git a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp index 280d3c3ff8c..3bf0777282f 100644 --- a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp @@ -177,7 +177,6 @@ pcl::LCCPSegmentation::mergeSmallSegments () while (continue_filtering) { continue_filtering = false; - unsigned int nr_filtered = 0; VertexIterator sv_itr, sv_itr_end; // Iterate through all supervoxels, check if they are in a "small" segment -> change label to largest neighborID @@ -195,7 +194,6 @@ pcl::LCCPSegmentation::mergeSmallSegments () if (seg_label_to_sv_list_map_[current_seg_label].size () <= min_segment_size_) { continue_filtering = true; - nr_filtered++; // Find largest neighbor for (auto neighbors_itr = seg_label_to_neighbor_set_map_[current_seg_label].cbegin (); neighbors_itr != seg_label_to_neighbor_set_map_[current_seg_label].cend (); ++neighbors_itr) diff --git a/surface/include/pcl/surface/impl/gp3.hpp b/surface/include/pcl/surface/impl/gp3.hpp index bcd87a70373..5f6c4bd449e 100644 --- a/surface/include/pcl/surface/impl/gp3.hpp +++ b/surface/include/pcl/surface/impl/gp3.hpp @@ -134,7 +134,7 @@ pcl::GreedyProjectionTriangulation::reconstructPolygons (std::vector

> uvn_nn (nnn_); Eigen::Vector2f uvn_s; @@ -909,10 +909,6 @@ pcl::GreedyProjectionTriangulation::reconstructPolygons (std::vector

::reconstructPolygons (std::vector &p } Eigen::Vector3i index; - int numOfFilledPad = 0; for (int i = 0; i < data_size_; ++i) { @@ -665,7 +664,6 @@ pcl::GridProjection::reconstructPolygons (std::vector &p if (occupied_cell_list_[getIndexIn1D (index)]) { fillPad (index); - numOfFilledPad++; } } } diff --git a/surface/src/on_nurbs/sequential_fitter.cpp b/surface/src/on_nurbs/sequential_fitter.cpp index 49bb6b511b1..c9c617ec60b 100644 --- a/surface/src/on_nurbs/sequential_fitter.cpp +++ b/surface/src/on_nurbs/sequential_fitter.cpp @@ -493,7 +493,6 @@ SequentialFitter::grow (float max_dist, float max_angle, unsigned min_length, un } float angle = std::cos (max_angle); - unsigned bnd_moved (0); for (unsigned i = 0; i < num_bnd; i++) { @@ -584,7 +583,6 @@ SequentialFitter::grow (float max_dist, float max_angle, unsigned min_length, un this->m_data.boundary[i] (0) = point.x; this->m_data.boundary[i] (1) = point.y; this->m_data.boundary[i] (2) = point.z; - bnd_moved++; } } // i diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index 775ccde3026..d51937acbc0 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -255,7 +255,6 @@ main (int argc, char** argv) if (single_view) number_of_points = 1; - int sid = -1; for (int i = 0; i < number_of_points; i++) { // Clear cloud for next view scan @@ -334,18 +333,13 @@ main (int argc, char** argv) // Sweep vertically for (double vert = vert_start; vert <= vert_end; vert += sp.vert_res) { - sid++; - tr1->Identity (); tr1->RotateWXYZ (vert, right); tr1->InternalTransformPoint (viewray, temp_beam); // Sweep horizontally - int pid = -1; for (double hor = hor_start; hor <= hor_end; hor += sp.hor_res) { - pid ++; - // Create a beam vector with (lat,long) angles (vert, hor) with the viewray tr2->Identity (); tr2->RotateWXYZ (hor, up); From b957fbee3bd837e8c569e0042691ff5c3baf2df7 Mon Sep 17 00:00:00 2001 From: "lilong.huang" Date: Tue, 6 Dec 2022 17:35:51 +0800 Subject: [PATCH 008/288] fix build with vtk by rm vtkMutexLock.h --- outofcore/tools/outofcore_viewer.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/outofcore/tools/outofcore_viewer.cpp b/outofcore/tools/outofcore_viewer.cpp index 6ec57e09359..795e03d7598 100644 --- a/outofcore/tools/outofcore_viewer.cpp +++ b/outofcore/tools/outofcore_viewer.cpp @@ -112,7 +112,6 @@ using AlignedPointT = Eigen::aligned_allocator; #include #include #include -#include #include #include #include From f0a62ae5ab1029c56239efc3d9aa0cfb31573fd2 Mon Sep 17 00:00:00 2001 From: Ka Long Date: Wed, 7 Dec 2022 17:11:25 +0000 Subject: [PATCH 009/288] Update CMakeLists.txt Fix issue on `#include ` and `#include ` not found error --- io/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index 9040f438a2b..55baf49e1aa 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -347,6 +347,7 @@ target_link_libraries("${LIB_NAME}" Boost::boost Boost::filesystem Boost::iostre if(VTK_FOUND) if(${VTK_VERSION} VERSION_GREATER_EQUAL 9.0) target_link_libraries("${LIB_NAME}" + VTK::FiltersGeneral VTK::IOImage VTK::IOGeometry VTK::IOPLY) From 5385dad2f37a246b11f853d11d484b5c04f52f65 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Dec 2022 16:49:56 +0100 Subject: [PATCH 010/288] Bump version to 1.13.0.99 post release --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 17020e162ac..42ea83b98a8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.13.0) +project(PCL VERSION 1.13.0.99) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) ### ---[ Find universal dependencies From 44670ff3f4ce959f0c84b88f0c1acd0a25ac50b1 Mon Sep 17 00:00:00 2001 From: luzpaz Date: Sat, 10 Dec 2022 13:58:46 -0500 Subject: [PATCH 011/288] Fix various typos (#5523) * Fix various typos Found via `codespell -q 3 -S ./CHANGES.md,./surface/src/3rdparty,./surface/include/pcl/surface/3rdparty,./recognition/include/pcl/recognition/3rdparty -L ang,bu,childs,coo,currect,frome,gool,hsi,indeces,ihs,indext,ith,lod,meshe,metre,metres,nd,opps,ot,te,vertexes` * Update cuda/common/include/pcl/cuda/cutil.h Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> * Update filters/src/extract_indices.cpp Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> * Fix typo incorrectly introduced * Added requested changes to svm_wrapper.cpp manually Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- .ci/scripts/build_tutorials.sh | 2 +- .dev/docker/env/Dockerfile | 4 ++-- .dev/docker/perception_pcl_ros/Dockerfile | 2 +- .dev/docker/perception_pcl_ros/colcon.Dockerfile | 2 +- .github/ISSUE_TEMPLATE/compilation-failure.md | 6 +++--- 2d/include/pcl/2d/impl/edge.hpp | 4 ++-- .../cloud_composer/items/cloud_composer_item.h | 6 +++--- .../pcl/apps/cloud_composer/signal_multiplexer.h | 2 +- .../cloud_composer/tool_interface/tool_factory.h | 2 +- .../tools/organized_segmentation.h | 2 +- .../pcl/apps/point_cloud_editor/mainWindow.h | 2 +- apps/src/openni_planar_convex_hull.cpp | 2 +- cmake/Modules/FindOpenMP.cmake | 2 +- cmake/Modules/FindPcap.cmake | 2 +- cmake/pcl_targets.cmake | 2 +- common/include/pcl/common/gaussian.h | 4 ++-- common/include/pcl/common/generate.h | 4 ++-- common/include/pcl/pcl_macros.h | 2 +- common/include/pcl/point_cloud.h | 2 +- common/include/pcl/range_image/range_image.h | 6 +++--- cuda/common/include/pcl/cuda/cutil.h | 2 +- cuda/common/include/pcl/cuda/point_cloud.h | 2 +- .../pcl/cuda/features/normal_3d_kernels.h | 2 +- doc/advanced/content/exceptions_guide.rst | 2 +- doc/advanced/content/pcl_style_guide.rst | 2 +- doc/tutorials/content/fpfh_estimation.rst | 2 +- doc/tutorials/content/function_filter.rst | 2 +- doc/tutorials/content/gpu_install.rst | 2 +- doc/tutorials/content/min_cut_segmentation.rst | 2 +- doc/tutorials/content/qt_colorize_cloud.rst | 2 +- doc/tutorials/content/qt_visualizer.rst | 4 ++-- .../gpu/people_detect/src/people_detect.cpp | 2 +- .../sources/pcl_plotter/pcl_plotter_demo.cpp | 2 +- .../vfh_recognition/nearest_neighbors.cpp | 2 +- doc/tutorials/content/tracking.rst | 2 +- doc/tutorials/content/walkthrough.rst | 2 +- doc/tutorials/content/writing_new_classes.rst | 4 ++-- features/include/pcl/features/boundary.h | 2 +- features/include/pcl/features/flare.h | 2 +- features/include/pcl/features/impl/flare.hpp | 2 +- .../include/pcl/features/impl/intensity_spin.hpp | 2 +- .../include/pcl/features/intensity_gradient.h | 2 +- filters/include/pcl/filters/bilateral.h | 2 +- .../pcl/filters/impl/voxel_grid_covariance.hpp | 4 ++-- .../include/pcl/filters/voxel_grid_covariance.h | 4 ++-- .../filters/voxel_grid_occlusion_estimation.h | 4 ++-- filters/src/extract_indices.cpp | 4 ++-- filters/src/statistical_outlier_removal.cpp | 4 ++-- geometry/include/pcl/geometry/mesh_base.h | 4 ++-- .../include/pcl/gpu/containers/device_array.h | 8 ++++---- .../include/pcl/gpu/containers/device_memory.h | 4 ++-- gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h | 4 ++-- gpu/kinfu/src/internal.h | 4 ++-- gpu/kinfu/tools/evaluation.h | 2 +- gpu/kinfu/tools/kinfu_app.cpp | 10 +++++----- gpu/kinfu/tools/kinfu_app_sim.cpp | 10 +++++----- gpu/kinfu/tools/record_tsdfvolume.cpp | 2 +- gpu/kinfu/tools/tsdf_volume.h | 2 +- .../include/pcl/gpu/kinfu_large_scale/kinfu.h | 4 ++-- gpu/kinfu_large_scale/src/cyclical_buffer.cpp | 2 +- gpu/kinfu_large_scale/src/internal.h | 4 ++-- gpu/kinfu_large_scale/tools/evaluation.h | 2 +- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 4 ++-- gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp | 10 +++++----- .../tools/process_kinfu_large_scale_output.cpp | 2 +- gpu/kinfu_large_scale/tools/record_maps_rgb.cpp | 2 +- .../tools/record_tsdfvolume.cpp | 2 +- gpu/octree/include/pcl/gpu/octree/octree.hpp | 2 +- gpu/people/src/bodyparts_detector.cpp | 4 ++-- gpu/people/src/cuda/elec.cu | 2 +- gpu/people/tools/people_app.cpp | 2 +- .../segmentation/gpu_seeded_hue_segmentation.h | 2 +- .../pcl/compression/impl/entropy_range_coder.hpp | 4 ++-- io/include/pcl/io/io_exception.h | 2 +- io/include/pcl/io/openni_camera/openni_device.h | 2 +- .../pcl/io/openni_camera/openni_exception.h | 2 +- io/include/pcl/io/pcd_io.h | 2 +- io/include/pcl/io/split.h | 2 +- io/include/pcl/io/tim_grabber.h | 2 +- io/src/obj_io.cpp | 2 +- io/src/openni_camera/openni_driver.cpp | 2 +- io/tools/convert_pcd_ascii_binary.cpp | 2 +- keypoints/include/pcl/keypoints/agast_2d.h | 6 +++--- keypoints/include/pcl/keypoints/harris_2d.h | 2 +- keypoints/include/pcl/keypoints/harris_3d.h | 4 ++-- keypoints/include/pcl/keypoints/harris_6d.h | 4 ++-- keypoints/include/pcl/keypoints/iss_3d.h | 2 +- keypoints/include/pcl/keypoints/trajkovic_2d.h | 2 +- keypoints/src/narf_keypoint.cpp | 2 +- ml/include/pcl/ml/dt/decision_tree_trainer.h | 2 +- ml/include/pcl/ml/ferns/fern_trainer.h | 2 +- ml/include/pcl/ml/permutohedral.h | 2 +- ml/include/pcl/ml/stats_estimator.h | 2 +- ml/include/pcl/ml/svm_wrapper.h | 2 +- ml/src/permutohedral.cpp | 6 +++--- ml/src/svm.cpp | 4 ++-- ml/src/svm_wrapper.cpp | 16 +++++++++------- octree/include/pcl/octree/octree2buf_base.h | 2 +- octree/include/pcl/octree/octree_search.h | 2 +- .../impl/outofcore_breadth_first_iterator.hpp | 2 +- .../impl/outofcore_depth_first_iterator.hpp | 2 +- .../include/pcl/outofcore/octree_base_node.h | 6 +++--- .../include/pcl/recognition/crh_alignment.h | 2 +- .../recognition/face_detection/rf_face_utils.h | 2 +- .../pcl/recognition/implicit_shape_model.h | 6 +++--- .../pcl/registration/correspondence_rejection.h | 2 +- registration/include/pcl/registration/ia_fpcs.h | 4 ++-- .../include/pcl/registration/impl/ia_fpcs.hpp | 6 +++--- .../include/pcl/registration/impl/ia_kfpcs.hpp | 2 +- .../include/pcl/registration/impl/icp.hpp | 2 +- .../include/pcl/registration/impl/joint_icp.hpp | 2 +- .../include/pcl/registration/impl/ndt.hpp | 6 +++--- registration/include/pcl/registration/ndt.h | 2 +- .../impl/sac_model_ellipse3d.hpp | 6 +++--- search/include/pcl/search/organized.h | 2 +- .../segmentation/euclidean_cluster_comparator.h | 4 ++-- .../pcl/segmentation/impl/crf_segmentation.hpp | 2 +- .../segmentation/impl/segment_differences.hpp | 2 +- .../segmentation/impl/supervoxel_clustering.hpp | 2 +- .../include/pcl/segmentation/planar_region.h | 2 +- .../pcl/segmentation/seeded_hue_segmentation.h | 2 +- .../pcl/segmentation/supervoxel_clustering.h | 4 ++-- simulation/tools/README_about_tools | 2 +- .../include/pcl/stereo/disparity_map_converter.h | 2 +- stereo/include/pcl/stereo/stereo_matching.h | 2 +- surface/include/pcl/surface/grid_projection.h | 4 ++-- .../include/pcl/surface/impl/texture_mapping.hpp | 2 +- surface/include/pcl/surface/mls.h | 2 +- surface/include/pcl/surface/texture_mapping.h | 2 +- test/features/test_normal_estimation.cpp | 4 ++-- test/octree/test_octree_iterator.cpp | 2 +- test/registration/test_registration.cpp | 2 +- tools/gp3_surface.cpp | 2 +- tools/icp2d.cpp | 2 +- tracking/include/pcl/tracking/coherence.h | 2 +- tracking/include/pcl/tracking/particle_filter.h | 2 +- tracking/include/pcl/tracking/pyramidal_klt.h | 2 +- .../pcl/visualization/common/float_image_utils.h | 2 +- .../include/pcl/visualization/image_viewer.h | 2 +- .../include/pcl/visualization/keyboard_event.h | 6 +++--- .../include/pcl/visualization/pcl_plotter.h | 2 +- .../include/pcl/visualization/pcl_visualizer.h | 2 +- .../point_cloud_geometry_handlers.h | 2 +- .../vtk/vtkFixedXRenderWindowInteractor.h | 2 +- visualization/src/pcl_painter2D.cpp | 2 +- .../src/vtk/vtkFixedXRenderWindowInteractor.cxx | 2 +- 146 files changed, 219 insertions(+), 217 deletions(-) diff --git a/.ci/scripts/build_tutorials.sh b/.ci/scripts/build_tutorials.sh index c26d02d974e..dac46f7444f 100755 --- a/.ci/scripts/build_tutorials.sh +++ b/.ci/scripts/build_tutorials.sh @@ -8,7 +8,7 @@ This script builds source code projects of PCL tutorials. Options: - -h Dispaly this help and exit. + -h Display this help and exit. -k Keep going after a configuration/build error. -s Print summary in the end. -e NAMES Exclude tutorials from the build. diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index fb7012e3336..e2cabbd76c6 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -2,7 +2,7 @@ ARG UBUNTU_VERSION=20.04 FROM "ubuntu:${UBUNTU_VERSION}" -# Eigen patch (https://eigen.tuxfamily.org/bz/show_bug.cgi?id=1462) to fix issue metioned +# Eigen patch (https://eigen.tuxfamily.org/bz/show_bug.cgi?id=1462) to fix issue mentioned # in https://github.com/PointCloudLibrary/pcl/issues/3729 is available in Eigen 3.3.7. # Not needed from 20.04 since it is the default version from apt ARG EIGEN_MINIMUM_VERSION=3.3.7 @@ -14,7 +14,7 @@ ARG ENSENSOSDK_VERSION=3.2.489 ARG REALSENSE_VERSION=2.50.0 # Check https://packages.ubuntu.com/search?suite=all&arch=any&searchon=names&keywords=libvtk%20qt-dev -# for available packes for choosen UBUNTU_VERSION +# for available packages for chosen UBUNTU_VERSION ARG VTK_VERSION=6 # Use the latest version of CMake by adding the Kitware repository if true, diff --git a/.dev/docker/perception_pcl_ros/Dockerfile b/.dev/docker/perception_pcl_ros/Dockerfile index 6d189fcbb21..2541cc6837b 100644 --- a/.dev/docker/perception_pcl_ros/Dockerfile +++ b/.dev/docker/perception_pcl_ros/Dockerfile @@ -10,7 +10,7 @@ COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall # Be careful: # * ROS uses Python2 -# * source ROS setup file in evey RUN snippet +# * source ROS setup file in every RUN snippet # # The dependencies of PCL can be reduced since # * we don't need to build visualization or docs diff --git a/.dev/docker/perception_pcl_ros/colcon.Dockerfile b/.dev/docker/perception_pcl_ros/colcon.Dockerfile index ad38e549e09..a215b025f43 100644 --- a/.dev/docker/perception_pcl_ros/colcon.Dockerfile +++ b/.dev/docker/perception_pcl_ros/colcon.Dockerfile @@ -9,7 +9,7 @@ ARG workspace="/root/catkin_ws" COPY ${flavor}_rosinstall.yaml ${workspace}/src/.rosinstall # Be careful: -# * source ROS setup file in evey RUN snippet +# * source ROS setup file in every RUN snippet # # TODO: The dependencies of PCL can be reduced since # * we don't need to build visualization or docs diff --git a/.github/ISSUE_TEMPLATE/compilation-failure.md b/.github/ISSUE_TEMPLATE/compilation-failure.md index 77771e2865b..1d5aa3cfe8b 100644 --- a/.github/ISSUE_TEMPLATE/compilation-failure.md +++ b/.github/ISSUE_TEMPLATE/compilation-failure.md @@ -15,9 +15,9 @@ Please paste the compilation results/errors. **To Reproduce** Provide a link to a live example, or an unambiguous set of steps to reproduce this bug. A reproducible example helps to provide faster answers. Custom OS, custom PCL configs or custom build systems make the issue difficult to reproduce. -* Best reproducability: A docker image + code snippets provided here -* Good reproducability: Common Linux OS + default PCL config + code snippets provided here -* Poor reproducability: code snippets +* Best reproducibility: A docker image + code snippets provided here +* Good reproducibility: Common Linux OS + default PCL config + code snippets provided here +* Poor reproducibility: code snippets Remember to reproduce the error in a clean rebuild (removing all build objects and starting build from scratch) diff --git a/2d/include/pcl/2d/impl/edge.hpp b/2d/include/pcl/2d/impl/edge.hpp index 22bdd74af7d..a13ead96e88 100644 --- a/2d/include/pcl/2d/impl/edge.hpp +++ b/2d/include/pcl/2d/impl/edge.hpp @@ -266,7 +266,7 @@ Edge::suppressNonMaxima( for (auto& point : maxima) point.intensity = 0.0f; - // tHigh and non-maximal supression + // tHigh and non-maximal suppression for (int i = 1; i < height - 1; i++) { for (int j = 1; j < width - 1; j++) { const PointXYZIEdge& ptedge = edges(j, i); @@ -339,7 +339,7 @@ Edge::detectEdgeCanny(pcl::PointCloud& output) // Edge discretization discretizeAngles(*edges); - // tHigh and non-maximal supression + // tHigh and non-maximal suppression pcl::PointCloud::Ptr maxima(new pcl::PointCloud); suppressNonMaxima(*edges, *maxima, tLow); diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/items/cloud_composer_item.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/items/cloud_composer_item.h index 7252b216b6d..07f9bc10355 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/items/cloud_composer_item.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/items/cloud_composer_item.h @@ -111,15 +111,15 @@ namespace pcl // CloudPtrT // getCloudPtr () const; - /** \brief Paint View function - reimpliment in item subclass if it can be displayed in PCLVisualizer*/ + /** \brief Paint View function - reimplement in item subclass if it can be displayed in PCLVisualizer*/ virtual void paintView (pcl::visualization::PCLVisualizer::Ptr vis) const; - /** \brief Remove from View function - reimpliment in item subclass if it can be displayed in PCLVisualizer*/ + /** \brief Remove from View function - reimplement in item subclass if it can be displayed in PCLVisualizer*/ virtual void removeFromView (pcl::visualization::PCLVisualizer::Ptr vis) const; - /** \brief Inspector additional tabs paint function - reimpliment in item subclass if item has additional tabs to show in Inspector*/ + /** \brief Inspector additional tabs paint function - reimplement in item subclass if item has additional tabs to show in Inspector*/ virtual QMap getInspectorTabs (); diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h index ee74b82a3f5..86c72299a5b 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h @@ -94,7 +94,7 @@ namespace pcl connect (const char *signal, QObject *receiver, const char *slot); /** - Disconencts a signal from a multiplexed object to a receiving (action) + Disconnects a signal from a multiplexed object to a receiving (action) object. @see connect(const char *signal, QObject *receiver, const char *slot) */ diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/tool_interface/tool_factory.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/tool_interface/tool_factory.h index 6429f8d1f6b..65781efadcd 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/tool_interface/tool_factory.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/tool_interface/tool_factory.h @@ -69,7 +69,7 @@ namespace pcl virtual QString getIconName () const = 0; - /** \brief Reimpliment this function to return the proper number if tool requires more than one input item */ + /** \brief Reimplement this function to return the proper number if tool requires more than one input item */ inline virtual int getNumInputItems () const { diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/organized_segmentation.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/organized_segmentation.h index 018c7a8e65f..a35d946d2ba 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/organized_segmentation.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/tools/organized_segmentation.h @@ -58,7 +58,7 @@ performTemplatedAction (const QList & input_data); inline QString - getToolName () const override { return "Organized Segmenation Tool";} + getToolName () const override { return "Organized Segmentation Tool";} }; diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/mainWindow.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/mainWindow.h index bfa2e997079..ded8c6b1c4f 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/mainWindow.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/mainWindow.h @@ -68,7 +68,7 @@ class MainWindow : public QMainWindow /// @brief Constructor /// @param argc The number of c-strings to be expected in argv /// @param argv An array of c-strings. The zero entry is expected to be - /// the name of the appliation. Any additional strings will be interpreted + /// the name of the application. Any additional strings will be interpreted /// as filenames designating point clouds to be loaded. MainWindow (int argc, char **argv); diff --git a/apps/src/openni_planar_convex_hull.cpp b/apps/src/openni_planar_convex_hull.cpp index 0cc1223f136..fab465bcf93 100644 --- a/apps/src/openni_planar_convex_hull.cpp +++ b/apps/src/openni_planar_convex_hull.cpp @@ -161,7 +161,7 @@ usage(char** argv) std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (wotks only in Linux) or" << std::endl + << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl << " (only in Linux and for devices which provide serial numbers)" << std::endl; // clang-format on } diff --git a/cmake/Modules/FindOpenMP.cmake b/cmake/Modules/FindOpenMP.cmake index cd17a179fcf..b4f6a6a1d82 100644 --- a/cmake/Modules/FindOpenMP.cmake +++ b/cmake/Modules/FindOpenMP.cmake @@ -154,7 +154,7 @@ int main(void) { # in Fortran, an implementation may provide an omp_lib.h header # or omp_lib module, or both (OpenMP standard, section 3.1) -# Furthmore !$ is the Fortran equivalent of #ifdef _OPENMP (OpenMP standard, 2.2.2) +# Furthermore !$ is the Fortran equivalent of #ifdef _OPENMP (OpenMP standard, 2.2.2) # Without the conditional compilation, some compilers (e.g. PGI) might compile OpenMP code # while not actually enabling OpenMP, building code sequentially set(OpenMP_Fortran_TEST_SOURCE diff --git a/cmake/Modules/FindPcap.cmake b/cmake/Modules/FindPcap.cmake index 65f84b38c27..ecc2e781b43 100644 --- a/cmake/Modules/FindPcap.cmake +++ b/cmake/Modules/FindPcap.cmake @@ -38,7 +38,7 @@ # Find the PCAP includes and library # http://www.tcpdump.org/ # -# The environment variable PCAPDIR allows to specficy where to find +# The environment variable PCAPDIR allows to specify where to find # libpcap in non standard location. # # 2012/01/02 - KEVEN RING diff --git a/cmake/pcl_targets.cmake b/cmake/pcl_targets.cmake index 86d06d0c836..2da076c23c5 100644 --- a/cmake/pcl_targets.cmake +++ b/cmake/pcl_targets.cmake @@ -310,7 +310,7 @@ function(PCL_ADD_EXECUTABLE _name) endif() # Some app targets report are defined with subsys other than apps - # It's simpler check for tools and assume everythin else as an app + # It's simpler check for tools and assume everything else as an app if(${ARGS_COMPONENT} STREQUAL "tools") set_target_properties(${_name} PROPERTIES FOLDER "Tools") else() diff --git a/common/include/pcl/common/gaussian.h b/common/include/pcl/common/gaussian.h index 9c7e0130b1e..8742ed32b2b 100644 --- a/common/include/pcl/common/gaussian.h +++ b/common/include/pcl/common/gaussian.h @@ -59,7 +59,7 @@ namespace pcl public: static const unsigned MAX_KERNEL_WIDTH = 71; - /** Computes the gaussian kernel and dervative assiociated to sigma. + /** Computes the gaussian kernel and dervative associated to sigma. * The kernel and derivative width are adjusted according. * \param[in] sigma * \param[out] kernel the computed gaussian kernel @@ -71,7 +71,7 @@ namespace pcl Eigen::VectorXf &kernel, unsigned kernel_width = MAX_KERNEL_WIDTH) const; - /** Computes the gaussian kernel and dervative assiociated to sigma. + /** Computes the gaussian kernel and dervative associated to sigma. * The kernel and derivative width are adjusted according. * \param[in] sigma * \param[out] kernel the computed gaussian kernel diff --git a/common/include/pcl/common/generate.h b/common/include/pcl/common/generate.h index 4e4fb1c4822..b3c4ae68e69 100644 --- a/common/include/pcl/common/generate.h +++ b/common/include/pcl/common/generate.h @@ -48,7 +48,7 @@ namespace pcl namespace common { - /** \brief CloudGenerator class generates a point cloud using some randoom number generator. + /** \brief CloudGenerator class generates a point cloud using some random number generator. * Generators can be found in \file common/random.h and easily extensible. * * \ingroup common @@ -79,7 +79,7 @@ namespace pcl const GeneratorParameters& z_params); /** Set parameters for x, y and z values. Uniqueness is ensured through seed incrementation. - * \param params parameteres for X, Y and Z values generation. + * \param params parameters for X, Y and Z values generation. */ void setParameters (const GeneratorParameters& params); diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index 298c58b37aa..da487b5e1bc 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -49,7 +49,7 @@ #if defined _MSC_VER // 4244 : conversion from 'type1' to 'type2', possible loss of data - // 4661 : no suitable definition provided for explicit template instantiation reques + // 4661 : no suitable definition provided for explicit template instantiation request // 4503 : decorated name length exceeded, name was truncated // 4146 : unary minus operator applied to unsigned type, result still unsigned #pragma warning (disable: 4018 4244 4267 4521 4251 4661 4305 4503 4146) diff --git a/common/include/pcl/point_cloud.h b/common/include/pcl/point_cloud.h index fa2172df178..a5607bffced 100644 --- a/common/include/pcl/point_cloud.h +++ b/common/include/pcl/point_cloud.h @@ -204,7 +204,7 @@ namespace pcl , height (height_) {} - //TODO: check if copy/move contructors/assignment operators are needed + //TODO: check if copy/move constructors/assignment operators are needed /** \brief Add a point cloud to the current cloud. * \param[in] rhs the cloud to add to the current cloud diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 782516d564b..5cf84900c05 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -397,7 +397,7 @@ namespace pcl inline PointWithRange& getPoint (float image_x, float image_y); - /** \brief Return the 3D point with range at the given image position. This methd performs no error checking + /** \brief Return the 3D point with range at the given image position. This method performs no error checking * to make sure the specified image position is inside of the image! * \param image_x the x coordinate * \param image_y the y coordinate @@ -590,13 +590,13 @@ namespace pcl getAcutenessValueImages (int pixel_distance, float*& acuteness_value_image_x, float*& acuteness_value_image_y) const; - /** Calculates, how much the surface changes at a point. Pi meaning a flat suface and 0.0f + /** Calculates, how much the surface changes at a point. Pi meaning a flat surface and 0.0f * would be a needle point */ //inline float // getSurfaceChange (const PointWithRange& point, const PointWithRange& neighbor1, // const PointWithRange& neighbor2) const; - /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat suface */ + /** Calculates, how much the surface changes at a point. 1 meaning a 90deg angle and 0 a flat surface */ PCL_EXPORTS float getSurfaceChange (int x, int y, int radius) const; diff --git a/cuda/common/include/pcl/cuda/cutil.h b/cuda/common/include/pcl/cuda/cutil.h index eee7ab5e1a7..194ce11464a 100644 --- a/cuda/common/include/pcl/cuda/cutil.h +++ b/cuda/common/include/pcl/cuda/cutil.h @@ -595,7 +595,7 @@ extern "C" { const unsigned int len, const float epsilon, const float threshold ); //////////////////////////////////////////////////////////////////////////////// - //! Compare two integer arrays witha n epsilon tolerance for equality + //! Compare two integer arrays with an epsilon tolerance for equality //! @return CUTTrue if \a reference and \a data are identical, //! otherwise CUTFalse //! @param reference handle to the reference data / gold image diff --git a/cuda/common/include/pcl/cuda/point_cloud.h b/cuda/common/include/pcl/cuda/point_cloud.h index 4435f61f5b3..16e7f249033 100644 --- a/cuda/common/include/pcl/cuda/point_cloud.h +++ b/cuda/common/include/pcl/cuda/point_cloud.h @@ -255,7 +255,7 @@ namespace pcl return (points_x.size ()); } - /** \brief Check if the internal pooint data vectors are valid. */ + /** \brief Check if the internal point data vectors are valid. */ bool sane () const { diff --git a/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h b/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h index ec6473eef85..2b4c9720ad5 100644 --- a/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h +++ b/cuda/features/include/pcl/cuda/features/normal_3d_kernels.h @@ -80,7 +80,7 @@ namespace pcl float curvature = evals.x / (query_pt.z * (0.2f / 4.0f) * query_pt.z * (0.2f / 4.0f)); float3 mc = normalize (evecs.data[0]); - // TODO: this should be an optional step, as it slows down eveything + // TODO: this should be an optional step, as it slows down everything // btw, this flips the normals to face the origin (assumed to be the view point) if ( dot (query_pt, mc) > 0 ) mc = -mc; diff --git a/doc/advanced/content/exceptions_guide.rst b/doc/advanced/content/exceptions_guide.rst index d337a6481a1..18eadc8ccb1 100644 --- a/doc/advanced/content/exceptions_guide.rst +++ b/doc/advanced/content/exceptions_guide.rst @@ -102,6 +102,6 @@ rule that can be applied but here are some of the most used guidelines: * exit with some error if the exception is critical * modify the parameters for the function that threw the exception and recall it again - * throw an exception with a meaningful message saying that you encountred an exception + * throw an exception with a meaningful message saying that you encountered an exception * continue (really bad) diff --git a/doc/advanced/content/pcl_style_guide.rst b/doc/advanced/content/pcl_style_guide.rst index 34bbe40d667..19b10bd6cc5 100644 --- a/doc/advanced/content/pcl_style_guide.rst +++ b/doc/advanced/content/pcl_style_guide.rst @@ -397,7 +397,7 @@ For get/set type methods the following rules apply: * If large amounts of data needs to be set (usually the case with input data in PCL) it is preferred to pass a boost shared pointer instead of the actual data. -* Getters always need to pass exactly the same types as their repsective setters +* Getters always need to pass exactly the same types as their respective setters and vice versa. * For getters, if only one argument needs to be passed this will be done via the return keyword. If two or more arguments need to be passed they will diff --git a/doc/tutorials/content/fpfh_estimation.rst b/doc/tutorials/content/fpfh_estimation.rst index cdc9711ea83..a5aa5a3ed49 100644 --- a/doc/tutorials/content/fpfh_estimation.rst +++ b/doc/tutorials/content/fpfh_estimation.rst @@ -90,7 +90,7 @@ library. The default FPFH implementation uses 11 binning subdivisions (e.g., each of the four feature values will use this many bins from its value interval), and a decorrelated scheme (see above: the feature histograms are computed separately -and concantenated) which results in a 33-byte array of float values. These are +and concatenated) which results in a 33-byte array of float values. These are stored in a **pcl::FPFHSignature33** point type. The following code snippet will estimate a set of FPFH features for all the diff --git a/doc/tutorials/content/function_filter.rst b/doc/tutorials/content/function_filter.rst index 59ed23355c2..c8b3b8450c7 100644 --- a/doc/tutorials/content/function_filter.rst +++ b/doc/tutorials/content/function_filter.rst @@ -4,7 +4,7 @@ Removing outliers using a custom non-destructive condition ---------------------------------------------------------- This document demonstrates how to use the FunctionFilter class to remove points from a PointCloud that do not satisfy a custom criteria. This is a cleaner -and faster appraoch compared to ConditionalRemoval filter or a `custom Condition class `_. +and faster approach 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 `_. diff --git a/doc/tutorials/content/gpu_install.rst b/doc/tutorials/content/gpu_install.rst index 5b58a5ceb9a..a06eaf12ec0 100644 --- a/doc/tutorials/content/gpu_install.rst +++ b/doc/tutorials/content/gpu_install.rst @@ -4,7 +4,7 @@ Configuring your PC to use your Nvidia GPU with PCL --------------------------------------------------- In this tutorial you will learn how to configure your system to make it compatible to run the GPU methods provided by PCL. -This tutorial is for Ubuntu, other Linux distrubutions can follow a similar process to set it up. +This tutorial is for Ubuntu, other Linux distributions can follow a similar process to set it up. Windows is currently **not** officially supported for the GPU methods. diff --git a/doc/tutorials/content/min_cut_segmentation.rst b/doc/tutorials/content/min_cut_segmentation.rst index 3fb1dd8823a..109af80370c 100644 --- a/doc/tutorials/content/min_cut_segmentation.rst +++ b/doc/tutorials/content/min_cut_segmentation.rst @@ -78,7 +78,7 @@ The purpose of these lines is to show that ``pcl::MinCutSegmentation`` class can :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. +It is the template 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 diff --git a/doc/tutorials/content/qt_colorize_cloud.rst b/doc/tutorials/content/qt_colorize_cloud.rst index 443fe23b195..9043766ae4c 100644 --- a/doc/tutorials/content/qt_colorize_cloud.rst +++ b/doc/tutorials/content/qt_colorize_cloud.rst @@ -82,7 +82,7 @@ pclviewer.cpp :language: cpp :lines: 8-12 -We initialize the members of our class to default values (note that theses values should match with the UI buttons ticked) +We initialize the members of our class to default values (note that these values should match with the UI buttons ticked) .. literalinclude:: sources/qt_colorize_cloud/pclviewer.cpp :language: cpp diff --git a/doc/tutorials/content/qt_visualizer.rst b/doc/tutorials/content/qt_visualizer.rst index 08c2b75d187..ee8a774f735 100644 --- a/doc/tutorials/content/qt_visualizer.rst +++ b/doc/tutorials/content/qt_visualizer.rst @@ -52,7 +52,7 @@ Use relative paths like this is better than absolute paths; this project should We specify in the general section that we want to build in the folder ``../build`` (this is a relative path from the ``.pro`` file). The first step of the building is to call ``cmake`` (from the ``build`` folder) with argument ``../src``; this is gonna create all files in the -``build`` folder without modifying anything in the ``src`` foler; thus keeping it clean. +``build`` folder without modifying anything in the ``src`` folder; thus keeping it clean. Then we just have to compile our program; the argument ``-j2`` allow to specify how many thread of your CPU you want to use for compilation. The more thread you use the faster the compilation will be (especially on big projects); but if you take all threads from the CPU your OS will likely be unresponsive during @@ -192,7 +192,7 @@ Here we connect slots and signals, this links UI actions to functions. Here is a | This is the last part of our constructor; we add the point cloud to the visualizer, call the method ``pSliderValueChanged`` to change the point size to 2. -We finally reset the camera within the PCL Visualizer not avoid the user having to zoom out and refesh the view to be +We finally reset the camera within the PCL Visualizer not avoid the user having to zoom out and refresh the view to be sure the modifications will be displayed. .. literalinclude:: sources/qt_visualizer/pclviewer.cpp diff --git a/doc/tutorials/content/sources/gpu/people_detect/src/people_detect.cpp b/doc/tutorials/content/sources/gpu/people_detect/src/people_detect.cpp index 025ed22ae89..47d4ae62175 100644 --- a/doc/tutorials/content/sources/gpu/people_detect/src/people_detect.cpp +++ b/doc/tutorials/content/sources/gpu/people_detect/src/people_detect.cpp @@ -318,7 +318,7 @@ class PeoplePCDApp int main(int argc, char** argv) { - // selecting GPU and prining info + // selecting GPU and printing info int device = 0; pc::parse_argument (argc, argv, "-gpu", device); pcl::gpu::setDevice (device); 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 d1e173abba3..218b3715a46 100644 --- a/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp +++ b/doc/tutorials/content/sources/pcl_plotter/pcl_plotter_demo.cpp @@ -47,7 +47,7 @@ main () //setting some properties plotter->setShowLegend (true); - //generating point correspondances + //generating point correspondences int numPoints = 69; double ax[100], acos[100], asin[100]; generateData (ax, acos, asin, numPoints); diff --git a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp index 783c092bbd3..e377394bcd6 100644 --- a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp @@ -267,7 +267,7 @@ main (int argc, char** argv) // Add the cluster name p.addText (cloud_name, 20, 10, cloud_name, viewport); } - // Add coordianate systems to all viewports + // Add coordinate systems to all viewports p.addCoordinateSystem (0.1, "global", 0); p.spin (); diff --git a/doc/tutorials/content/tracking.rst b/doc/tutorials/content/tracking.rst index 8625bfc3b7e..5ca1b1a1509 100644 --- a/doc/tutorials/content/tracking.rst +++ b/doc/tutorials/content/tracking.rst @@ -132,5 +132,5 @@ After few seconds, tracking will start working and you can move tracking object More Advanced ------------- -If you want to see more flexible and useful tracking code which starts tracking without preparing to make segemented model beforehand, you should refer a tracking code https://github.com/PointCloudLibrary/pcl/blob/master/apps/src/openni_tracking.cpp. It will show you better and more legible code. The above Figures are windows when you implement that code. +If you want to see more flexible and useful tracking code which starts tracking without preparing to make segmented model beforehand, you should refer a tracking code https://github.com/PointCloudLibrary/pcl/blob/master/apps/src/openni_tracking.cpp. It will show you better and more legible code. The above Figures are windows when you implement that code. diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index 33c26903a21..7cd28fec69f 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -730,7 +730,7 @@ This section provides a quick reference for some of the common tools in PCL. ``pcl_pcd_convert_NaN_nan input.pcd output.pcd`` - * ``pcl_convert_pcd_ascii_binary``: converts PCD (Point Cloud Data) files from ASCII to binary and viceversa. + * ``pcl_convert_pcd_ascii_binary``: converts PCD (Point Cloud Data) files from ASCII to binary and vice-versa. **Usage example:** diff --git a/doc/tutorials/content/writing_new_classes.rst b/doc/tutorials/content/writing_new_classes.rst index d823ddb84c0..2dab0a40f77 100644 --- a/doc/tutorials/content/writing_new_classes.rst +++ b/doc/tutorials/content/writing_new_classes.rst @@ -770,7 +770,7 @@ defines a way to define a region of interest / *list of point indices* that the algorithm should operate on, rather than the entire cloud, via :pcl:`setIndices`. -All classes inheriting from :pcl:`PCLBase` exhbit the following +All classes inheriting from :pcl:`PCLBase` exhibit the following behavior: in case no set of indices is given by the user, a fake one is created once and used for the duration of the algorithm. This means that we could easily change the implementation code above to operate on a ** @@ -986,7 +986,7 @@ class look like: /** \brief Compute the intensity average for a single point * \param[in] pid the point index to compute the weight for - * \param[in] indices the set of nearest neighor indices + * \param[in] indices the set of nearest neighbor indices * \param[in] distances the set of nearest neighbor distances * \return the intensity average at a given point index */ diff --git a/features/include/pcl/features/boundary.h b/features/include/pcl/features/boundary.h index c9bc22ade6a..a56be0abf13 100644 --- a/features/include/pcl/features/boundary.h +++ b/features/include/pcl/features/boundary.h @@ -121,7 +121,7 @@ namespace pcl /** \brief Check whether a point is a boundary point in a planar patch of projected points given by indices. * \note A coordinate system u-v-n must be computed a-priori using \a getCoordinateSystemOnPlane * \param[in] cloud a pointer to the input point cloud - * \param[in] q_point a pointer to the querry point + * \param[in] q_point a pointer to the query point * \param[in] indices the estimated point neighbors of the query point * \param[in] u the u direction * \param[in] v the v direction diff --git a/features/include/pcl/features/flare.h b/features/include/pcl/features/flare.h index b0f37e409ee..be47ba868e6 100644 --- a/features/include/pcl/features/flare.h +++ b/features/include/pcl/features/flare.h @@ -213,7 +213,7 @@ namespace pcl inline void setSearchMethodForSampledSurface (const KdTreePtr &tree) { sampled_tree_ = tree; } - /** \brief Get a pointer to the search method used for the extimation of x axis. */ + /** \brief Get a pointer to the search method used for the estimation of x axis. */ inline const KdTreePtr& getSearchMethodForSampledSurface () const { diff --git a/features/include/pcl/features/impl/flare.hpp b/features/include/pcl/features/impl/flare.hpp index ba841a2ca6f..2f8d3c9577d 100644 --- a/features/include/pcl/features/impl/flare.hpp +++ b/features/include/pcl/features/impl/flare.hpp @@ -142,7 +142,7 @@ template (*normals_, neighbours_indices, fitted_normal)) { - //all normals in the neighbourood are invalid + //all normals in the neighbourhood are invalid //setting lrf to NaN lrf.setConstant (std::numeric_limits::quiet_NaN ()); return (std::numeric_limits::max ()); diff --git a/features/include/pcl/features/impl/intensity_spin.hpp b/features/include/pcl/features/impl/intensity_spin.hpp index cffb505622a..b7dd7ae4b4f 100644 --- a/features/include/pcl/features/impl/intensity_spin.hpp +++ b/features/include/pcl/features/impl/intensity_spin.hpp @@ -147,7 +147,7 @@ pcl::IntensitySpinEstimation::computeFeature (PointCloudOut for (std::size_t idx = 0; idx < indices_->size (); ++idx) { // Find neighbors within the search radius - // TODO: do we want to use searchForNeigbors instead? + // TODO: do we want to use searchForNeighbors instead? int k = tree_->radiusSearch ((*indices_)[idx], search_radius_, nn_indices, nn_dist_sqr); if (k == 0) { diff --git a/features/include/pcl/features/intensity_gradient.h b/features/include/pcl/features/intensity_gradient.h index e8a2a1aaa51..768fb71a6c0 100644 --- a/features/include/pcl/features/intensity_gradient.h +++ b/features/include/pcl/features/intensity_gradient.h @@ -90,7 +90,7 @@ namespace pcl /** \brief Estimate the intensity gradient around a given point based on its spatial neighborhood of points * \param cloud a point cloud dataset containing XYZI coordinates (Cartesian coordinates + intensity) - * \param indices the indices of the neighoring points in the dataset + * \param indices the indices of the neighboring points in the dataset * \param point the 3D Cartesian coordinates of the point at which to estimate the gradient * \param mean_intensity * \param normal the 3D surface normal of the given point diff --git a/filters/include/pcl/filters/bilateral.h b/filters/include/pcl/filters/bilateral.h index fc5353fdf80..e1065797f84 100644 --- a/filters/include/pcl/filters/bilateral.h +++ b/filters/include/pcl/filters/bilateral.h @@ -75,7 +75,7 @@ namespace pcl } /** \brief Compute the intensity average for a single point * \param[in] pid the point index to compute the weight for - * \param[in] indices the set of nearest neighor indices + * \param[in] indices the set of nearest neighbor indices * \param[in] distances the set of nearest neighbor distances * \return the intensity average at a given point index */ diff --git a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp index b67351dcdfc..0c4c458bac4 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp @@ -267,7 +267,7 @@ pcl::VoxelGridCovariance::applyFilter (PointCloud &output) if (save_leaf_layout_) leaf_layout_.resize (div_b_[0] * div_b_[1] * div_b_[2], -1); - // Eigen values and vectors calculated to prevent near singluar matrices + // Eigen values and vectors calculated to prevent near singular matrices Eigen::SelfAdjointEigenSolver eigensolver; Eigen::Matrix3d eigen_val; Eigen::Vector3d pt_sum; @@ -289,7 +289,7 @@ pcl::VoxelGridCovariance::applyFilter (PointCloud &output) leaf.mean_ /= leaf.nr_points; // If the voxel contains sufficient points, its covariance is calculated and is added to the voxel centroids and output clouds. - // Points with less than the minimum points will have a can not be accuratly approximated using a normal distribution. + // Points with less than the minimum points will have a can not be accurately approximated using a normal distribution. if (leaf.nr_points >= min_points_per_voxel_) { if (save_leaf_layout_) diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index 67b9fe2f7f8..e2c815d3cb4 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -44,7 +44,7 @@ namespace pcl { - /** \brief A searchable voxel strucure containing the mean and covariance of the data. + /** \brief A searchable voxel structure containing the mean and covariance of the data. * \note For more information please see * Magnusson, M. (2009). The Three-Dimensional Normal-Distributions Transform — * an Efficient Representation for Registration, Surface Analysis, and Loop Detection. @@ -582,7 +582,7 @@ namespace pcl /** \brief Point cloud containing centroids of voxels containing atleast minimum number of points. */ PointCloudPtr voxel_centroids_; - /** \brief Indices of leaf structurs associated with each point in \ref voxel_centroids_ (used for searching). */ + /** \brief Indices of leaf structures associated with each point in \ref voxel_centroids_ (used for searching). */ std::vector voxel_centroids_leaf_indices_; /** \brief KdTree generated using \ref voxel_centroids_ (used for searching). */ diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index b148e2bd282..4285fb2bfc7 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -179,7 +179,7 @@ namespace pcl const Eigen::Vector4f& direction); /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) - * unsing a ray traversal algorithm. + * using a ray traversal algorithm. * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k). * \param[in] origin The sensor origin. * \param[in] direction The sensor orientation @@ -193,7 +193,7 @@ namespace pcl const float t_min); /** \brief Returns the state of the target voxel (0 = visible, 1 = occupied) and - * the voxels penetrated by the ray unsing a ray traversal algorithm. + * the voxels penetrated by the ray using a ray traversal algorithm. * \param[out] out_ray The voxels penetrated by the ray in (i, j, k) coordinates * \param[in] target_voxel The target voxel in the voxel grid with coordinate (i, j, k). * \param[in] origin The sensor origin. diff --git a/filters/src/extract_indices.cpp b/filters/src/extract_indices.cpp index 6ac3544d895..14d04e13af2 100644 --- a/filters/src/extract_indices.cpp +++ b/filters/src/extract_indices.cpp @@ -65,7 +65,7 @@ pcl::ExtractIndices::applyFilter (PCLPointCloud2 &output) Indices indices = *indices_; std::sort (indices.begin (), indices.end ()); - // Get the diference + // Get the difference Indices remaining_indices; set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (), inserter (remaining_indices, remaining_indices.begin ())); @@ -120,7 +120,7 @@ pcl::ExtractIndices::applyFilter (PCLPointCloud2 &output) Indices indices = *indices_; std::sort (indices.begin (), indices.end ()); - // Get the diference + // Get the difference Indices remaining_indices; set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (), inserter (remaining_indices, remaining_indices.begin ())); diff --git a/filters/src/statistical_outlier_removal.cpp b/filters/src/statistical_outlier_removal.cpp index baaf90b9efc..3690d86c3fa 100644 --- a/filters/src/statistical_outlier_removal.cpp +++ b/filters/src/statistical_outlier_removal.cpp @@ -56,7 +56,7 @@ pcl::StatisticalOutlierRemoval::applyFilter (PCLPointCloud2 if (std_mul_ == 0.0) { - PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!\n", getClassName ().c_str ()); + PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multiplier not set!\n", getClassName ().c_str ()); output.width = output.height = 0; output.data.clear (); return; @@ -147,7 +147,7 @@ pcl::StatisticalOutlierRemoval::applyFilter (Indices& indic if (std_mul_ == 0.0) { - PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multipler not set!\n", getClassName ().c_str ()); + PCL_ERROR ("[pcl::%s::applyFilter] Standard deviation multiplier not set!\n", getClassName ().c_str ()); indices.clear(); return; } diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index 4928236aab3..c61da1c67aa 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -727,7 +727,7 @@ class MeshBase { return (this->isBoundary(this->getOutgoingHalfEdgeIndex(idx_vertex))); } - /** \brief Check if the given half-edge lies on the bounddary. */ + /** \brief Check if the given half-edge lies on the boundary. */ inline bool isBoundary(const HalfEdgeIndex& idx_he) const { @@ -2167,7 +2167,7 @@ class MeshBase { /** \brief Connectivity information for the faces. */ Faces faces_; - // NOTE: It is MUCH faster to store these variables permamently. + // NOTE: It is MUCH faster to store these variables permanently. /** \brief Storage for addFaceImplBase and deleteFace. */ HalfEdgeIndices inner_he_; diff --git a/gpu/containers/include/pcl/gpu/containers/device_array.h b/gpu/containers/include/pcl/gpu/containers/device_array.h index 74dfcbe8a70..2930172ee9a 100644 --- a/gpu/containers/include/pcl/gpu/containers/device_array.h +++ b/gpu/containers/include/pcl/gpu/containers/device_array.h @@ -100,7 +100,7 @@ class PCL_EXPORTS DeviceArray : public DeviceMemory { copyTo(DeviceArray& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param host_ptr pointer to buffer to upload * \param size elements number * */ @@ -136,7 +136,7 @@ class PCL_EXPORTS DeviceArray : public DeviceMemory { std::size_t num_elements) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param data host vector to upload from * */ template @@ -238,7 +238,7 @@ class PCL_EXPORTS DeviceArray2D : public DeviceMemory2D { copyTo(DeviceArray2D& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param host_ptr pointer to host buffer to upload * \param host_step stride between two consecutive rows in bytes for host buffer * \param rows number of rows to upload @@ -262,7 +262,7 @@ class PCL_EXPORTS DeviceArray2D : public DeviceMemory2D { swap(DeviceArray2D& other_arg); /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param data host vector to upload from * \param cols stride in elements between two consecutive rows for host buffer * */ diff --git a/gpu/containers/include/pcl/gpu/containers/device_memory.h b/gpu/containers/include/pcl/gpu/containers/device_memory.h index 40f120024ed..5b23a652de4 100644 --- a/gpu/containers/include/pcl/gpu/containers/device_memory.h +++ b/gpu/containers/include/pcl/gpu/containers/device_memory.h @@ -97,7 +97,7 @@ class PCL_EXPORTS DeviceMemory { copyTo(DeviceMemory& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param host_ptr_arg pointer to buffer to upload * \param sizeBytes_arg buffer size * */ @@ -230,7 +230,7 @@ class PCL_EXPORTS DeviceMemory2D { copyTo(DeviceMemory2D& other) const; /** \brief Uploads data to internal buffer in GPU memory. It calls create() inside to - * ensure that intenal buffer size is enough. + * ensure that internal buffer size is enough. * \param host_ptr_arg pointer to host buffer to upload * \param host_step_arg stride between two consecutive rows in bytes for host buffer * \param rows_arg number of rows to upload diff --git a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h index 7e24a9acf14..8723245f351 100644 --- a/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h +++ b/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h @@ -121,7 +121,7 @@ namespace pcl void setIcpCorespFilteringParams (float distThreshold, float sineOfAngle); - /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceedes the threshold value. + /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceeds the threshold value. * The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant) * \param[in] threshold a value to compare with the metric. Suitable values are ~0.001 */ @@ -278,7 +278,7 @@ namespace pcl /** \brief Array of camera translations for each moment of time. */ std::vector tvecs_; - /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceedes some value. */ + /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceeds some value. */ float integration_metric_threshold_; /** \brief ICP step is completely disabled. Only integration now. */ diff --git a/gpu/kinfu/src/internal.h b/gpu/kinfu/src/internal.h index daf34652c51..535689f927b 100644 --- a/gpu/kinfu/src/internal.h +++ b/gpu/kinfu/src/internal.h @@ -251,7 +251,7 @@ namespace pcl integrateTsdfVolume (const PtrStepSz& depth_raw, const Intr& intr, const float3& volume_size, const Mat33& Rcurr_inv, const float3& tcurr, float tranc_dist, PtrStep volume, DeviceArray2D& depthRawScaled); - /** \brief Initialzied color volume + /** \brief Initialized color volume * \param[out] color_volume color volume for initialization */ @@ -352,7 +352,7 @@ namespace pcl void extractNormals (const PtrStep& volume, const float3& volume_size, const PtrSz& input, NormalType* output); - /** \brief Performs colors exctraction from color volume + /** \brief Performs colors extraction from color volume * \param[in] color_volume color volume * \param[in] volume_size volume size * \param[in] points points for which color are computed diff --git a/gpu/kinfu/tools/evaluation.h b/gpu/kinfu/tools/evaluation.h index 552a1f588f4..5af84fb5b65 100644 --- a/gpu/kinfu/tools/evaluation.h +++ b/gpu/kinfu/tools/evaluation.h @@ -72,7 +72,7 @@ class Evaluation bool grab (double stamp, pcl::gpu::PtrStepSz& depth); /** \brief Reads depth & rgb frame from the folder. Before calling this folder please call 'setMatchFile', or an error will be returned otherwise. - * \param stamp index of accociated frame pair (stamps are not implemented) + * \param stamp index of associated frame pair (stamps are not implemented) * \param depth * \param rgb24 */ diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 84d05ed2cc4..50e670bbba0 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -567,9 +567,9 @@ struct SceneCloudView switch (extraction_mode_) { - case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break; - case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; - case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; + case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break; + case 1: std::cout << "Cloud extraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; + case 2: std::cout << "Cloud extraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; } ; } @@ -1073,8 +1073,8 @@ struct KinFuApp std::cout << " Esc : exit" << std::endl; std::cout << " T : take cloud" << std::endl; std::cout << " A : take mesh" << std::endl; - std::cout << " M : toggle cloud exctraction mode" << std::endl; - std::cout << " N : toggle normals exctraction" << std::endl; + std::cout << " M : toggle cloud extraction mode" << std::endl; + std::cout << " N : toggle normals extraction" << std::endl; std::cout << " I : toggle independent camera mode" << std::endl; std::cout << " B : toggle volume bounds" << std::endl; std::cout << " * : toggle scene view painting ( requires registration mode )" << std::endl; diff --git a/gpu/kinfu/tools/kinfu_app_sim.cpp b/gpu/kinfu/tools/kinfu_app_sim.cpp index 1591c199846..383ecb83758 100644 --- a/gpu/kinfu/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu/tools/kinfu_app_sim.cpp @@ -807,9 +807,9 @@ struct SceneCloudView switch (extraction_mode_) { - case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break; - case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; - case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; + case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break; + case 1: std::cout << "Cloud extraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; + case 2: std::cout << "Cloud extraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; } ; } @@ -1217,8 +1217,8 @@ struct KinFuApp std::cout << " Esc : exit" << std::endl; std::cout << " T : take cloud" << std::endl; std::cout << " A : take mesh" << std::endl; - std::cout << " M : toggle cloud exctraction mode" << std::endl; - std::cout << " N : toggle normals exctraction" << std::endl; + std::cout << " M : toggle cloud extraction mode" << std::endl; + std::cout << " N : toggle normals extraction" << std::endl; std::cout << " I : toggle independent camera mode" << std::endl; std::cout << " B : toggle volume bounds" << std::endl; std::cout << " * : toggle scene view painting ( requires registration mode )" << std::endl; diff --git a/gpu/kinfu/tools/record_tsdfvolume.cpp b/gpu/kinfu/tools/record_tsdfvolume.cpp index 07878994a8b..dc58cbb55c6 100644 --- a/gpu/kinfu/tools/record_tsdfvolume.cpp +++ b/gpu/kinfu/tools/record_tsdfvolume.cpp @@ -97,7 +97,7 @@ class DeviceVolume /** \brief Creates the TSDF volume on the GPU * param[in] depth depth readings from the sensor - * param[in] intr camaera intrinsics + * param[in] intr camera intrinsics */ void createFromDepth (const pcl::device::PtrStepSz &depth, const pcl::device::Intr &intr); diff --git a/gpu/kinfu/tools/tsdf_volume.h b/gpu/kinfu/tools/tsdf_volume.h index 5b700d6e657..6820749b7d3 100644 --- a/gpu/kinfu/tools/tsdf_volume.h +++ b/gpu/kinfu/tools/tsdf_volume.h @@ -237,7 +237,7 @@ namespace pcl // void // convertToCloud (pcl::PointCloud::Ptr &cloud) const; - /** \brief Crate Volume from Point Cloud */ + /** \brief Create Volume from Point Cloud */ // template void // createFromCloud (const typename pcl::PointCloud::ConstPtr &cloud, const Intr &intr); diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h index 6c8f1f359f5..dd114fd47f7 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h @@ -125,7 +125,7 @@ namespace pcl void setIcpCorespFilteringParams (float distThreshold, float sineOfAngle); - /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceedes the threshold value. + /** \brief Sets integration threshold. TSDF volume is integrated iff a camera movement metric exceeds the threshold value. * The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant) * \param[in] threshold a value to compare with the metric. Suitable values are ~0.001 */ @@ -421,7 +421,7 @@ namespace pcl /** \brief Array of camera translations for each moment of time. */ std::vector tvecs_; - /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceedes some value. */ + /** \brief Camera movement threshold. TSDF is integrated iff a camera movement metric exceeds some value. */ float integration_metric_threshold_; /** \brief When set to true, KinFu will extract the whole world and mesh it. */ diff --git a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp index 745eb56cfc8..7d1accb5bb8 100644 --- a/gpu/kinfu_large_scale/src/cyclical_buffer.cpp +++ b/gpu/kinfu_large_scale/src/cyclical_buffer.cpp @@ -108,7 +108,7 @@ pcl::gpu::kinfuLS::CyclicalBuffer::performShift (const TsdfVolume::Ptr volume, c // Retrieving intensities // TODO change this mechanism by using PointIntensity directly (in spite of float) - // when tried, this lead to wrong intenisty values being extracted by fetchSliceAsCloud () (padding pbls?) + // when tried, this lead to wrong intensity values being extracted by fetchSliceAsCloud () (padding pbls?) std::vector > intensities_vector; intensities.download (intensities_vector); current_slice_intensities->resize (current_slice_xyz->size ()); diff --git a/gpu/kinfu_large_scale/src/internal.h b/gpu/kinfu_large_scale/src/internal.h index b5e5673a59f..c46ffa1c0ea 100644 --- a/gpu/kinfu_large_scale/src/internal.h +++ b/gpu/kinfu_large_scale/src/internal.h @@ -240,7 +240,7 @@ namespace pcl PCL_EXPORTS void clearTSDFSlice (PtrStep volume, pcl::gpu::kinfuLS::tsdf_buffer* buffer, int shiftX, int shiftY, int shiftZ); - /** \brief Initialzied color volume + /** \brief Initialized color volume * \param[out] color_volume color volume for initialization */ void @@ -366,7 +366,7 @@ namespace pcl void extractNormals (const PtrStep& volume, const float3& volume_size, const PtrSz& input, NormalType* output); - /** \brief Performs colors exctraction from color volume + /** \brief Performs colors extraction from color volume * \param[in] color_volume color volume * \param[in] volume_size volume size * \param[in] points points for which color are computed diff --git a/gpu/kinfu_large_scale/tools/evaluation.h b/gpu/kinfu_large_scale/tools/evaluation.h index b4fa69a2703..8b2252a2ccf 100644 --- a/gpu/kinfu_large_scale/tools/evaluation.h +++ b/gpu/kinfu_large_scale/tools/evaluation.h @@ -72,7 +72,7 @@ class Evaluation bool grab (double stamp, pcl::gpu::PtrStepSz& depth); /** \brief Reads depth & rgb frame from the folder. Before calling this folder please call 'setMatchFile', or an error will be returned otherwise. - * \param stamp index of accociated frame pair (stamps are not implemented) + * \param stamp index of associated frame pair (stamps are not implemented) * \param depth * \param rgb24 */ diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index d96b6171de3..a7f58b04f9b 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -1143,8 +1143,8 @@ struct KinFuLSApp std::cout << " Esc : exit" << std::endl; std::cout << " T : take cloud" << std::endl; std::cout << " A : take mesh" << std::endl; - std::cout << " M : toggle cloud exctraction mode" << std::endl; - std::cout << " N : toggle normals exctraction" << std::endl; + std::cout << " M : toggle cloud extraction mode" << std::endl; + std::cout << " N : toggle normals extraction" << std::endl; std::cout << " I : toggle independent camera mode" << std::endl; std::cout << " B : toggle volume bounds" << std::endl; std::cout << " * : toggle scene view painting ( requires registration mode )" << std::endl; diff --git a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp index c333b269941..b1ff4f56b99 100644 --- a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp @@ -801,9 +801,9 @@ struct SceneCloudView switch (extraction_mode_) { - case 0: std::cout << "Cloud exctraction mode: GPU, Connected-6" << std::endl; break; - case 1: std::cout << "Cloud exctraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; - case 2: std::cout << "Cloud exctraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; + case 0: std::cout << "Cloud extraction mode: GPU, Connected-6" << std::endl; break; + case 1: std::cout << "Cloud extraction mode: CPU, Connected-6 (requires a lot of memory)" << std::endl; break; + case 2: std::cout << "Cloud extraction mode: CPU, Connected-26 (requires a lot of memory)" << std::endl; break; } ; } @@ -1240,8 +1240,8 @@ struct KinFuApp std::cout << " Esc : exit" << std::endl; std::cout << " T : take cloud" << std::endl; std::cout << " A : take mesh" << std::endl; - std::cout << " M : toggle cloud exctraction mode" << std::endl; - std::cout << " N : toggle normals exctraction" << std::endl; + std::cout << " M : toggle cloud extraction mode" << std::endl; + std::cout << " N : toggle normals extraction" << std::endl; std::cout << " I : toggle independent camera mode" << std::endl; std::cout << " B : toggle volume bounds" << std::endl; std::cout << " * : toggle scene view painting ( requires registration mode )" << std::endl; diff --git a/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp b/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp index 0620a84ca7f..ec9263cc0fd 100644 --- a/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp +++ b/gpu/kinfu_large_scale/tools/process_kinfu_large_scale_output.cpp @@ -90,7 +90,7 @@ main (int argc, char** argv) std::vector > transforms; //Get world as a vector of cubes - wm.getWorldAsCubes (pcl::device::kinfuLS::VOLUME_X, clouds, transforms, 0.025); // 2.5% overlapp (12 cells with a 512-wide cube) + wm.getWorldAsCubes (pcl::device::kinfuLS::VOLUME_X, clouds, transforms, 0.025); // 2.5% overlap (12 cells with a 512-wide cube) //Creating the standalone marching cubes instance float volume_size = pcl::device::kinfuLS::VOLUME_SIZE; diff --git a/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp b/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp index 483c38c9195..08508a687fa 100644 --- a/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp +++ b/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp @@ -254,7 +254,7 @@ grabberMapsCallBack(const openni_wrapper::Image::Ptr& image_wrapper, const openn ////////////////////////////////////////////////////////////////////////////////////////// -// Procuder thread function +// Producer thread function void grabAndSend () { diff --git a/gpu/kinfu_large_scale/tools/record_tsdfvolume.cpp b/gpu/kinfu_large_scale/tools/record_tsdfvolume.cpp index b88550a8551..575108a4ebd 100644 --- a/gpu/kinfu_large_scale/tools/record_tsdfvolume.cpp +++ b/gpu/kinfu_large_scale/tools/record_tsdfvolume.cpp @@ -95,7 +95,7 @@ class DeviceVolume /** \brief Creates the TSDF volume on the GPU * param[in] depth depth readings from the sensor - * param[in] intr camaera intrinsics + * param[in] intr camera intrinsics */ void createFromDepth (const pcl::device::PtrStepSz &depth, const pcl::device::Intr &intr); diff --git a/gpu/octree/include/pcl/gpu/octree/octree.hpp b/gpu/octree/include/pcl/gpu/octree/octree.hpp index 9f645f348e8..015f9ff95a4 100644 --- a/gpu/octree/include/pcl/gpu/octree/octree.hpp +++ b/gpu/octree/include/pcl/gpu/octree/octree.hpp @@ -51,7 +51,7 @@ namespace pcl namespace gpu { /** - * \brief Octree implementation on GPU. It suppors parallel building and parallel batch search as well . + * \brief Octree implementation on GPU. It supports parallel building and parallel batch search as well . * \author Anaoly Baksheev, Itseez, myname.mysurname@mycompany.com */ diff --git a/gpu/people/src/bodyparts_detector.cpp b/gpu/people/src/bodyparts_detector.cpp index 8d0eb888b14..3cf271bcbbd 100644 --- a/gpu/people/src/bodyparts_detector.cpp +++ b/gpu/people/src/bodyparts_detector.cpp @@ -188,7 +188,7 @@ pcl::gpu::people::RDFBodyPartsDetector::process (const pcl::device::Depth& depth labels_smoothed_.download(lmap_host_, c); //async_labels_download.download(labels_smoothed_); - // cc = generalized floodfill = approximation of euclidian clusterisation + // cc = generalized floodfill = approximation of euclidean clusterisation device::ConnectedComponents::computeEdges(labels_smoothed_, depth, NUM_PARTS, cluster_tolerance_ * cluster_tolerance_, edges_); device::ConnectedComponents::labelComponents(edges_, comps_); @@ -283,7 +283,7 @@ pcl::gpu::people::RDFBodyPartsDetector::processSmooth (const pcl::device::Depth& labels_smoothed_.download(lmap_host_, c); //async_labels_download.download(labels_smoothed_); - // cc = generalized floodfill = approximation of euclidian clusterisation + // cc = generalized floodfill = approximation of euclidean clusterisation device::ConnectedComponents::computeEdges(labels_smoothed_, depth, NUM_PARTS, cluster_tolerance_ * cluster_tolerance_, edges_); device::ConnectedComponents::labelComponents(edges_, comps_); diff --git a/gpu/people/src/cuda/elec.cu b/gpu/people/src/cuda/elec.cu index e11beb8f5b5..0cacdf9f0e1 100644 --- a/gpu/people/src/cuda/elec.cu +++ b/gpu/people/src/cuda/elec.cu @@ -294,7 +294,7 @@ namespace pcl int old_label = old_labels[i][j]; int new_label = new_labels[i][j]; - //if there is a neigboring element with a smaller label, update the equivalence tree of the processed element + //if there is a neighboring element with a smaller label, update the equivalence tree of the processed element //(the tree is always flattened in this stage so there is no need to use findRoot to find the root) if (new_label < old_label) { diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index acf452edd02..fe6f3fefa64 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -373,7 +373,7 @@ int main(int argc, char** argv) if(pc::find_switch (argc, argv, "--help") || pc::find_switch (argc, argv, "-h")) return print_help(), 0; - // selecting GPU and prining info + // selecting GPU and printing info int device = 0; pc::parse_argument (argc, argv, "-gpu", device); pcl::gpu::setDevice (device); 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 afa34b2363f..47b44568a82 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 @@ -121,7 +121,7 @@ class SeededHueSegmentation { host_cloud_ = host_cloud; } - /** \brief Set the tollerance on the hue + /** \brief Set the tolerance on the hue * \param[in] delta_hue the new delta hue */ inline void diff --git a/io/include/pcl/compression/impl/entropy_range_coder.hpp b/io/include/pcl/compression/impl/entropy_range_coder.hpp index 83218ead926..610f5adc5aa 100644 --- a/io/include/pcl/compression/impl/entropy_range_coder.hpp +++ b/io/include/pcl/compression/impl/entropy_range_coder.hpp @@ -313,7 +313,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input while (readPos < input_size) { - // read symol + // read symbol unsigned int inputsymbol = inputIntVector_arg[readPos++]; // map to range @@ -501,7 +501,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector& inputB // start encoding while (readPos < input_size) { - // read symol + // read symbol std::uint8_t ch = inputByteVector_arg[readPos++]; // map to range diff --git a/io/include/pcl/io/io_exception.h b/io/include/pcl/io/io_exception.h index 50dbbb22b6a..156f32d4723 100644 --- a/io/include/pcl/io/io_exception.h +++ b/io/include/pcl/io/io_exception.h @@ -43,7 +43,7 @@ #include -//fom +//from #if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__ #define __PRETTY_FUNCTION__ __FUNCTION__ #endif diff --git a/io/include/pcl/io/openni_camera/openni_device.h b/io/include/pcl/io/openni_camera/openni_device.h index fcc8d733995..7115de514c0 100644 --- a/io/include/pcl/io/openni_camera/openni_device.h +++ b/io/include/pcl/io/openni_camera/openni_device.h @@ -101,7 +101,7 @@ namespace openni_wrapper findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (); /** \brief finds a depth output mode that can be used to retrieve depth images in desired output mode. - * e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possbile by downsampling, + * e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possible by downsampling, * but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible. * \param[in] output_mode the desired output mode * \param[out] mode the compatible mode that the device natively supports. diff --git a/io/include/pcl/io/openni_camera/openni_exception.h b/io/include/pcl/io/openni_camera/openni_exception.h index 37c56a0d949..e0e3789ebf1 100644 --- a/io/include/pcl/io/openni_camera/openni_exception.h +++ b/io/include/pcl/io/openni_camera/openni_exception.h @@ -46,7 +46,7 @@ //#include <-- because current header is included in NVCC-compiled code and contains . Consider -//fom +//from #if defined _WIN32 && defined _MSC_VER && !defined __PRETTY_FUNCTION__ #define __PRETTY_FUNCTION__ __FUNCTION__ #endif diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index 7b825ab9179..c10c525e111 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -204,7 +204,7 @@ namespace pcl * \param[out] cloud the resultant point cloud dataset to be filled. * \param[in] pcd_version the PCD version of the stream (from readHeader()). * \param[in] compressed indicates whether the PCD block contains compressed - * data. This should be true if the data_type returne by readHeader() == 2. + * data. This should be true if the data_type returned by readHeader() == 2. * \param[in] data_idx the offset of the body, as reported by readHeader(). * * \return diff --git a/io/include/pcl/io/split.h b/io/include/pcl/io/split.h index 9a28c90e34d..ec59640a4e4 100644 --- a/io/include/pcl/io/split.h +++ b/io/include/pcl/io/split.h @@ -14,7 +14,7 @@ namespace pcl { /** \brief Lightweight tokenization function * This function can be used as a boost::split substitute. When benchmarked against - * boost, this function will create much less alocations and hence it is much better + * boost, this function will create much less allocations and hence it is much better * suited for quick line tokenization. * * Cool thing is this function will work with SequenceSequenceT = diff --git a/io/include/pcl/io/tim_grabber.h b/io/include/pcl/io/tim_grabber.h index 654d4ca60fc..786e501b967 100644 --- a/io/include/pcl/io/tim_grabber.h +++ b/io/include/pcl/io/tim_grabber.h @@ -25,7 +25,7 @@ namespace pcl { -//// note: Protcol named CoLaA (used by SICK) has some information. +//// note: Protocol named CoLaA (used by SICK) has some information. //// In this Grabber, only the amount_of_data is used, so other information is truncated. //// Details of the protocol can be found at the following URL. diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 81598a3c943..1bdbbe3b047 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -380,7 +380,7 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c continue; // Trim the line - //TOOD: we can easily do this without boost + //TODO: we can easily do this without boost boost::trim (line); // Ignore comments diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index 2347b4f886e..ffa91d3e8b7 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -221,7 +221,7 @@ openni_wrapper::OpenNIDriver::stopAll () openni_wrapper::OpenNIDriver::~OpenNIDriver () noexcept { - // no exception during destuctor + // no exception during destructor try { stopAll (); diff --git a/io/tools/convert_pcd_ascii_binary.cpp b/io/tools/convert_pcd_ascii_binary.cpp index 641e373e5dc..d2f79182975 100644 --- a/io/tools/convert_pcd_ascii_binary.cpp +++ b/io/tools/convert_pcd_ascii_binary.cpp @@ -39,7 +39,7 @@ \author Radu Bogdan Rusu -@b convert_pcd_ascii_binary converts PCD (Point Cloud Data) files from ascii to binary and viceversa. +@b convert_pcd_ascii_binary converts PCD (Point Cloud Data) files from ascii to binary and vice-versa. **/ diff --git a/keypoints/include/pcl/keypoints/agast_2d.h b/keypoints/include/pcl/keypoints/agast_2d.h index 6089e705f34..e9e139fd048 100644 --- a/keypoints/include/pcl/keypoints/agast_2d.h +++ b/keypoints/include/pcl/keypoints/agast_2d.h @@ -106,7 +106,7 @@ namespace pcl /** \brief Applies non-max-suppression. * \param[in] intensity_data the image data * \param[in] input the keypoint positions - * \param[out] output the resultant keypoints after non-max-supression + * \param[out] output the resultant keypoints after non-max-suppression */ void applyNonMaxSuppression (const std::vector& intensity_data, @@ -116,7 +116,7 @@ namespace pcl /** \brief Applies non-max-suppression. * \param[in] intensity_data the image data * \param[in] input the keypoint positions - * \param[out] output the resultant keypoints after non-max-supression + * \param[out] output the resultant keypoints after non-max-suppression */ void applyNonMaxSuppression (const std::vector& intensity_data, @@ -213,7 +213,7 @@ namespace pcl /** \brief Non-max-suppression helper method. * \param[in] input the keypoint positions * \param[in] scores the keypoint scores computed on the image data - * \param[out] output the resultant keypoints after non-max-supression + * \param[out] output the resultant keypoints after non-max-suppression */ void applyNonMaxSuppression (const pcl::PointCloud &input, diff --git a/keypoints/include/pcl/keypoints/harris_2d.h b/keypoints/include/pcl/keypoints/harris_2d.h index 2754e858ec1..5305d4f0eaf 100644 --- a/keypoints/include/pcl/keypoints/harris_2d.h +++ b/keypoints/include/pcl/keypoints/harris_2d.h @@ -121,7 +121,7 @@ namespace pcl /** \brief whether the detected key points should be refined or not. If turned of, the key points are a subset of * the original point cloud. Otherwise the key points may be arbitrary. - * \brief note non maxima supression needs to be on in order to use this feature. + * \brief note non maxima suppression needs to be on in order to use this feature. * \param[in] do_refine */ void setRefine (bool do_refine); diff --git a/keypoints/include/pcl/keypoints/harris_3d.h b/keypoints/include/pcl/keypoints/harris_3d.h index d6a3bf56c77..88f8e637155 100644 --- a/keypoints/include/pcl/keypoints/harris_3d.h +++ b/keypoints/include/pcl/keypoints/harris_3d.h @@ -108,7 +108,7 @@ namespace pcl void setMethod (ResponseMethod type); - /** \brief Set the radius for normal estimation and non maxima supression. + /** \brief Set the radius for normal estimation and non maxima suppression. * \param[in] radius */ void @@ -129,7 +129,7 @@ namespace pcl setNonMaxSupression (bool = false); /** \brief Whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary. - * \brief note non maxima supression needs to be on in order to use this feature. + * \brief note non maxima suppression needs to be on in order to use this feature. * \param[in] do_refine */ void diff --git a/keypoints/include/pcl/keypoints/harris_6d.h b/keypoints/include/pcl/keypoints/harris_6d.h index 91ba241a8a2..e2ba39535f4 100644 --- a/keypoints/include/pcl/keypoints/harris_6d.h +++ b/keypoints/include/pcl/keypoints/harris_6d.h @@ -88,7 +88,7 @@ namespace pcl virtual ~HarrisKeypoint6D () = default; /** - * @brief set the radius for normal estimation and non maxima supression. + * @brief set the radius for normal estimation and non maxima suppression. * @param radius */ void setRadius (float radius); @@ -109,7 +109,7 @@ namespace pcl /** * @brief whether the detected key points should be refined or not. If turned of, the key points are a subset of the original point cloud. Otherwise the key points may be arbitrary. - * @brief note non maxima supression needs to be on in order to use this feature. + * @brief note non maxima suppression needs to be on in order to use this feature. * @param do_refine */ void setRefine (bool do_refine); diff --git a/keypoints/include/pcl/keypoints/iss_3d.h b/keypoints/include/pcl/keypoints/iss_3d.h index 2a686907df8..24ebdbbddda 100644 --- a/keypoints/include/pcl/keypoints/iss_3d.h +++ b/keypoints/include/pcl/keypoints/iss_3d.h @@ -141,7 +141,7 @@ namespace pcl void setSalientRadius (double salient_radius); - /** \brief Set the radius for the application of the non maxima supression algorithm. + /** \brief Set the radius for the application of the non maxima suppression algorithm. * \param[in] non_max_radius the non maxima suppression radius */ void diff --git a/keypoints/include/pcl/keypoints/trajkovic_2d.h b/keypoints/include/pcl/keypoints/trajkovic_2d.h index 355cdf537a5..7434f16a052 100644 --- a/keypoints/include/pcl/keypoints/trajkovic_2d.h +++ b/keypoints/include/pcl/keypoints/trajkovic_2d.h @@ -43,7 +43,7 @@ namespace pcl { /** \brief TrajkovicKeypoint2D implements Trajkovic and Hedley corner detector on - * organized pooint cloud using intensity information. + * organized point cloud using intensity information. * It uses first order statistics to find variation of intensities in horizontal * or vertical directions. * diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index da466453f93..35daf09357d 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -632,7 +632,7 @@ NarfKeypoint::calculateSparseInterestImage () relevent_point_indices.resize(newPointIdx); } - // Caclulate interest values for neighbors + // Calculate interest values for neighbors for (const int &index2 : neighbors_within_radius_overhead) { int y2 = index2/range_image.width, diff --git a/ml/include/pcl/ml/dt/decision_tree_trainer.h b/ml/include/pcl/ml/dt/decision_tree_trainer.h index 3920182af96..35650887cf3 100644 --- a/ml/include/pcl/ml/dt/decision_tree_trainer.h +++ b/ml/include/pcl/ml/dt/decision_tree_trainer.h @@ -215,7 +215,7 @@ class PCL_EXPORTS DecisionTreeTrainer { std::size_t max_depth, NodeType& node); - /** Creates uniformely distrebuted thresholds over the range of the supplied + /** Creates uniformly distributed thresholds over the range of the supplied * values. * * \param[in] num_of_thresholds the number of thresholds to create diff --git a/ml/include/pcl/ml/ferns/fern_trainer.h b/ml/include/pcl/ml/ferns/fern_trainer.h index 8657c2cd309..4c9b35dc569 100644 --- a/ml/include/pcl/ml/ferns/fern_trainer.h +++ b/ml/include/pcl/ml/ferns/fern_trainer.h @@ -149,7 +149,7 @@ class PCL_EXPORTS FernTrainer { train(Fern& fern); protected: - /** Creates uniformely distrebuted thresholds over the range of the supplied + /** Creates uniformly distributed thresholds over the range of the supplied * values. * * \param[in] num_of_thresholds the number of thresholds to create diff --git a/ml/include/pcl/ml/permutohedral.h b/ml/include/pcl/ml/permutohedral.h index 5f4017e2c25..d1ec89a702e 100644 --- a/ml/include/pcl/ml/permutohedral.h +++ b/ml/include/pcl/ml/permutohedral.h @@ -102,7 +102,7 @@ class Permutohedral { void debug(); - /** Pseudo radnom generator. */ + /** Pseudo random generator. */ inline std::size_t generateHashKey(const std::vector& k) { diff --git a/ml/include/pcl/ml/stats_estimator.h b/ml/include/pcl/ml/stats_estimator.h index 72424be49bc..f42cc3c9300 100644 --- a/ml/include/pcl/ml/stats_estimator.h +++ b/ml/include/pcl/ml/stats_estimator.h @@ -52,7 +52,7 @@ class PCL_EXPORTS StatsEstimator { /** Destructor. */ virtual ~StatsEstimator() = default; - /** Returns the number of brances a node can have (e.g. a binary tree has 2). */ + /** Returns the number of branches a node can have (e.g. a binary tree has 2). */ virtual std::size_t getNumOfBranches() const = 0; diff --git a/ml/include/pcl/ml/svm_wrapper.h b/ml/include/pcl/ml/svm_wrapper.h index 00eab956b2d..441185d2b31 100644 --- a/ml/include/pcl/ml/svm_wrapper.h +++ b/ml/include/pcl/ml/svm_wrapper.h @@ -499,7 +499,7 @@ class SVMClassify : public SVM { /** Read in a normalized classification problem (in svmlight format). * - * The data are kept whitout normalizing. + * The data is kept without normalizing. * * \return false if fails */ diff --git a/ml/src/permutohedral.cpp b/ml/src/permutohedral.cpp index fed0447c348..f6609b1c6f9 100644 --- a/ml/src/permutohedral.cpp +++ b/ml/src/permutohedral.cpp @@ -106,7 +106,7 @@ pcl::Permutohedral::init(const std::vector& feature, // Elevate the feature (y = Ep, see p.5 in [Adams etal 2010]) int index = k * feature_dimension; - // sm contains the sum of 1..n of our faeture vector + // sm contains the sum of 1..n of our feature vector float sm = 0; for (int j = d_; j > 0; j--) { float cf = feature[index + j - 1] * scale_factor(j - 1); @@ -367,7 +367,7 @@ pcl::Permutohedral::initOLD(const std::vector& feature, // const float * f = feature + k*feature_size; int index = k * feature_dimension; - // sm contains the sum of 1..n of our faeture vector + // sm contains the sum of 1..n of our feature vector float sm = 0; for (int j = d_; j > 0; j--) { // float cf = f[j-1]*scale_factor[j-1]; @@ -388,7 +388,7 @@ pcl::Permutohedral::initOLD(const std::vector& feature, } // Find the simplex we are in and store it in rank (where rank describes what - // position coorinate i has in the sorted order of the features values) + // position coordinate i has in the sorted order of the features values) for (int i = 0; i <= d_; i++) rank[i] = 0; for (int i = 0; i < d_; i++) { diff --git a/ml/src/svm.cpp b/ml/src/svm.cpp index 072337f9ce6..77280277e3f 100644 --- a/ml/src/svm.cpp +++ b/ml/src/svm.cpp @@ -971,7 +971,7 @@ Solver::select_working_set(int& out_i, int& out_j) // return i,j such that // i: maximizes -y_i * grad(f)_i, i in I_up(\alpha) // j: minimizes the decrease of obj value - // (if quadratic coefficeint <= 0, replace it with tau) + // (if quadratic coefficient <= 0, replace it with tau) // -y_j*grad(f)_j < -y_i*grad(f)_i, j in I_low(\alpha) double Gmax = -INF; @@ -1215,7 +1215,7 @@ Solver_NU::select_working_set(int& out_i, int& out_j) // return i,j such that y_i = y_j and // i: maximizes -y_i * grad(f)_i, i in I_up(\alpha) // j: minimizes the decrease of obj value - // (if quadratic coefficeint <= 0, replace it with tau) + // (if quadratic coefficient <= 0, replace it with tau) // -y_j*grad(f)_j < -y_i*grad(f)_i, j in I_low(\alpha) double Gmaxp = -INF; diff --git a/ml/src/svm_wrapper.cpp b/ml/src/svm_wrapper.cpp index cbde3caba15..b85b82341df 100644 --- a/ml/src/svm_wrapper.cpp +++ b/ml/src/svm_wrapper.cpp @@ -552,7 +552,7 @@ pcl::SVMClassify::classificationTest() if (predict_probability_) { if (svm_check_probability_model(&model_) == 0) { PCL_WARN("[pcl::%s::classificationTest] Classifier model does not support " - "probabiliy estimates. Automatically disabled.\n", + "probability estimates. Automatically disabled.\n", getClassName().c_str()); predict_probability_ = false; } @@ -667,9 +667,10 @@ pcl::SVMClassify::classification() if (predict_probability_) { if (svm_check_probability_model(&model_) == 0) { - PCL_WARN("[pcl::%s::classification] Classifier model does not support probabiliy " - "estimates. Automatically disabled.\n", - getClassName().c_str()); + PCL_WARN( + "[pcl::%s::classification] Classifier model does not support probability " + "estimates. Automatically disabled.\n", + getClassName().c_str()); predict_probability_ = false; } } @@ -748,9 +749,10 @@ pcl::SVMClassify::classification(pcl::SVMData in) if (predict_probability_) { if (svm_check_probability_model(&model_) == 0) { - PCL_WARN("[pcl::%s::classification] Classifier model does not support probabiliy " - "estimates. Automatically disabled.\n", - getClassName().c_str()); + PCL_WARN( + "[pcl::%s::classification] Classifier model does not support probability " + "estimates. Automatically disabled.\n", + getClassName().c_str()); predict_probability_ = false; } } diff --git a/octree/include/pcl/octree/octree2buf_base.h b/octree/include/pcl/octree/octree2buf_base.h index 88577e36e23..df5db780562 100644 --- a/octree/include/pcl/octree/octree2buf_base.h +++ b/octree/include/pcl/octree/octree2buf_base.h @@ -258,7 +258,7 @@ class Octree2BufBase { using LeafNodeIterator = OctreeLeafNodeDepthFirstIterator; using ConstLeafNodeIterator = const OctreeLeafNodeDepthFirstIterator; - // The currently valide names + // The currently valid names using LeafNodeDepthFirstIterator = OctreeLeafNodeDepthFirstIterator; using ConstLeafNodeDepthFirstIterator = const OctreeLeafNodeDepthFirstIterator; diff --git a/octree/include/pcl/octree/octree_search.h b/octree/include/pcl/octree/octree_search.h index cff49c39cc8..a0bc8c6d891 100644 --- a/octree/include/pcl/octree/octree_search.h +++ b/octree/include/pcl/octree/octree_search.h @@ -403,7 +403,7 @@ class OctreePointCloudSearch * \param[in] key octree key addressing a leaf node. * \param[in] tree_depth current depth/level in the octree * \param[in] squared_search_radius squared search radius distance - * \param[out] point_candidates priority queue of nearest neigbor point candidates + * \param[out] point_candidates priority queue of nearest neighbor point candidates * \return squared search radius based on current point candidate set found */ double diff --git a/outofcore/include/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp b/outofcore/include/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp index a726b9ff6ab..6fbc4ed0708 100644 --- a/outofcore/include/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp +++ b/outofcore/include/pcl/outofcore/impl/outofcore_breadth_first_iterator.hpp @@ -106,7 +106,7 @@ namespace pcl //////////////////////////////////////////////////////////////////////////////// - }//namesapce pcl + }//namespace pcl }//namespace outofcore #endif //PCL_OUTOFCORE_BREADTH_FIRST_ITERATOR_IMPL_H_ diff --git a/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp b/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp index 18fa677ed8c..82d88c1a0bd 100644 --- a/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp +++ b/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp @@ -142,7 +142,7 @@ namespace pcl //////////////////////////////////////////////////////////////////////////////// - }//namesapce pcl + }//namespace pcl }//namespace outofcore #endif //PCL_OUTOFCORE_DEPTH_FIRST_ITERATOR_IMPL_H_ diff --git a/outofcore/include/pcl/outofcore/octree_base_node.h b/outofcore/include/pcl/outofcore/octree_base_node.h index fd447bbb0e6..7085d530227 100644 --- a/outofcore/include/pcl/outofcore/octree_base_node.h +++ b/outofcore/include/pcl/outofcore/octree_base_node.h @@ -281,7 +281,7 @@ namespace pcl return (res); } - /** \brief Count loaded chilren */ + /** \brief Count loaded children */ virtual std::size_t getNumLoadedChildren () const { @@ -346,8 +346,8 @@ namespace pcl virtual std::size_t countNumChildren () const; - /** \brief Counts the number of loaded chilren by testing the \c children_ array; - * used to update num_loaded_chilren_ internally + /** \brief Counts the number of loaded children by testing the \c children_ array; + * used to update num_loaded_children_ internally */ virtual std::size_t countNumLoadedChildren () const; diff --git a/recognition/include/pcl/recognition/crh_alignment.h b/recognition/include/pcl/recognition/crh_alignment.h index 74ff8f55ec2..a8853e6f57d 100644 --- a/recognition/include/pcl/recognition/crh_alignment.h +++ b/recognition/include/pcl/recognition/crh_alignment.h @@ -64,7 +64,7 @@ namespace pcl /** \brief computes the transformation to the z-axis * \param[in] centroid - * \param[out] trasnformation to z-axis + * \param[out] transformation to z-axis */ void computeTransformToZAxes (Eigen::Vector3f & centroid, Eigen::Affine3f & transform) diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h index 4fc967e484a..bd0d0785603 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_utils.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_utils.h @@ -387,7 +387,7 @@ namespace pcl } } - //compute covariance from offsets and angles for all branchs + //compute covariance from offsets and angles for all branches std::vector < Eigen::Matrix3d > offset_covariances; std::vector < Eigen::Matrix3d > angle_covariances; diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index 5d57ab7f631..652200dd596 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -96,10 +96,10 @@ namespace pcl getColoredCloud (typename pcl::PointCloud::Ptr cloud = 0); /** \brief This method finds the strongest peaks (points were density has most higher values). - * It is based on the non maxima supression principles. + * It is based on the non maxima suppression principles. * \param[out] out_peaks it will contain the strongest peaks * \param[in] in_class_id class of interest for which peaks are evaluated - * \param[in] in_non_maxima_radius non maxima supression radius. The shapes radius is recommended for this value. + * \param[in] in_non_maxima_radius non maxima suppression radius. The shapes radius is recommended for this value. * \param in_sigma */ void @@ -150,7 +150,7 @@ namespace pcl }; /** \brief The assignment of this structure is to store the statistical/learned weights and other information - * of the trained Implict Shape Model algorithm. + * of the trained Implicit Shape Model algorithm. */ struct PCL_EXPORTS ISMModel { diff --git a/registration/include/pcl/registration/correspondence_rejection.h b/registration/include/pcl/registration/correspondence_rejection.h index 75e9957a74c..df388ac784a 100644 --- a/registration/include/pcl/registration/correspondence_rejection.h +++ b/registration/include/pcl/registration/correspondence_rejection.h @@ -396,7 +396,7 @@ class DataContainer : public DataContainerInterface { /** \brief The input transformed point cloud dataset */ PointCloudPtr input_transformed_; - /** \brief The target point cloud datase. */ + /** \brief The target point cloud dataset. */ PointCloudConstPtr target_; /** \brief Normals to the input point cloud */ diff --git a/registration/include/pcl/registration/ia_fpcs.h b/registration/include/pcl/registration/ia_fpcs.h index 788dfd0d9e3..220a58b6b20 100644 --- a/registration/include/pcl/registration/ia_fpcs.h +++ b/registration/include/pcl/registration/ia_fpcs.h @@ -327,7 +327,7 @@ class FPCSInitialAlignment : public Registration(indices_->size()); @@ -397,7 +397,7 @@ pcl::registration::FPCSInitialAlignment::max()) { - // order points to build largest quadrangle and calcuate intersection ratios of + // order points to build largest quadrangle and calculate intersection ratios of // diagonals setupBase(base_indices, ratio); return (0); @@ -834,7 +834,7 @@ pcl::registration::FPCSInitialAlignment::initCompute() pcl::registration::FPCSInitialAlignment:: initCompute(); - // set the threshold values with respect to keypoint charactersitics + // set the threshold values with respect to keypoint characteristics max_pair_diff_ = delta_ * 1.414f; // diff between 2 points of delta_ accuracy coincidation_limit_ = delta_ * 2.828f; // diff between diff of 2 points max_edge_diff_ = diff --git a/registration/include/pcl/registration/impl/icp.hpp b/registration/include/pcl/registration/impl/icp.hpp index e4cbac64cd8..583c8bc117e 100644 --- a/registration/include/pcl/registration/impl/icp.hpp +++ b/registration/include/pcl/registration/impl/icp.hpp @@ -225,7 +225,7 @@ IterativeClosestPoint::computeTransformation( ++nr_iterations_; - // Update the vizualization of icp convergence + // Update the visualization of icp convergence if (update_visualizer_ != nullptr) { pcl::Indices source_indices_good, target_indices_good; for (const Correspondence& corr : *correspondences_) { diff --git a/registration/include/pcl/registration/impl/joint_icp.hpp b/registration/include/pcl/registration/impl/joint_icp.hpp index 0ed47185f4c..b1ac2ceda1f 100644 --- a/registration/include/pcl/registration/impl/joint_icp.hpp +++ b/registration/include/pcl/registration/impl/joint_icp.hpp @@ -244,7 +244,7 @@ JointIterativeClosestPoint::computeTransformat ++nr_iterations_; - // Update the vizualization of icp convergence + // Update the visualization of icp convergence // if (update_visualizer_ != 0) // update_visualizer_(output, source_indices_good, *target_, target_indices_good ); diff --git a/registration/include/pcl/registration/impl/ndt.hpp b/registration/include/pcl/registration/impl/ndt.hpp index 67033c8f78b..7bba7522f43 100644 --- a/registration/include/pcl/registration/impl/ndt.hpp +++ b/registration/include/pcl/registration/impl/ndt.hpp @@ -684,7 +684,7 @@ NormalDistributionsTransform::computeStepLengt const int max_step_iterations = 10; int step_iterations = 0; - // Sufficient decreace constant, Equation 1.1 [More, Thuete 1994] + // Sufficient decrease constant, Equation 1.1 [More, Thuete 1994] const double mu = 1.e-4; // Curvature condition constant, Equation 1.2 [More, Thuete 1994] const double nu = 0.9; @@ -718,7 +718,7 @@ NormalDistributionsTransform::computeStepLengt // Updates score, gradient and hessian. Hessian calculation is unnecessary but // testing showed that most step calculations use the initial step suggestion and - // recalculation the reusable portions of the hessian would intail more computation + // recalculation the reusable portions of the hessian would entail more computation // time. score = computeDerivatives(score_gradient, hessian, trans_cloud, x_t, true); @@ -732,7 +732,7 @@ NormalDistributionsTransform::computeStepLengt // Calculate psi'(alpha_t) double d_psi_t = auxilaryFunction_dPsiMT(d_phi_t, d_phi_0, mu); - // Iterate until max number of iterations, interval convergance or a value satisfies + // Iterate until max number of iterations, interval convergence or a value satisfies // the sufficient decrease, Equation 1.1, and curvature condition, Equation 1.2 [More, // Thuente 1994] while (!interval_converged && step_iterations < max_step_iterations && diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index dad439e3d6c..478fa0b22aa 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -404,7 +404,7 @@ class NormalDistributionsTransform * Thuente 1994) and \f$ \delta \vec{p} \f$ normalized in Algorithm 2 * [Magnusson 2009] * \param[in] step_init initial step length estimate, \f$ \alpha_0 \f$ in - * Moore-Thuente (1994) and the noramal of \f$ \delta \vec{p} \f$ in Algorithm + * Moore-Thuente (1994) and the normal of \f$ \delta \vec{p} \f$ in Algorithm * 2 [Magnusson 2009] * \param[in] step_max maximum step length, \f$ \alpha_max \f$ in * Moore-Thuente (1994) diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp index a85b9bb3add..247a58e3d1f 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp @@ -223,7 +223,7 @@ pcl::SampleConsensusModelEllipse3D::computeModelCoefficients (const Indi model_coefficients[6] = static_cast(ellipse_normal[1]); model_coefficients[7] = static_cast(ellipse_normal[2]); - // Retrive the ellipse point at the tilt angle t (par_t), along the local x-axis + // Retrieve the ellipse point at the tilt angle t (par_t), along the local x-axis const Eigen::VectorXf params = (Eigen::VectorXf(5) << par_a, par_b, par_h, par_k, par_t).finished(); Eigen::Vector3f p_th_(0.0, 0.0, 0.0); get_ellipse_point(params, par_t, p_th_(0), p_th_(1)); @@ -551,7 +551,7 @@ pcl::SampleConsensusModelEllipse3D::projectPoints ( float th_opt; dvec2ellipse(params, p_(0), p_(1), th_opt); - // Retrive the ellipse point at the tilt angle t, along the local x-axis + // Retrieve the ellipse point at the tilt angle t, along the local x-axis Eigen::Vector3f k_(0.0, 0.0, 0.0); get_ellipse_point(params, th_opt, k_[0], k_[1]); @@ -613,7 +613,7 @@ pcl::SampleConsensusModelEllipse3D::projectPoints ( float th_opt; dvec2ellipse(params, p_(0), p_(1), th_opt); - // Retrive the ellipse point at the tilt angle t, along the local x-axis + // Retrieve the ellipse point at the tilt angle t, along the local x-axis //// model_coefficients[5] = static_cast(par_t); Eigen::Vector3f k_(0.0, 0.0, 0.0); get_ellipse_point(params, th_opt, k_[0], k_[1]); diff --git a/search/include/pcl/search/organized.h b/search/include/pcl/search/organized.h index 138759f0bfd..cbf15566976 100644 --- a/search/include/pcl/search/organized.h +++ b/search/include/pcl/search/organized.h @@ -52,7 +52,7 @@ namespace pcl { namespace search { - /** \brief OrganizedNeighbor is a class for optimized nearest neigbhor search in organized point clouds. + /** \brief OrganizedNeighbor is a class for optimized nearest neighbor search in organized point clouds. * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys * \ingroup search */ diff --git a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h index 300fb20f073..67592875996 100644 --- a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h @@ -48,7 +48,7 @@ namespace pcl { - /** \brief EuclideanClusterComparator is a comparator used for finding clusters based on euclidian distance. + /** \brief EuclideanClusterComparator is a comparator used for finding clusters based on euclidean distance. * * \author Alex Trevor */ @@ -126,7 +126,7 @@ namespace pcl return labels_; } - /** \brief Get exlude labels */ + /** \brief Get exclude labels */ const ExcludeLabelSetConstPtr& getExcludeLabels () const { diff --git a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp index 57213cf3e29..2c2f9f5bac0 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp @@ -349,7 +349,7 @@ pcl::CrfSegmentation::createUnaryPotentials (std::vector &unary, } } - // set the engeries for the labels + // set the energies for the labels std::size_t u_idx = k * n_labels; if (label > 0) { diff --git a/segmentation/include/pcl/segmentation/impl/segment_differences.hpp b/segmentation/include/pcl/segmentation/impl/segment_differences.hpp index ad4de5e943f..dc3611639ec 100755 --- a/segmentation/include/pcl/segmentation/impl/segment_differences.hpp +++ b/segmentation/include/pcl/segmentation/impl/segment_differences.hpp @@ -63,7 +63,7 @@ pcl::getPointCloudDifference ( // Iterate through the source data set for (index_t i = 0; i < static_cast (src.size ()); ++i) { - // Ignore invalid points in the inpout cloud + // Ignore invalid points in the input cloud if (!isFinite (src[i])) continue; // Search for the closest point in the target data set (number of neighbors to find = 1) diff --git a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp index 2af3e32e9b5..54aed117bbe 100644 --- a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp @@ -505,7 +505,7 @@ pcl::SupervoxelClustering::getSupervoxelAdjacencyList (VoxelAdjacencyLis if (edge_added) { VoxelData centroid_data = (sv_itr)->getCentroid (); - //Find the neighbhor with this label + //Find the neighbor with this label VoxelData neighb_centroid_data; for (typename HelperListT::const_iterator neighb_itr = supervoxel_helpers_.cbegin (); neighb_itr != supervoxel_helpers_.cend (); ++neighb_itr) diff --git a/segmentation/include/pcl/segmentation/planar_region.h b/segmentation/include/pcl/segmentation/planar_region.h index acdd7e3c77c..f9b9b99e4db 100644 --- a/segmentation/include/pcl/segmentation/planar_region.h +++ b/segmentation/include/pcl/segmentation/planar_region.h @@ -81,7 +81,7 @@ namespace pcl * \param[in] centroid the centroid of the region. * \param[in] covariance the covariance of the region. * \param[in] count the number of points in the region. - * \param[in] contour the contour / boudnary for the region + * \param[in] contour the contour / boundary for the region * \param[in] coefficients the model coefficients (a,b,c,d) for the plane */ PlanarRegion (const Eigen::Vector3f& centroid, const Eigen::Matrix3f& covariance, unsigned count, diff --git a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h index 286bc92a581..0a8826cea14 100644 --- a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h +++ b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h @@ -130,7 +130,7 @@ namespace pcl inline double getClusterTolerance () const { return (cluster_tolerance_); } - /** \brief Set the tollerance on the hue + /** \brief Set the tolerance on the hue * \param[in] delta_hue the new delta hue */ inline void diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index ff5aae70dcc..e46239c50af 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -275,14 +275,14 @@ namespace pcl /** \brief Returns labeled cloud * Points that belong to the same supervoxel have the same label. - * Labels for segments start from 1, unlabled points have label 0 + * Labels for segments start from 1, unlabeled points have label 0 */ typename pcl::PointCloud::Ptr getLabeledCloud () const; /** \brief Returns labeled voxelized cloud * Points that belong to the same supervoxel have the same label. - * Labels for segments start from 1, unlabled points have label 0 + * Labels for segments start from 1, unlabeled points have label 0 */ pcl::PointCloud::Ptr getLabeledVoxelCloud () const; diff --git a/simulation/tools/README_about_tools b/simulation/tools/README_about_tools index 5c4d778cf14..36e60b73786 100644 --- a/simulation/tools/README_about_tools +++ b/simulation/tools/README_about_tools @@ -18,6 +18,6 @@ status : reads obj, creates window, use keyboard to drive around environment was : range_performance_test.cpp 4. sim_test_simple -purpose: similar code to #3 but has a 2x2 grid each containing 640x480 windows, but operates as #1. press 'v' to capture a cloud to file (only works properly if 2x2 canged to 1x1) +purpose: similar code to #3 but has a 2x2 grid each containing 640x480 windows, but operates as #1. press 'v' to capture a cloud to file (only works properly if 2x2 changed to 1x1) status : reads obj, creates window, use keyboard to drive around environment was : range_test_v2.cpp diff --git a/stereo/include/pcl/stereo/disparity_map_converter.h b/stereo/include/pcl/stereo/disparity_map_converter.h index 0fb59953241..a0942fa0a33 100644 --- a/stereo/include/pcl/stereo/disparity_map_converter.h +++ b/stereo/include/pcl/stereo/disparity_map_converter.h @@ -221,7 +221,7 @@ class DisparityMapConverter { * \param[in] row * \param[in] column * \param[in] disparity - * \return the 3D point, that corresponds to the input parametres and the camera + * \return the 3D point, that corresponds to the input parameters and the camera * calibration. */ PointXYZ diff --git a/stereo/include/pcl/stereo/stereo_matching.h b/stereo/include/pcl/stereo/stereo_matching.h index 7dd966adc18..df7106476f0 100644 --- a/stereo/include/pcl/stereo/stereo_matching.h +++ b/stereo/include/pcl/stereo/stereo_matching.h @@ -452,7 +452,7 @@ class PCL_EXPORTS BlockBasedStereoMatching : public GrayStereoMatching { * This class implements an adaptive-cost stereo matching algorithm based on 2-pass * Scanline Optimization. The algorithm is inspired by the paper: [1] L. Wang et al., * "High Quality Real-time Stereo using Adaptive Cost Aggregation and Dynamic - * Programming", 3DPVT 2006 Cost aggregation is performed using adaptive weigths + * Programming", 3DPVT 2006 Cost aggregation is performed using adaptive weights * computed on a single column as proposed in [1]. Instead of using Dynamic Programming * as in [1], the optimization is performed via 2-pass Scanline Optimization. The * algorithm is based on the Sum of Absolute Differences (SAD) matching function Only diff --git a/surface/include/pcl/surface/grid_projection.h b/surface/include/pcl/surface/grid_projection.h index e1ca758c2b3..77142c50006 100644 --- a/surface/include/pcl/surface/grid_projection.h +++ b/surface/include/pcl/surface/grid_projection.h @@ -318,7 +318,7 @@ namespace pcl getDataPtsUnion (const Eigen::Vector3i &index, pcl::Indices &pt_union_indices); /** \brief Given the index of a cell, exam it's up, left, front edges, and add - * the vectices to m_surface list.the up, left, front edges only share 4 + * the vertices to m_surface list.the up, left, front edges only share 4 * points, we first get the vectors at these 4 points and exam whether those * three edges are intersected by the surface \param index the input index * \param pt_union_indices the union of input data points within the cell and padding cells @@ -399,7 +399,7 @@ namespace pcl /** \brief Test whether the edge is intersected by the surface by * doing the dot product of the vector at two end points. Also test - * whether the edge is intersected by the maximum surface by examing + * whether the edge is intersected by the maximum surface by examining * the 2nd derivative of the intersection point * \param end_pts the two points of the edge * \param vect_at_end_pts diff --git a/surface/include/pcl/surface/impl/texture_mapping.hpp b/surface/include/pcl/surface/impl/texture_mapping.hpp index 6ce1afeda85..95ebc342f44 100644 --- a/surface/include/pcl/surface/impl/texture_mapping.hpp +++ b/surface/include/pcl/surface/impl/texture_mapping.hpp @@ -851,7 +851,7 @@ pcl::TextureMapping::textureMeshwithMultipleCameras (pcl::TextureMesh // current neighbor is inside triangle and is closer => the corresponding face visibility[indexes_uv_to_points[idxNeighbor].idx_face] = false; cpt_invisible++; - //TODO we could remove the projections of this face from the kd-tree cloud, but I fond it slower, and I need the point to keep ordered to querry UV coordinates later + //TODO we could remove the projections of this face from the kd-tree cloud, but I found it slower, and I need the point to keep ordered to query UV coordinates later } } } diff --git a/surface/include/pcl/surface/mls.h b/surface/include/pcl/surface/mls.h index b5cb6080d93..94df042d9d5 100644 --- a/surface/include/pcl/surface/mls.h +++ b/surface/include/pcl/surface/mls.h @@ -648,7 +648,7 @@ namespace pcl /** \brief Number of coefficients, to be computed from the requested order.*/ int nr_coeff_; - /** \brief Collects for each point in output the corrseponding point in the input. */ + /** \brief Collects for each point in output the corresponding point in the input. */ PointIndicesPtr corresponding_input_indices_; /** \brief Search for the nearest neighbors of a given point using a radius search diff --git a/surface/include/pcl/surface/texture_mapping.h b/surface/include/pcl/surface/texture_mapping.h index b7318cc8e4a..0700ccd3c98 100644 --- a/surface/include/pcl/surface/texture_mapping.h +++ b/surface/include/pcl/surface/texture_mapping.h @@ -406,7 +406,7 @@ namespace pcl * \param[in] p1 first point of the triangle. * \param[in] p2 second point of the triangle. * \param[in] p3 third point of the triangle. - * \param[in] pt the querry point. + * \param[in] pt the query point. */ inline bool checkPointInsideTriangle (const pcl::PointXY &p1, const pcl::PointXY &p2, const pcl::PointXY &p3, const pcl::PointXY &pt); diff --git a/test/features/test_normal_estimation.cpp b/test/features/test_normal_estimation.cpp index c93f910d8c4..58a5e77f763 100644 --- a/test/features/test_normal_estimation.cpp +++ b/test/features/test_normal_estimation.cpp @@ -166,7 +166,7 @@ TEST (PCL, NormalEstimation) n.setSearchSurface (surfaceptr); EXPECT_EQ (n.getSearchSurface (), surfaceptr); - // Additional test for searchForNeigbhors + // Additional test for searchForNeighbors surfaceptr.reset (new PointCloud); *surfaceptr = *cloudptr; surfaceptr->points.resize (640 * 480); @@ -267,7 +267,7 @@ TEST (PCL, TranslatedNormalEstimation) n.setSearchSurface (surfaceptr); EXPECT_EQ (n.getSearchSurface (), surfaceptr); - // Additional test for searchForNeigbhors + // Additional test for searchForNeighbors surfaceptr.reset (new PointCloud); *surfaceptr = *cloudptr; surfaceptr->points.resize (640 * 480); diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index 0f91a74aa3c..83d23565aa6 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -1581,7 +1581,7 @@ struct OctreePointCloudSierpinskiTest /** \brief Computes the total number of parent nodes at the specified depth * * The octree is built such that the number of the leaf nodes is equal to - * 4^depth and the number of branch nodes is egal to (4^depth -1)/(4 - 1), + * 4^depth and the number of branch nodes is equal to (4^depth -1)/(4 - 1), * where depth is the detph of the octree. The details of the expression * provided for the number of branch nodes could be found at: * https://en.wikipedia.org/wiki/Geometric_progression#Geometric_series diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index b5a3402b115..cdebf4bc35e 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -183,7 +183,7 @@ TEST(PCL, ICP_translated) pcl::PointCloud Final; icp.align(Final); - // Check that we have sucessfully converged + // Check that we have successfully converged ASSERT_TRUE(icp.hasConverged()); // Test that the fitness score is below acceptable threshold diff --git a/tools/gp3_surface.cpp b/tools/gp3_surface.cpp index 3a1eb742021..421aad041af 100644 --- a/tools/gp3_surface.cpp +++ b/tools/gp3_surface.cpp @@ -58,7 +58,7 @@ printHelp (int, char **argv) print_info (" where options are:\n"); print_info (" -radius X = use a radius of Xm around each point to determine the neighborhood (default: "); print_value ("%f", default_radius); print_info (")\n"); - print_info (" -mu X = set the multipler of the nearest neighbor distance to obtain the final search radius (default: "); + print_info (" -mu X = set the multiplier of the nearest neighbor distance to obtain the final search radius (default: "); print_value ("%f", default_mu); print_info (")\n"); } diff --git a/tools/icp2d.cpp b/tools/icp2d.cpp index 701a1dc96aa..b10f4e577f3 100644 --- a/tools/icp2d.cpp +++ b/tools/icp2d.cpp @@ -103,7 +103,7 @@ main (int argc, char **argv) pcl::registration::TransformationEstimationLM::Ptr te (new pcl::registration::TransformationEstimationLM); te->setWarpFunction (warp_fcn); - // Pass the TransformationEstimation objec to the ICP algorithm + // Pass the TransformationEstimation object to the ICP algorithm icp.setTransformationEstimation (te); icp.setMaximumIterations (iter); diff --git a/tracking/include/pcl/tracking/coherence.h b/tracking/include/pcl/tracking/coherence.h index a8a47729b5f..69c4211bec8 100644 --- a/tracking/include/pcl/tracking/coherence.h +++ b/tracking/include/pcl/tracking/coherence.h @@ -21,7 +21,7 @@ class PointCoherence { /** \brief empty constructor */ PointCoherence() = default; - /** \brief empty distructor */ + /** \brief empty destructor */ virtual ~PointCoherence() = default; /** \brief compute coherence from the source point to the target point. diff --git a/tracking/include/pcl/tracking/particle_filter.h b/tracking/include/pcl/tracking/particle_filter.h index f4cf99e6113..1f0fe6a4513 100644 --- a/tracking/include/pcl/tracking/particle_filter.h +++ b/tracking/include/pcl/tracking/particle_filter.h @@ -484,7 +484,7 @@ class ParticleFilterTracker : public Tracker { computeTransformedPointCloudWithoutNormal(const StateT& hypothesis, PointCloudIn& cloud); - /** \brief This method should get called before starting the actua computation. */ + /** \brief This method should get called before starting the actual computation. */ bool initCompute() override; diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index d971ccc7d7f..fa410114273 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -349,7 +349,7 @@ class PyramidalKLTTracker : public Tracker { convolveRows(const FloatImageConstPtr& input, FloatImage& output) const; /** \brief extract the patch from the previous image, previous image gradients - * surrounding pixel alocation while interpolating image and gradients data + * surrounding pixel allocation while interpolating image and gradients data * and compute covariation matrix of derivatives. * \param[in] img original image * \param[in] grad_x original image gradient along X direction diff --git a/visualization/include/pcl/visualization/common/float_image_utils.h b/visualization/include/pcl/visualization/common/float_image_utils.h index bc5de74e8c7..0168815359e 100644 --- a/visualization/include/pcl/visualization/common/float_image_utils.h +++ b/visualization/include/pcl/visualization/common/float_image_utils.h @@ -43,7 +43,7 @@ namespace pcl { namespace visualization { - /** @b Provide some gerneral functionalities regarding 2d float arrays, e.g., for visualization purposes + /** @b Provide some general functionalities regarding 2d float arrays, e.g., for visualization purposes * \author Bastian Steder * \ingroup visualization */ diff --git a/visualization/include/pcl/visualization/image_viewer.h b/visualization/include/pcl/visualization/image_viewer.h index 1c2d147332b..dd65d37f9c8 100644 --- a/visualization/include/pcl/visualization/image_viewer.h +++ b/visualization/include/pcl/visualization/image_viewer.h @@ -560,7 +560,7 @@ namespace pcl bool wasStopped () const { return (stopped_); } - /** \brief Stop the interaction and close the visualizaton window. */ + /** \brief Stop the interaction and close the visualization window. */ void close () { diff --git a/visualization/include/pcl/visualization/keyboard_event.h b/visualization/include/pcl/visualization/keyboard_event.h index 042381893bd..226ea40ea27 100644 --- a/visualization/include/pcl/visualization/keyboard_event.h +++ b/visualization/include/pcl/visualization/keyboard_event.h @@ -48,11 +48,11 @@ namespace pcl class KeyboardEvent { public: - /** \brief bit patter for the ALT key*/ + /** \brief bit pattern for the ALT key*/ static const unsigned int Alt = 1; - /** \brief bit patter for the Control key*/ + /** \brief bit pattern for the Control key*/ static const unsigned int Ctrl = 2; - /** \brief bit patter for the Shift key*/ + /** \brief bit pattern for the Shift key*/ static const unsigned int Shift = 4; /** \brief Constructor diff --git a/visualization/include/pcl/visualization/pcl_plotter.h b/visualization/include/pcl/visualization/pcl_plotter.h index 93f78695d17..1df71fd8734 100644 --- a/visualization/include/pcl/visualization/pcl_plotter.h +++ b/visualization/include/pcl/visualization/pcl_plotter.h @@ -393,7 +393,7 @@ namespace pcl bool wasStopped () const; - /** \brief Stop the interaction and close the visualizaton window. */ + /** \brief Stop the interaction and close the visualization window. */ void close (); diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 4d1d9290e4a..577a2d3c25a 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -1252,7 +1252,7 @@ namespace pcl void resetStoppedFlag (); - /** \brief Stop the interaction and close the visualizaton window. */ + /** \brief Stop the interaction and close the visualization window. */ void close (); diff --git a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h index ea2be9563a6..df18ad3158b 100644 --- a/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h +++ b/visualization/include/pcl/visualization/point_cloud_geometry_handlers.h @@ -89,7 +89,7 @@ namespace pcl virtual std::string getFieldName () const = 0; - /** \brief Checl if this handler is capable of handling the input data or not. */ + /** \brief Check if this handler is capable of handling the input data or not. */ inline bool isCapable () const { return (capable_); } diff --git a/visualization/include/pcl/visualization/vtk/vtkFixedXRenderWindowInteractor.h b/visualization/include/pcl/visualization/vtk/vtkFixedXRenderWindowInteractor.h index 10ffdf9d9c4..54bac8e7396 100644 --- a/visualization/include/pcl/visualization/vtk/vtkFixedXRenderWindowInteractor.h +++ b/visualization/include/pcl/visualization/vtk/vtkFixedXRenderWindowInteractor.h @@ -148,7 +148,7 @@ class VTKRENDERINGUI_EXPORT vtkXRenderWindowInteractor : public vtkRenderWindowI void StartEventLoop() override; /** - * Deallocate X ressource that may have been allocated + * Deallocate X resource that may have been allocated * Also calls finalize on the render window if available */ void Finalize(); diff --git a/visualization/src/pcl_painter2D.cpp b/visualization/src/pcl_painter2D.cpp index f257dc93283..8e9106a6201 100644 --- a/visualization/src/pcl_painter2D.cpp +++ b/visualization/src/pcl_painter2D.cpp @@ -54,7 +54,7 @@ pcl::visualization::PCLPainter2D::PCLPainter2D(char const * name) exit_loop_timer_->interactor = view_->GetInteractor (); - //defaulat state + //default state win_width_ = 640; win_height_ = 480; bkg_color_[0] = 1; bkg_color_[1] = 1; bkg_color_[2] = 1; diff --git a/visualization/src/vtk/vtkFixedXRenderWindowInteractor.cxx b/visualization/src/vtk/vtkFixedXRenderWindowInteractor.cxx index 07a0d083187..60faa683e5a 100644 --- a/visualization/src/vtk/vtkFixedXRenderWindowInteractor.cxx +++ b/visualization/src/vtk/vtkFixedXRenderWindowInteractor.cxx @@ -794,7 +794,7 @@ void vtkXRenderWindowInteractor::DispatchEvent(XEvent* event) this->InvokeEvent(vtkCommand::DropFilesEvent, filePaths); XFree(data); - // Inform the source the the drag and drop operation was sucessfull + // Inform the source the the drag and drop operation was successful XEvent reply; memset(&reply, 0, sizeof(reply)); From c3cca46b751da0109de8bc85f15c97ff3c85c166 Mon Sep 17 00:00:00 2001 From: Rasmus Date: Sat, 10 Dec 2022 20:02:56 +0100 Subject: [PATCH 012/288] Fix incorrect printf format specifier and typo (#5536) * Fix incorrect printf format specifier and typo * Update tools/radius_filter.cpp Co-authored-by: Lars Glud Co-authored-by: Lars Glud --- tools/radius_filter.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/tools/radius_filter.cpp b/tools/radius_filter.cpp index 36f336a1d2f..3ab8e3b7d9a 100644 --- a/tools/radius_filter.cpp +++ b/tools/radius_filter.cpp @@ -57,8 +57,8 @@ printHelp (int, char **argv) { pcl::console::print_error ("Syntax is: %s input.pcd output.pcd \n", argv[0]); pcl::console::print_info (" where options are:\n"); - pcl::console::print_info (" -radius X = Radius of the spere to filter (default: "); - pcl::console::print_value ("%s", default_radius); pcl::console::print_info (")\n"); + pcl::console::print_info (" -radius X = Radius of the sphere to filter (default: "); + pcl::console::print_value ("%f", default_radius); pcl::console::print_info (")\n"); pcl::console::print_info (" -inside X = keep the points inside the [min, max] interval or not (default: "); pcl::console::print_value ("%d", default_inside); pcl::console::print_info (")\n"); pcl::console::print_info (" -keep 0/1 = keep the points organized (1) or not (default: "); @@ -132,7 +132,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir // Prepare output file name std::string filename = boost::filesystem::path(pcd_file).filename().string(); - + // Save into the second file const std::string filepath = output_dir + '/' + filename; saveCloud (filepath, output); From ec6ad8e45efaa6f55f37024e87f55fde30462ea3 Mon Sep 17 00:00:00 2001 From: SunBlack Date: Wed, 23 Nov 2022 23:11:25 +0100 Subject: [PATCH 013/288] Fix MSVC warning C26814: "The const variable 'variable' can be computed at compile time. Consider using constexpr." --- apps/in_hand_scanner/src/icp.cpp | 2 +- apps/in_hand_scanner/src/integration.cpp | 4 +- apps/in_hand_scanner/src/main_window.cpp | 2 +- apps/in_hand_scanner/src/opengl_viewer.cpp | 4 +- .../pcl/apps/point_cloud_editor/localTypes.h | 14 ++--- apps/src/feature_matching.cpp | 2 +- ...multiscale_feature_persistence_example.cpp | 2 +- apps/src/openni_feature_persistence.cpp | 6 +- apps/src/openni_mobile_server.cpp | 2 +- apps/src/openni_organized_edge_detection.cpp | 2 +- apps/src/openni_shift_to_depth_conversion.cpp | 2 +- apps/src/pcd_organized_edge_detection.cpp | 2 +- apps/src/ppf_object_recognition.cpp | 2 +- apps/src/pyramid_surface_matching.cpp | 2 +- ...ale_interest_region_extraction_example.cpp | 4 +- common/include/pcl/common/impl/copy_point.hpp | 4 +- common/include/pcl/common/impl/eigen.hpp | 2 +- common/include/pcl/point_representation.h | 2 +- common/include/pcl/register_point_struct.h | 14 ++--- .../example_difference_of_normals.cpp | 2 +- .../example_sift_keypoint_estimation.cpp | 8 +-- ...xample_sift_normal_keypoint_estimation.cpp | 8 +-- .../example_sift_z_keypoint_estimation.cpp | 8 +-- .../example_extract_clusters_normals.cpp | 6 +- .../include/pcl/features/impl/brisk_2d.hpp | 2 +- gpu/kinfu/tools/kinfu_app.cpp | 2 +- gpu/kinfu/tools/record_tsdfvolume.cpp | 6 +- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 2 +- .../tools/record_maps_rgb.cpp | 2 +- gpu/people/include/pcl/gpu/people/tree.h | 2 +- gpu/people/src/cuda/nvidia/NCV.hpp | 4 +- .../compression/impl/entropy_range_coder.hpp | 32 +++++------ io/tools/openni_pcd_recorder.cpp | 2 +- .../include/pcl/keypoints/impl/harris_3d.hpp | 2 +- .../pcl/keypoints/impl/sift_keypoint.hpp | 4 +- .../pcl/octree/impl/octree_pointcloud.hpp | 4 +- octree/include/pcl/octree/octree_search.h | 2 +- .../pcl/outofcore/impl/octree_base.hpp | 4 +- outofcore/tools/outofcore_process.cpp | 4 +- .../pcl/recognition/color_gradient_modality.h | 6 +- .../recognition/impl/implicit_shape_model.hpp | 6 +- .../recognition/impl/linemod/line_rgbd.hpp | 2 +- .../recognition/ransac_based/obj_rec_ransac.h | 4 +- .../pcl/recognition/surface_normal_modality.h | 16 +++--- registration/include/pcl/registration/bfgs.h | 2 +- .../impl/correspondence_rejection_poly.hpp | 2 +- .../include/pcl/registration/impl/ia_fpcs.hpp | 4 +- .../include/pcl/registration/impl/ndt.hpp | 6 +- .../pcl/sample_consensus/method_types.h | 14 ++--- .../3rdparty/opennurbs/opennurbs_array_defs.h | 2 +- .../poisson4/multi_grid_octree_data.hpp | 8 +-- test/common/test_eigen.cpp | 56 +++++++++---------- test/common/test_macros.cpp | 2 +- test/common/test_parse.cpp | 10 ++-- test/common/test_polygon_mesh.cpp | 4 +- test/common/test_spring.cpp | 4 +- test/common/test_wrappers.cpp | 2 +- test/features/test_flare_estimation.cpp | 6 +- test/features/test_gradient_estimation.cpp | 2 +- test/features/test_ii_normals.cpp | 16 +++--- test/features/test_pfh_estimation.cpp | 2 +- test/filters/test_crop_hull.cpp | 2 +- test/filters/test_farthest_point_sampling.cpp | 4 +- test/filters/test_filters.cpp | 2 +- test/filters/test_uniform_sampling.cpp | 2 +- test/geometry/test_iterator.cpp | 8 +-- test/geometry/test_mesh_common_functions.h | 4 +- test/geometry/test_quad_mesh.cpp | 2 +- test/gpu/octree/performance.cpp | 4 +- test/gpu/octree/test_host_radius_search.cpp | 2 +- test/gpu/octree/test_knn_search.cpp | 4 +- test/gpu/octree/test_radius_search.cpp | 2 +- test/io/test_octree_compression.cpp | 2 +- test/io/test_ply_mesh_io.cpp | 4 +- test/io/test_range_coder.cpp | 2 +- test/kdtree/test_kdtree.cpp | 2 +- test/keypoints/test_iss_3d.cpp | 4 +- test/keypoints/test_keypoints.cpp | 15 +++-- test/octree/test_octree.cpp | 16 +++--- test/octree/test_octree_iterator.cpp | 6 +- test/outofcore/test_outofcore.cpp | 8 +-- test/registration/test_fpcs_ia_data.h | 8 +-- test/registration/test_kfpcs_ia.cpp | 2 +- test/registration/test_kfpcs_ia_data.h | 8 +-- .../registration/test_registration_api_data.h | 26 ++++----- .../test_sample_consensus.cpp | 2 +- .../test_sample_consensus_line_models.cpp | 8 +-- .../test_sample_consensus_plane_models.cpp | 12 ++-- test/search/test_search.cpp | 8 +-- test/surface/test_moving_least_squares.cpp | 4 +- tools/crop_to_hull.cpp | 2 +- tools/mesh_sampling.cpp | 4 +- tools/obj_rec_ransac_accepted_hypotheses.cpp | 2 +- tools/obj_rec_ransac_model_opps.cpp | 2 +- tools/obj_rec_ransac_result.cpp | 2 +- tools/obj_rec_ransac_scene_opps.cpp | 2 +- tools/openni_image.cpp | 2 +- tools/train_linemod_template.cpp | 4 +- .../include/pcl/tracking/impl/tracking.hpp | 2 +- 99 files changed, 275 insertions(+), 276 deletions(-) diff --git a/apps/in_hand_scanner/src/icp.cpp b/apps/in_hand_scanner/src/icp.cpp index b3ae1372f41..cbd16668eaa 100644 --- a/apps/in_hand_scanner/src/icp.cpp +++ b/apps/in_hand_scanner/src/icp.cpp @@ -161,7 +161,7 @@ pcl::ihs::ICP::findTransformation(const MeshConstPtr& mesh_model, { // Check the input // TODO: Double check the minimum number of points necessary for icp - const std::size_t n_min = 4; + constexpr std::size_t n_min = 4; if (mesh_model->sizeVertices() < n_min || cloud_data->size() < n_min) { std::cerr << "ERROR in icp.cpp: Not enough input points!\n"; diff --git a/apps/in_hand_scanner/src/integration.cpp b/apps/in_hand_scanner/src/integration.cpp index 9b5bdc11ce7..3d7517ac145 100644 --- a/apps/in_hand_scanner/src/integration.cpp +++ b/apps/in_hand_scanner/src/integration.cpp @@ -124,7 +124,7 @@ pcl::ihs::Integration::reconstructMesh(const CloudXYZRGBNormalConstPtr& cloud_da // * 3 - 0 // const int offset_1 = -width; const int offset_2 = -width - 1; - const int offset_3 = -1; + constexpr int offset_3 = -1; const int offset_4 = -width - 2; for (int r = 1; r < height; ++r) { @@ -262,7 +262,7 @@ pcl::ihs::Integration::merge(const CloudXYZRGBNormalConstPtr& cloud_data, // * 3 - 0 // const int offset_1 = -width; const int offset_2 = -width - 1; - const int offset_3 = -1; + constexpr int offset_3 = -1; const int offset_4 = -width - 2; const float dot_min = std::cos(max_angle_ * 17.45329252e-3); // deg to rad diff --git a/apps/in_hand_scanner/src/main_window.cpp b/apps/in_hand_scanner/src/main_window.cpp index f32601307db..d97e9c14bb9 100644 --- a/apps/in_hand_scanner/src/main_window.cpp +++ b/apps/in_hand_scanner/src/main_window.cpp @@ -70,7 +70,7 @@ pcl::ihs::MainWindow::MainWindow(QWidget* parent) spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); ui_->toolBar->insertWidget(ui_->actionHelp, spacer); - const double max = std::numeric_limits::max(); + constexpr double max = std::numeric_limits::max(); // In hand scanner QHBoxLayout* layout = new QHBoxLayout(ui_->placeholder_in_hand_scanner); diff --git a/apps/in_hand_scanner/src/opengl_viewer.cpp b/apps/in_hand_scanner/src/opengl_viewer.cpp index 054f601f138..48320e911aa 100644 --- a/apps/in_hand_scanner/src/opengl_viewer.cpp +++ b/apps/in_hand_scanner/src/opengl_viewer.cpp @@ -484,7 +484,7 @@ pcl::ihs::OpenGLViewer::addMesh(const CloudXYZRGBNormalConstPtr& cloud, const int h = cloud->height; const int offset_1 = -w; const int offset_2 = -w - 1; - const int offset_3 = -1; + constexpr int offset_3 = -1; FaceVertexMeshPtr mesh(new FaceVertexMesh()); mesh->transformation = T; @@ -1083,7 +1083,7 @@ pcl::ihs::OpenGLViewer::initializeGL() void pcl::ihs::OpenGLViewer::setupViewport(const int w, const int h) { - const float aspect_ratio = 4. / 3.; + constexpr float aspect_ratio = 4. / 3.; // Use the biggest possible area of the window to draw to // case 1 (w < w_scaled): case 2 (w >= w_scaled): diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h index 024d237ccea..ed7fa8d76d2 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/localTypes.h @@ -167,25 +167,25 @@ struct IncIndex /// A helpful const representing the number of elements in our vectors. /// This is used for all operations that require the copying of the vector. /// Although this is used in a fairly generic way, the display requires 3D. -const unsigned int XYZ_SIZE = 3; +constexpr unsigned int XYZ_SIZE = 3; /// A helpful const representing the number of elements in each row/col in /// our matrices. This is used for all operations that require the copying of /// the matrix. -const unsigned int MATRIX_SIZE_DIM = 4; +constexpr unsigned int MATRIX_SIZE_DIM = 4; /// A helpful const representing the number of elements in our matrices. /// This is used for all operations that require the copying of the matrix. -const unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM; +constexpr unsigned int MATRIX_SIZE = MATRIX_SIZE_DIM * MATRIX_SIZE_DIM; /// The default window width -const unsigned int WINDOW_WIDTH = 1200; +constexpr unsigned int WINDOW_WIDTH = 1200; /// The default window height -const unsigned int WINDOW_HEIGHT = 1000; +constexpr unsigned int WINDOW_HEIGHT = 1000; /// The default z translation used to push the world origin in front of the /// display -const float DISPLAY_Z_TRANSLATION = -2.0f; +constexpr float DISPLAY_Z_TRANSLATION = -2.0f; /// The radius of the trackball given as a percentage of the screen width -const float TRACKBALL_RADIUS_SCALE = 0.4f; +constexpr float TRACKBALL_RADIUS_SCALE = 0.4f; diff --git a/apps/src/feature_matching.cpp b/apps/src/feature_matching.cpp index 488af48cca1..1ff0784410a 100644 --- a/apps/src/feature_matching.cpp +++ b/apps/src/feature_matching.cpp @@ -324,7 +324,7 @@ ICCVTutorial::findCorrespondences( // Find the index of the best match for each keypoint, and store it in // "correspondences_out" - const int k = 1; + constexpr int k = 1; pcl::Indices k_indices(k); std::vector k_squared_distances(k); for (int i = 0; i < static_cast(source->size()); ++i) { diff --git a/apps/src/multiscale_feature_persistence_example.cpp b/apps/src/multiscale_feature_persistence_example.cpp index 5ae97db8dcc..a2bc67958d5 100644 --- a/apps/src/multiscale_feature_persistence_example.cpp +++ b/apps/src/multiscale_feature_persistence_example.cpp @@ -47,7 +47,7 @@ using namespace pcl; const Eigen::Vector4f subsampling_leaf_size(0.01f, 0.01f, 0.01f, 0.0f); -const float normal_estimation_search_radius = 0.05f; +constexpr float normal_estimation_search_radius = 0.05f; void subsampleAndCalculateNormals(PointCloud::Ptr& cloud, diff --git a/apps/src/openni_feature_persistence.cpp b/apps/src/openni_feature_persistence.cpp index 70b99cb604f..f61571d91a6 100644 --- a/apps/src/openni_feature_persistence.cpp +++ b/apps/src/openni_feature_persistence.cpp @@ -69,11 +69,11 @@ using namespace std::chrono_literals; } while (false) // clang-format on -const float default_subsampling_leaf_size = 0.02f; -const float default_normal_search_radius = 0.041f; +constexpr float default_subsampling_leaf_size = 0.02f; +constexpr float default_normal_search_radius = 0.041f; const double aux[] = {0.21, 0.32}; const std::vector default_scales_vector(aux, aux + 2); -const float default_alpha = 1.2f; +constexpr float default_alpha = 1.2f; template class OpenNIFeaturePersistence { diff --git a/apps/src/openni_mobile_server.cpp b/apps/src/openni_mobile_server.cpp index 5a1c8d62bf7..e4440dcd0f0 100644 --- a/apps/src/openni_mobile_server.cpp +++ b/apps/src/openni_mobile_server.cpp @@ -79,7 +79,7 @@ CopyPointCloudToBuffers(const pcl::PointCloud::ConstPtr& clou point.x > bounds_max.x || point.y > bounds_max.y || point.z > bounds_max.z) continue; - const int conversion_factor = 500; + constexpr int conversion_factor = 500; cloud_buffers.points[j * 3 + 0] = static_cast(point.x * conversion_factor); cloud_buffers.points[j * 3 + 1] = static_cast(point.y * conversion_factor); diff --git a/apps/src/openni_organized_edge_detection.cpp b/apps/src/openni_organized_edge_detection.cpp index caf01aae7c8..1fc6aee478a 100644 --- a/apps/src/openni_organized_edge_detection.cpp +++ b/apps/src/openni_organized_edge_detection.cpp @@ -68,7 +68,7 @@ class OpenNIOrganizedEdgeDetection { *this); viewer->resetCameraViewpoint("cloud"); - const int point_size = 2; + constexpr int point_size = 2; viewer->addPointCloud(cloud, "nan boundary edges"); viewer->setPointCloudRenderingProperties( pcl::visualization::PCL_VISUALIZER_POINT_SIZE, diff --git a/apps/src/openni_shift_to_depth_conversion.cpp b/apps/src/openni_shift_to_depth_conversion.cpp index 292a06ef3d4..7de78e4f2eb 100644 --- a/apps/src/openni_shift_to_depth_conversion.cpp +++ b/apps/src/openni_shift_to_depth_conversion.cpp @@ -164,7 +164,7 @@ class SimpleOpenNIViewer { int centerY = static_cast(height_arg / 2); const float fl_const = 1.0f / focalLength_arg; - static const float bad_point = std::numeric_limits::quiet_NaN(); + constexpr float bad_point = std::numeric_limits::quiet_NaN(); std::size_t i = 0; for (int y = -centerY; y < +centerY; ++y) diff --git a/apps/src/pcd_organized_edge_detection.cpp b/apps/src/pcd_organized_edge_detection.cpp index 6eb0c222c0a..e1eb6f9af11 100644 --- a/apps/src/pcd_organized_edge_detection.cpp +++ b/apps/src/pcd_organized_edge_detection.cpp @@ -227,7 +227,7 @@ compute(const pcl::PCLPointCloud2::ConstPtr& input, pcl::copyPointCloud(*cloud, label_indices[3].indices, *high_curvature_edges); pcl::copyPointCloud(*cloud, label_indices[4].indices, *rgb_edges); - const int point_size = 2; + constexpr int point_size = 2; viewer.addPointCloud(nan_boundary_edges, "nan boundary edges"); viewer.setPointCloudRenderingProperties( pcl::visualization::PCL_VISUALIZER_POINT_SIZE, point_size, "nan boundary edges"); diff --git a/apps/src/ppf_object_recognition.cpp b/apps/src/ppf_object_recognition.cpp index e02d9d62b1a..b12ac2a0f43 100644 --- a/apps/src/ppf_object_recognition.cpp +++ b/apps/src/ppf_object_recognition.cpp @@ -15,7 +15,7 @@ using namespace pcl; using namespace std::chrono_literals; const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f); -const float normal_estimation_search_radius = 0.05f; +constexpr float normal_estimation_search_radius = 0.05f; PointCloud::Ptr subsampleAndCalculateNormals(const PointCloud::Ptr& cloud) diff --git a/apps/src/pyramid_surface_matching.cpp b/apps/src/pyramid_surface_matching.cpp index 6580262a8f9..b325b4473d9 100644 --- a/apps/src/pyramid_surface_matching.cpp +++ b/apps/src/pyramid_surface_matching.cpp @@ -9,7 +9,7 @@ using namespace pcl; #include const Eigen::Vector4f subsampling_leaf_size(0.02f, 0.02f, 0.02f, 0.0f); -const float normal_estimation_search_radius = 0.05f; +constexpr float normal_estimation_search_radius = 0.05f; void subsampleAndCalculateNormals(PointCloud::Ptr& cloud, diff --git a/apps/src/statistical_multiscale_interest_region_extraction_example.cpp b/apps/src/statistical_multiscale_interest_region_extraction_example.cpp index ecc55a77c82..b966c39a29f 100644 --- a/apps/src/statistical_multiscale_interest_region_extraction_example.cpp +++ b/apps/src/statistical_multiscale_interest_region_extraction_example.cpp @@ -42,8 +42,8 @@ using namespace pcl; -const float subsampling_leaf_size = 0.003f; -const float base_scale = 0.005f; +constexpr float subsampling_leaf_size = 0.003f; +constexpr float base_scale = 0.005f; int main(int, char** argv) diff --git a/common/include/pcl/common/impl/copy_point.hpp b/common/include/pcl/common/impl/copy_point.hpp index d5978f539d7..42843d090e3 100644 --- a/common/include/pcl/common/impl/copy_point.hpp +++ b/common/include/pcl/common/impl/copy_point.hpp @@ -118,10 +118,10 @@ struct CopyPointHelper::type; using FieldListOutT = typename pcl::traits::fieldList::type; using FieldList = typename pcl::intersect::type; - const std::uint32_t offset_in = boost::mpl::if_, + constexpr std::uint32_t offset_in = boost::mpl::if_, pcl::traits::offset, pcl::traits::offset >::type::value; - const std::uint32_t offset_out = boost::mpl::if_, + constexpr std::uint32_t offset_out = boost::mpl::if_, pcl::traits::offset, pcl::traits::offset >::type::value; pcl::for_each_type (pcl::NdConcatenateFunctor (point_in, point_out)); diff --git a/common/include/pcl/common/impl/eigen.hpp b/common/include/pcl/common/impl/eigen.hpp index fbc9eb8a2b4..4ff30cd5cbd 100644 --- a/common/include/pcl/common/impl/eigen.hpp +++ b/common/include/pcl/common/impl/eigen.hpp @@ -89,7 +89,7 @@ computeRoots (const Matrix& m, Roots& roots) computeRoots2 (c2, c1, roots); else { - const Scalar s_inv3 = Scalar (1.0 / 3.0); + constexpr Scalar s_inv3 = Scalar(1.0 / 3.0); const Scalar s_sqrt3 = std::sqrt (Scalar (3.0)); // Construct the parameters used in classifying the roots of the equation // and in solving the equation for the roots in closed form. diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 5acdd9eb448..a7f2e57c346 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -250,7 +250,7 @@ namespace pcl template inline void operator() () { using FieldT = typename pcl::traits::datatype::type; - const int NrDims = pcl::traits::datatype::size; + constexpr int NrDims = pcl::traits::datatype::size; Helper::copyPoint (p1_, p2_, f_idx_); } diff --git a/common/include/pcl/register_point_struct.h b/common/include/pcl/register_point_struct.h index 1a09228b834..af9d32a0662 100644 --- a/common/include/pcl/register_point_struct.h +++ b/common/include/pcl/register_point_struct.h @@ -100,7 +100,7 @@ namespace pcl plus (std::remove_const_t &l, const T &r) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T) / sizeof (type); + constexpr std::uint32_t count = sizeof(T) / sizeof(type); for (std::uint32_t i = 0; i < count; ++i) l[i] += r[i]; } @@ -117,7 +117,7 @@ namespace pcl plusscalar (T1 &p, const T2 &scalar) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T1) / sizeof (type); + constexpr std::uint32_t count = sizeof(T1) / sizeof(type); for (std::uint32_t i = 0; i < count; ++i) p[i] += scalar; } @@ -134,7 +134,7 @@ namespace pcl minus (std::remove_const_t &l, const T &r) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T) / sizeof (type); + constexpr std::uint32_t count = sizeof(T) / sizeof(type); for (std::uint32_t i = 0; i < count; ++i) l[i] -= r[i]; } @@ -151,7 +151,7 @@ namespace pcl minusscalar (T1 &p, const T2 &scalar) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T1) / sizeof (type); + constexpr std::uint32_t count = sizeof(T1) / sizeof(type); for (std::uint32_t i = 0; i < count; ++i) p[i] -= scalar; } @@ -168,7 +168,7 @@ namespace pcl mulscalar (T1 &p, const T2 &scalar) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T1) / sizeof (type); + constexpr std::uint32_t count = sizeof(T1) / sizeof(type); for (std::uint32_t i = 0; i < count; ++i) p[i] *= scalar; } @@ -185,7 +185,7 @@ namespace pcl divscalar (T1 &p, const T2 &scalar) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (T1) / sizeof (type); + constexpr std::uint32_t count = sizeof (T1) / sizeof (type); for (std::uint32_t i = 0; i < count; ++i) p[i] /= scalar; } @@ -202,7 +202,7 @@ namespace pcl divscalar2 (ArrayT &p, const ScalarT &scalar) { using type = std::remove_all_extents_t; - static const std::uint32_t count = sizeof (ArrayT) / sizeof (type); + constexpr std::uint32_t count = sizeof (ArrayT) / sizeof (type); for (std::uint32_t i = 0; i < count; ++i) p[i] = scalar / p[i]; } diff --git a/examples/features/example_difference_of_normals.cpp b/examples/features/example_difference_of_normals.cpp index fd7b505ca77..4d2637864e3 100644 --- a/examples/features/example_difference_of_normals.cpp +++ b/examples/features/example_difference_of_normals.cpp @@ -99,7 +99,7 @@ int main (int argc, char *argv[]) // Create downsampled point cloud for DoN NN search with large scale large_cloud_downsampled = PointCloud::Ptr(new pcl::PointCloud); - const float largedownsample = float (scale2/decimation); + constexpr float largedownsample = float(scale2 / decimation); sor.setLeafSize (largedownsample, largedownsample, largedownsample); sor.filter (*large_cloud_downsampled); std::cout << "Using leaf size of " << largedownsample << " for large scale, " << large_cloud_downsampled->size() << " points" << std::endl; diff --git a/examples/keypoints/example_sift_keypoint_estimation.cpp b/examples/keypoints/example_sift_keypoint_estimation.cpp index 612e070ea11..34748942bdc 100644 --- a/examples/keypoints/example_sift_keypoint_estimation.cpp +++ b/examples/keypoints/example_sift_keypoint_estimation.cpp @@ -57,10 +57,10 @@ main(int, char** argv) std::cout << "points: " << cloud->size () <size () < ne; diff --git a/examples/keypoints/example_sift_z_keypoint_estimation.cpp b/examples/keypoints/example_sift_z_keypoint_estimation.cpp index 146f03f5d46..036a8a6b39f 100644 --- a/examples/keypoints/example_sift_z_keypoint_estimation.cpp +++ b/examples/keypoints/example_sift_z_keypoint_estimation.cpp @@ -75,10 +75,10 @@ main(int, char** argv) std::cout << "points: " << cloud_xyz->size () < sift; diff --git a/examples/segmentation/example_extract_clusters_normals.cpp b/examples/segmentation/example_extract_clusters_normals.cpp index 30b3728d7b6..a4fec273ce1 100644 --- a/examples/segmentation/example_extract_clusters_normals.cpp +++ b/examples/segmentation/example_extract_clusters_normals.cpp @@ -79,9 +79,9 @@ main (int argc, char **argv) // Extracting Euclidean clusters using cloud and its normals std::vector cluster_indices; - const float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system - const double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals - const unsigned int min_cluster_size = 50; + constexpr float tolerance = 0.5f; // 50cm tolerance in (x, y, z) coordinate system + constexpr double eps_angle = 5 * (M_PI / 180.0); // 5degree tolerance in normals + constexpr unsigned int min_cluster_size = 50; pcl::extractEuclideanClusters (*cloud_ptr, *cloud_normals, tolerance, tree_ec, cluster_indices, eps_angle, min_cluster_size); diff --git a/features/include/pcl/features/impl/brisk_2d.hpp b/features/include/pcl/features/impl/brisk_2d.hpp index b65fade791a..4b505d309a9 100644 --- a/features/include/pcl/features/impl/brisk_2d.hpp +++ b/features/include/pcl/features/impl/brisk_2d.hpp @@ -124,7 +124,7 @@ BRISK2DEstimation::generateKernel ( scale_list_ = new float[scales_]; size_list_ = new unsigned int[scales_]; - const float sigma_scale = 1.3f; + constexpr float sigma_scale = 1.3f; for (unsigned int scale = 0; scale < scales_; ++scale) { diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 50e670bbba0..04f91172f08 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -732,7 +732,7 @@ struct KinFuApp { if(registration_) { - const int max_color_integration_weight = 2; + constexpr int max_color_integration_weight = 2; kinfu_.initColorIntegration(max_color_integration_weight); integrate_colors_ = true; } diff --git a/gpu/kinfu/tools/record_tsdfvolume.cpp b/gpu/kinfu/tools/record_tsdfvolume.cpp index dc58cbb55c6..873111eb2ac 100644 --- a/gpu/kinfu/tools/record_tsdfvolume.cpp +++ b/gpu/kinfu/tools/record_tsdfvolume.cpp @@ -138,8 +138,8 @@ DeviceVolume::createFromDepth (const pcl::device::PtrStepSz; - const int rows = 480; - const int cols = 640; + constexpr int rows = 480; + constexpr int cols = 640; // scale depth values gpu::DeviceArray2D device_depth_scaled; @@ -197,7 +197,7 @@ DeviceVolume::getVolume (pcl::TSDFVolume::Ptr &volume) bool DeviceVolume::getCloud (pcl::PointCloud::Ptr &cloud) { - const int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000; + constexpr int DEFAULT_VOLUME_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000; // point buffer on the device pcl::gpu::DeviceArray device_cloud_buffer (DEFAULT_VOLUME_CLOUD_BUFFER_SIZE); diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index a7f58b04f9b..d2b8c71279f 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -790,7 +790,7 @@ struct KinFuLSApp { if(registration_) { - const int max_color_integration_weight = 2; + constexpr int max_color_integration_weight = 2; kinfu_->initColorIntegration(max_color_integration_weight); integrate_colors_ = true; } diff --git a/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp b/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp index 08508a687fa..60addb9839c 100644 --- a/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp +++ b/gpu/kinfu_large_scale/tools/record_maps_rgb.cpp @@ -71,7 +71,7 @@ do \ bool is_done = false; std::mutex io_mutex; -const int BUFFER_SIZE = 1000; +constexpr int BUFFER_SIZE = 1000; static int counter = 1; ////////////////////////////////////////////////////////////////////////////////////////// class MapsBuffer diff --git a/gpu/people/include/pcl/gpu/people/tree.h b/gpu/people/include/pcl/gpu/people/tree.h index de0858948b1..9aef9a67039 100644 --- a/gpu/people/include/pcl/gpu/people/tree.h +++ b/gpu/people/include/pcl/gpu/people/tree.h @@ -53,7 +53,7 @@ namespace pcl namespace trees { // this has nothing to do here... - static const double focal = 1000.; + constexpr double focal = 1000.; // ############################################### // compile type values diff --git a/gpu/people/src/cuda/nvidia/NCV.hpp b/gpu/people/src/cuda/nvidia/NCV.hpp index 039cac5fe4a..08cab2752be 100644 --- a/gpu/people/src/cuda/nvidia/NCV.hpp +++ b/gpu/people/src/cuda/nvidia/NCV.hpp @@ -212,8 +212,8 @@ NCV_CT_ASSERT(sizeof(NcvPoint2D32u) == 2 * sizeof(Ncv32u)); // //============================================================================== -const Ncv32u K_WARP_SIZE = 32; -const Ncv32u K_LOG2_WARP_SIZE = 5; +constexpr Ncv32u K_WARP_SIZE = 32; +constexpr Ncv32u K_LOG2_WARP_SIZE = 5; //============================================================================== // diff --git a/io/include/pcl/compression/impl/entropy_range_coder.hpp b/io/include/pcl/compression/impl/entropy_range_coder.hpp index 610f5adc5aa..65832a0747a 100644 --- a/io/include/pcl/compression/impl/entropy_range_coder.hpp +++ b/io/include/pcl/compression/impl/entropy_range_coder.hpp @@ -54,9 +54,9 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector& inpu DWord freq[257]; // define limits - const DWord top = static_cast (1) << 24; - const DWord bottom = static_cast (1) << 16; - const DWord maxRange = static_cast (1) << 16; + constexpr DWord top = static_cast(1) << 24; + constexpr DWord bottom = static_cast(1) << 16; + constexpr DWord maxRange = static_cast(1) << 16; auto input_size = static_cast (inputByteVector_arg.size ()); @@ -132,9 +132,9 @@ pcl::AdaptiveRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream DWord freq[257]; // define limits - const DWord top = static_cast (1) << 24; - const DWord bottom = static_cast (1) << 16; - const DWord maxRange = static_cast (1) << 16; + constexpr DWord top = static_cast(1) << 24; + constexpr DWord bottom = static_cast(1) << 16; + constexpr DWord maxRange = static_cast(1) << 16; auto output_size = static_cast (outputByteVector_arg.size ()); @@ -222,9 +222,9 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input std::ostream& outputByteStream_arg) { // define numerical limits - const std::uint64_t top = static_cast (1) << 56; - const std::uint64_t bottom = static_cast (1) << 48; - const std::uint64_t maxRange = static_cast (1) << 48; + constexpr std::uint64_t top = static_cast(1) << 56; + constexpr std::uint64_t bottom = static_cast(1) << 48; + constexpr std::uint64_t maxRange = static_cast(1) << 48; auto input_size = static_cast (inputIntVector_arg.size ()); @@ -353,8 +353,8 @@ pcl::StaticRangeCoder::decodeStreamToIntVector (std::istream& inputByteStream_ar std::vector& outputIntVector_arg) { // define range limits - const std::uint64_t top = static_cast (1) << 56; - const std::uint64_t bottom = static_cast (1) << 48; + constexpr std::uint64_t top = static_cast(1) << 56; + constexpr std::uint64_t bottom = static_cast(1) << 48; std::uint64_t frequencyTableSize; unsigned char frequencyTableByteSize; @@ -445,9 +445,9 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector& inputB DWord freq[257]; // define numerical limits - const DWord top = static_cast (1) << 24; - const DWord bottom = static_cast (1) << 16; - const DWord maxRange = static_cast (1) << 16; + constexpr DWord top = static_cast(1) << 24; + constexpr DWord bottom = static_cast(1) << 16; + constexpr DWord maxRange = static_cast(1) << 16; DWord low, range; @@ -543,8 +543,8 @@ pcl::StaticRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_a DWord freq[257]; // define range limits - const DWord top = static_cast (1) << 24; - const DWord bottom = static_cast (1) << 16; + constexpr DWord top = static_cast(1) << 24; + constexpr DWord bottom = static_cast(1) << 16; DWord low, range; DWord code; diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp index 50f82d8ba59..b4a0206b825 100644 --- a/io/tools/openni_pcd_recorder.cpp +++ b/io/tools/openni_pcd_recorder.cpp @@ -94,7 +94,7 @@ getTotalSystemMemory () const std::size_t BUFFER_SIZE = std::size_t (getTotalSystemMemory () / (640 * 480 * sizeof (pcl::PointXYZRGBA))); #else -const std::size_t BUFFER_SIZE = 200; +constexpr std::size_t BUFFER_SIZE = 200; #endif ////////////////////////////////////////////////////////////////////////////////////////// diff --git a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp index 542d5bae86b..29801e6f292 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp @@ -504,7 +504,7 @@ pcl::HarrisKeypoint3D::refineCorners (PointCloudOu Eigen::Matrix3f nnT; Eigen::Matrix3f NNT; Eigen::Vector3f NNTp; - const unsigned max_iterations = 10; + constexpr unsigned max_iterations = 10; #pragma omp parallel for \ default(none) \ shared(corners) \ diff --git a/keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp b/keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp index c9a5e100e6c..b5c43e957de 100644 --- a/keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp +++ b/keypoints/include/pcl/keypoints/impl/sift_keypoint.hpp @@ -128,7 +128,7 @@ pcl::SIFTKeypoint::detectKeypoints (PointCloudOut &output) cloud = temp; // Make sure the downsampled cloud still has enough points - const std::size_t min_nr_points = 25; + constexpr std::size_t min_nr_points = 25; if (cloud->size () < min_nr_points) break; @@ -261,7 +261,7 @@ pcl::SIFTKeypoint::findScaleSpaceExtrema ( const PointCloudIn &input, KdTree &tree, const Eigen::MatrixXf &diff_of_gauss, pcl::Indices &extrema_indices, std::vector &extrema_scales) { - const int k = 25; + constexpr int k = 25; pcl::Indices nn_indices (k); std::vector nn_dist (k); diff --git a/octree/include/pcl/octree/impl/octree_pointcloud.hpp b/octree/include/pcl/octree/impl/octree_pointcloud.hpp index 7bcd151661b..9966e4be463 100644 --- a/octree/include/pcl/octree/impl/octree_pointcloud.hpp +++ b/octree/include/pcl/octree/impl/octree_pointcloud.hpp @@ -475,7 +475,7 @@ pcl::octree::OctreePointCloud adoptBoundingBoxToPoint(const PointT& point_arg) { - const float minValue = std::numeric_limits::epsilon(); + constexpr float minValue = std::numeric_limits::epsilon(); // increase octree size until point fits into bounding box while (true) { @@ -679,7 +679,7 @@ void pcl::octree::OctreePointCloud:: getKeyBitSize() { - const float minValue = std::numeric_limits::epsilon(); + constexpr float minValue = std::numeric_limits::epsilon(); // find maximum key values for x, y, z const auto max_key_x = diff --git a/octree/include/pcl/octree/octree_search.h b/octree/include/pcl/octree/octree_search.h index a0bc8c6d891..c22fa85473e 100644 --- a/octree/include/pcl/octree/octree_search.h +++ b/octree/include/pcl/octree/octree_search.h @@ -534,7 +534,7 @@ class OctreePointCloudSearch unsigned char& a) const { // Account for division by zero when direction vector is 0.0 - const float epsilon = 1e-10f; + constexpr float epsilon = 1e-10f; if (direction.x() == 0.0) direction.x() = epsilon; if (direction.y() == 0.0) diff --git a/outofcore/include/pcl/outofcore/impl/octree_base.hpp b/outofcore/include/pcl/outofcore/impl/octree_base.hpp index e4bad953b67..257f620ea9d 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base.hpp @@ -209,7 +209,7 @@ namespace pcl { std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_); - const bool _FORCE_BB_CHECK = true; + constexpr bool _FORCE_BB_CHECK = true; std::uint64_t pt_added = root_node_->addDataToLeaf (p, _FORCE_BB_CHECK); @@ -569,7 +569,7 @@ namespace pcl std::unique_lock < std::shared_timed_mutex > lock (read_write_mutex_); - const int number_of_nodes = 1; + constexpr int number_of_nodes = 1; std::vector current_branch (number_of_nodes, static_cast(nullptr)); current_branch[0] = root_node_; diff --git a/outofcore/tools/outofcore_process.cpp b/outofcore/tools/outofcore_process.cpp index 9f966cb2db7..ac57843215a 100644 --- a/outofcore/tools/outofcore_process.cpp +++ b/outofcore/tools/outofcore_process.cpp @@ -70,8 +70,8 @@ using pcl::console::print_info; using octree_disk = OutofcoreOctreeBase<>; -const int OCTREE_DEPTH (0); -const int OCTREE_RESOLUTION (1); +constexpr int OCTREE_DEPTH (0); +constexpr int OCTREE_RESOLUTION(1); PCLPointCloud2::Ptr getCloudFromFile (boost::filesystem::path pcd_path) diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index bd7ae7a876f..16891698ffb 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -295,7 +295,7 @@ computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::ve { // code taken from OpenCV const int n = int (kernel_size); - const int SMALL_GAUSSIAN_SIZE = 7; + constexpr int SMALL_GAUSSIAN_SIZE = 7; static const float small_gaussian_tab[][SMALL_GAUSSIAN_SIZE] = { {1.f}, @@ -340,7 +340,7 @@ pcl::ColorGradientModality:: processInputData () { // compute gaussian kernel values - const std::size_t kernel_size = 7; + constexpr std::size_t kernel_size = 7; std::vector kernel_values; computeGaussianKernel (kernel_size, 0.0f, kernel_values); @@ -971,7 +971,7 @@ quantizeColorGradients () quantized_color_gradients_.resize (width, height); - const float angleScale = 16.0f/360.0f; + constexpr float angleScale = 16.0f / 360.0f; //float min_angle = std::numeric_limits::max (); //float max_angle = -std::numeric_limits::max (); diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index c78f4f130ce..3319533e7d6 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -140,7 +140,7 @@ pcl::features::ISMVoteList::findStrongestPeaks ( // heuristic: start from NUM_INIT_PTS different locations selected uniformly // on the votes. Intuitively, it is likely to get a good location in dense regions. - const int NUM_INIT_PTS = 100; + constexpr int NUM_INIT_PTS = 100; double SIGMA_DIST = in_sigma;// rule of thumb: 10% of the object radius const double FINAL_EPS = SIGMA_DIST / 100;// another heuristic @@ -1128,7 +1128,7 @@ pcl::ism::ImplicitShapeModelEstimation::simplifyCl grid.filter (temp_cloud); //extract indices of points from source cloud which are closest to grid points - const float max_value = std::numeric_limits::max (); + constexpr float max_value = std::numeric_limits::max (); const auto num_source_points = in_point_cloud->size (); const auto num_sample_points = temp_cloud.size (); @@ -1262,7 +1262,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe int flags, Eigen::MatrixXf& cluster_centers) { - const int spp_trials = 3; + constexpr int spp_trials = 3; std::size_t number_of_points = points_to_cluster.rows () > 1 ? points_to_cluster.rows () : points_to_cluster.cols (); int feature_dimension = points_to_cluster.rows () > 1 ? FeatureSize : 1; diff --git a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp index 7069437e2fc..04e3d9e9a1e 100644 --- a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp +++ b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp @@ -676,7 +676,7 @@ LineRGBD::refineDetectionsAlongDepth () } } - const std::size_t nr_bins = 1000; + constexpr std::size_t nr_bins = 1000; const float step_size = (max_depth - min_depth) / static_cast (nr_bins-1); std::vector depth_bins (nr_bins, 0); for (std::size_t row_index = start_y; row_index < end_y; ++row_index) diff --git a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h index a240aaa4997..c2aa6173262 100644 --- a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h +++ b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h @@ -329,9 +329,9 @@ namespace pcl { // 'p_obj' is the probability that given that the first sample point belongs to an object, // the second sample point will belong to the same object - const double p_obj = 0.25f; + constexpr double p_obj = 0.25f; // old version: p = p_obj*relative_obj_size_*fraction_of_pairs_in_hash_table_; - const double p = p_obj*relative_obj_size_; + const double p = p_obj * relative_obj_size_; if ( 1.0 - p <= 0.0 ) return 1; diff --git a/recognition/include/pcl/recognition/surface_normal_modality.h b/recognition/include/pcl/recognition/surface_normal_modality.h index 4651b501c8d..3e0c7866b77 100644 --- a/recognition/include/pcl/recognition/surface_normal_modality.h +++ b/recognition/include/pcl/recognition/surface_normal_modality.h @@ -192,15 +192,15 @@ namespace pcl delete[] lut; lut = new unsigned char[size_x*size_y*size_z]; - const int nr_normals = 8; + constexpr int nr_normals = 8; pcl::PointCloud::VectorType ref_normals (nr_normals); - const float normal0_angle = 40.0f * 3.14f / 180.0f; + constexpr float normal0_angle = 40.0f * 3.14f / 180.0f; ref_normals[0].x = std::cos (normal0_angle); ref_normals[0].y = 0.0f; ref_normals[0].z = -sinf (normal0_angle); - const float inv_nr_normals = 1.0f / static_cast (nr_normals); + constexpr float inv_nr_normals = 1.0f / static_cast(nr_normals); for (int normal_index = 1; normal_index < nr_normals; ++normal_index) { const float angle = 2.0f * static_cast (M_PI * normal_index * inv_nr_normals); @@ -749,7 +749,7 @@ pcl::SurfaceNormalModality::computeAndQuantizeSurfaceNormals2 () const int l_W = width; const int l_H = height; - const int l_r = 5; // used to be 7 + constexpr int l_r = 5; // used to be 7 //const int l_offset0 = -l_r - l_r * l_W; //const int l_offset1 = 0 - l_r * l_W; //const int l_offset2 = +l_r - l_r * l_W; @@ -774,8 +774,8 @@ pcl::SurfaceNormalModality::computeAndQuantizeSurfaceNormals2 () //const int l_offsetx = GRANULARITY / 2; //const int l_offsety = GRANULARITY / 2; - const int difference_threshold = 50; - const int distance_threshold = 2000; + constexpr int difference_threshold = 50; + constexpr int distance_threshold = 2000; //const double scale = 1000.0; //const double difference_threshold = 0.05 * scale; @@ -1027,7 +1027,7 @@ pcl::SurfaceNormalModality::extractFeatures (const MaskMap & mask, float weights[8] = {0,0,0,0,0,0,0,0}; - const std::size_t off = 4; + constexpr std::size_t off = 4; for (std::size_t row_index = off; row_index < height-off; ++row_index) { for (std::size_t col_index = off; col_index < width-off; ++col_index) @@ -1297,7 +1297,7 @@ pcl::SurfaceNormalModality::extractAllFeatures ( float weights[8] = {0,0,0,0,0,0,0,0}; - const std::size_t off = 4; + constexpr std::size_t off = 4; for (std::size_t row_index = off; row_index < height-off; ++row_index) { for (std::size_t col_index = off; col_index < width-off; ++col_index) diff --git a/registration/include/pcl/registration/bfgs.h b/registration/include/pcl/registration/bfgs.h index dad1d542c4a..1d35fa2d7e8 100644 --- a/registration/include/pcl/registration/bfgs.h +++ b/registration/include/pcl/registration/bfgs.h @@ -28,7 +28,7 @@ class PolynomialSolver<_Scalar, 2> : public PolynomialSolverBase<_Scalar, 2> { void compute(const OtherPolynomial& poly, bool& hasRealRoot) { - const Scalar ZERO(0); + constexpr Scalar ZERO(0); Scalar a2(2 * poly[2]); assert(ZERO != poly[poly.size() - 1]); Scalar discriminant((poly[1] * poly[1]) - (4 * poly[0] * poly[2])); diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp index 21883483617..4b4bd0b2cfe 100644 --- a/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp +++ b/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp @@ -178,7 +178,7 @@ CorrespondenceRejectorPoly::findThresholdOtsu( const std::vector& histogram) { // Precision - const double eps = std::numeric_limits::epsilon(); + constexpr double eps = std::numeric_limits::epsilon(); // Histogram dimension const int nbins = static_cast(histogram.size()); diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index d85c073a03a..51bb956783a 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -290,8 +290,8 @@ pcl::registration::FPCSInitialAlignment::computeStepLengt // The Search Algorithm for T(mu) [More, Thuente 1994] - const int max_step_iterations = 10; + constexpr int max_step_iterations = 10; int step_iterations = 0; // Sufficient decrease constant, Equation 1.1 [More, Thuete 1994] - const double mu = 1.e-4; + constexpr double mu = 1.e-4; // Curvature condition constant, Equation 1.2 [More, Thuete 1994] - const double nu = 0.9; + constexpr double nu = 0.9; // Initial endpoints of Interval I, double a_l = 0, a_u = 0; diff --git a/sample_consensus/include/pcl/sample_consensus/method_types.h b/sample_consensus/include/pcl/sample_consensus/method_types.h index 0eb0e472478..568deb36ded 100644 --- a/sample_consensus/include/pcl/sample_consensus/method_types.h +++ b/sample_consensus/include/pcl/sample_consensus/method_types.h @@ -42,11 +42,11 @@ namespace pcl { - const static int SAC_RANSAC = 0; - const static int SAC_LMEDS = 1; - const static int SAC_MSAC = 2; - const static int SAC_RRANSAC = 3; - const static int SAC_RMSAC = 4; - const static int SAC_MLESAC = 5; - const static int SAC_PROSAC = 6; + constexpr int SAC_RANSAC = 0; + constexpr int SAC_LMEDS = 1; + constexpr int SAC_MSAC = 2; + constexpr int SAC_RRANSAC = 3; + constexpr int SAC_RMSAC = 4; + constexpr int SAC_MLESAC = 5; + constexpr int SAC_PROSAC = 6; } diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_array_defs.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_array_defs.h index 441ad59d3a0..533285a80a6 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_array_defs.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_array_defs.h @@ -842,7 +842,7 @@ int ON_ClassArray::NewCapacity() const // Reserve() size and then wasting gigabytes of memory. // cap_size = 128 MB on 32-bit os, 256 MB on 64 bit os - const std::size_t cap_size = 32*sizeof(void*)*1024*1024; + constexpr std::size_t cap_size = 32*sizeof(void*)*1024*1024; if (m_count*sizeof(T) <= cap_size || m_count < 8) return ((m_count <= 2) ? 4 : 2*m_count); diff --git a/surface/include/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp b/surface/include/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp index 187eba0e5ca..e48b0da4374 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp +++ b/surface/include/pcl/surface/3rdparty/poisson4/multi_grid_octree_data.hpp @@ -48,9 +48,9 @@ namespace pcl namespace poisson { - const Real MATRIX_ENTRY_EPSILON = Real(0); - const Real EPSILON=Real(1e-6); - const Real ROUND_EPS=Real(1e-5); + constexpr Real MATRIX_ENTRY_EPSILON = Real(0); + constexpr Real EPSILON=Real(1e-6); + constexpr Real ROUND_EPS = Real(1e-5); void atomicOr(volatile int& dest, int value) { @@ -736,7 +736,7 @@ namespace pcl Real w; node->centerAndWidth( center , w ); width=w; - const double SAMPLE_SCALE = 1. / ( 0.125 * 0.125 + 0.75 * 0.75 + 0.125 * 0.125 ); + constexpr double SAMPLE_SCALE = 1. / ( 0.125 * 0.125 + 0.75 * 0.75 + 0.125 * 0.125 ); for( int i=0 ; i result = Eigen::Matrix::Zero (); Eigen::Matrix error = Eigen::Matrix::Zero (); - const Scalar epsilon = 1e-5f; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-5f; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -124,8 +124,8 @@ TEST (PCL, InverseGeneral3x3d) CMatrix c_inverse = CMatrix::Zero (); Eigen::Matrix result = Eigen::Matrix::Zero (); Eigen::Matrix error = Eigen::Matrix::Zero (); - const Scalar epsilon = 1e-13; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-13; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -183,8 +183,8 @@ TEST (PCL, InverseSymmetric3x3f) CMatrix c_inverse = CMatrix::Zero (); Eigen::Matrix result = Eigen::Matrix::Zero (); Eigen::Matrix error = Eigen::Matrix::Zero (); - const Scalar epsilon = 1e-5f; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-5f; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -248,8 +248,8 @@ TEST (PCL, InverseSymmetric3x3d) CMatrix c_inverse = CMatrix::Zero (); Eigen::Matrix result = Eigen::Matrix::Zero (); Eigen::Matrix error = Eigen::Matrix::Zero (); - const Scalar epsilon = 1e-13; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-13; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -314,8 +314,8 @@ TEST (PCL, Inverse2x2f) CMatrix c_inverse = CMatrix::Zero (); Eigen::Matrix result = Eigen::Matrix::Zero (); Eigen::Matrix error = Eigen::Matrix::Zero (); - const Scalar epsilon = 1e-6f; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-6f; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -372,8 +372,8 @@ TEST (PCL, Inverse2x2d) CMatrix c_inverse = CMatrix::Zero (); Eigen::Matrix result; Eigen::Matrix error; - const Scalar epsilon = 1e-15; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1e-15; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -479,8 +479,8 @@ TEST (PCL, eigen22d) Eigen::Matrix c_result; Eigen::Matrix c_error; - const Scalar epsilon = 1.25e-14; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 1.25e-14; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -537,8 +537,8 @@ TEST (PCL, eigen22f) Eigen::Matrix c_result; Eigen::Matrix c_error; - const Scalar epsilon = 3.1e-5f; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 3.1e-5f; + constexpr unsigned iterations = 1000000; // test floating point row-major : row-major for (unsigned idx = 0; idx < iterations; ++idx) @@ -676,8 +676,8 @@ TEST (PCL, eigen33d) Eigen::Matrix c_result; Eigen::Matrix c_error; - const Scalar epsilon = 2e-5; - const unsigned iterations = 1000000; + constexpr Scalar epsilon = 2e-5; + constexpr unsigned iterations = 1000000; // special case r_matrix = Eigen::Matrix(3, 2, 1).asDiagonal(); @@ -751,7 +751,7 @@ TEST (PCL, eigen33f) Eigen::Matrix c_result; Eigen::Matrix c_error; - const Scalar epsilon = 1e-3f; + constexpr Scalar epsilon = 1e-3f; constexpr unsigned iterations = 1000000; unsigned r_fail_count = 0; @@ -1128,9 +1128,9 @@ TEST (PCL, getTransFromUnitVectors) TEST (PCL, getTransformation) { - const float rot_x = 2.8827f; - const float rot_y = -0.31190f; - const float rot_z = -0.93058f; + constexpr float rot_x = 2.8827f; + constexpr float rot_y = -0.31190f; + constexpr float rot_z = -0.93058f; Eigen::Affine3f affine; pcl::getTransformation (0, 0, 0, rot_x, rot_y, rot_z, affine); @@ -1142,12 +1142,12 @@ TEST (PCL, getTransformation) TEST (PCL, getTranslationAndEulerAngles) { - const float trans_x = 0.1f; - const float trans_y = 0.2f; - const float trans_z = 0.3f; - const float rot_x = 2.8827f; - const float rot_y = -0.31190f; - const float rot_z = -0.93058f; + constexpr float trans_x = 0.1f; + constexpr float trans_y = 0.2f; + constexpr float trans_z = 0.3f; + constexpr float rot_x = 2.8827f; + constexpr float rot_y = -0.31190f; + constexpr float rot_z = -0.93058f; Eigen::Affine3f affine; pcl::getTransformation (trans_x, trans_y, trans_z, rot_x, rot_y, rot_z, affine); diff --git a/test/common/test_macros.cpp b/test/common/test_macros.cpp index 7fc62e70cb3..018ce2797ec 100644 --- a/test/common/test_macros.cpp +++ b/test/common/test_macros.cpp @@ -67,7 +67,7 @@ TEST(MACROS, expect_near_vectors_macro) { v1.clear (); v2.clear (); - const static float epsilon = 1e-5f; + constexpr float epsilon = 1e-5f; for (std::size_t i = 0; i < 3; i++) { float val = static_cast (i) * 1.5f; diff --git a/test/common/test_parse.cpp b/test/common/test_parse.cpp index 7ec6da1d038..b529562a84d 100644 --- a/test/common/test_parse.cpp +++ b/test/common/test_parse.cpp @@ -51,7 +51,7 @@ TEST (PCL, parse_double) const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr}; const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr}; const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr}; - const int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; + constexpr int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; int index = -1; double value = 0; @@ -79,7 +79,7 @@ TEST (PCL, parse_float) const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr}; const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr}; const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr}; - const int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; + constexpr int argc = static_cast(sizeof(argv_1) / sizeof(argv_1[0])) - 1; int index = -1; float value = 0; @@ -107,7 +107,7 @@ TEST (PCL, parse_longint) const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr}; const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr}; const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr}; - const int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; + constexpr int argc = static_cast(sizeof(argv_1) / sizeof(argv_1[0])) - 1; int index = -1; long int value = 0; @@ -135,7 +135,7 @@ TEST (PCL, parse_unsignedint) const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr}; const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr}; const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr}; - const int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; + constexpr int argc = static_cast(sizeof(argv_1) / sizeof(argv_1[0])) - 1; int index = -1; unsigned int value = 53; @@ -163,7 +163,7 @@ TEST (PCL, parse_int) const char* argv_1[] = { &arg0[0], &arg1[0], &arg2_1[0], nullptr}; const char* argv_2[] = { &arg0[0], &arg1[0], &arg2_2[0], nullptr}; const char* argv_3[] = { &arg0[0], &arg1[0], &arg2_3[0], nullptr}; - const int argc = static_cast (sizeof (argv_1)/sizeof (argv_1[0])) - 1; + constexpr int argc = static_cast(sizeof(argv_1) / sizeof(argv_1[0])) - 1; int index = -1; int value = 0; diff --git a/test/common/test_polygon_mesh.cpp b/test/common/test_polygon_mesh.cpp index d03038ab192..f97c1a6807d 100644 --- a/test/common/test_polygon_mesh.cpp +++ b/test/common/test_polygon_mesh.cpp @@ -66,7 +66,7 @@ TEST(PolygonMesh, concatenate_header) TEST(PolygonMesh, concatenate_cloud) { PointCloud cloud_template; - const std::size_t size = 10 * 480; + constexpr std::size_t size = 10 * 480; cloud_template.width = 10; cloud_template.height = 480; @@ -91,7 +91,7 @@ TEST(PolygonMesh, concatenate_cloud) TEST(PolygonMesh, concatenate_vertices) { - const std::size_t size = 15; + constexpr std::size_t size = 15; PolygonMesh test, dummy; // The algorithm works regardless of the organization. diff --git a/test/common/test_spring.cpp b/test/common/test_spring.cpp index ffb1de669e7..f1474df076e 100644 --- a/test/common/test_spring.cpp +++ b/test/common/test_spring.cpp @@ -44,8 +44,8 @@ using namespace pcl; using namespace pcl::test; PointCloud::Ptr cloud_ptr (new PointCloud (4, 5)); -const std::size_t size = 5 * 4; -const int amount = 2; +constexpr std::size_t size = 5 * 4; +constexpr int amount = 2; // TEST (PointCloudSpring, vertical) // { diff --git a/test/common/test_wrappers.cpp b/test/common/test_wrappers.cpp index c446487472b..676f92cdd25 100644 --- a/test/common/test_wrappers.cpp +++ b/test/common/test_wrappers.cpp @@ -46,7 +46,7 @@ using namespace pcl; using namespace pcl::test; PointCloud cloud; -const std::size_t size = 10 * 480; +constexpr std::size_t size = 10 * 480; TEST (PointCloud, size) { diff --git a/test/features/test_flare_estimation.cpp b/test/features/test_flare_estimation.cpp index 7e9746ca256..320cbf4c76c 100644 --- a/test/features/test_flare_estimation.cpp +++ b/test/features/test_flare_estimation.cpp @@ -62,7 +62,7 @@ TEST (PCL, FLARELocalReferenceFrameEstimation) pcl::PointCloud::Ptr normals (new pcl::PointCloud ()); pcl::PointCloud bunny_LRF; - const float mesh_res = 0.005f; + constexpr float mesh_res = 0.005f; // Compute normals pcl::NormalEstimation ne; @@ -159,8 +159,8 @@ main (int argc, char** argv) tree->setInputCloud (cloud); //create and set sampled point cloud for computation of X axis - const float sampling_perc = 0.2f; - const float sampling_incr = 1.0f / sampling_perc; + constexpr float sampling_perc = 0.2f; + constexpr float sampling_incr = 1.0f / sampling_perc; sampled_cloud.reset (new pcl::PointCloud ()); diff --git a/test/features/test_gradient_estimation.cpp b/test/features/test_gradient_estimation.cpp index 7127c13b063..589b42fb883 100644 --- a/test/features/test_gradient_estimation.cpp +++ b/test/features/test_gradient_estimation.cpp @@ -113,7 +113,7 @@ TEST (PCL, IntensityGradientEstimation) float gz = (-nz * nx) * tmpx + (-nz * ny) * tmpy + (1 - nz * nz) * tmpz; // Compare the estimates to the derived values. - const float tolerance = 0.11f; + constexpr float tolerance = 0.11f; EXPECT_NEAR (g_est[0], gx, tolerance); EXPECT_NEAR (g_est[1], gy, tolerance); EXPECT_NEAR (g_est[2], gz, tolerance); diff --git a/test/features/test_ii_normals.cpp b/test/features/test_ii_normals.cpp index 73450329792..914def1f8cb 100644 --- a/test/features/test_ii_normals.cpp +++ b/test/features/test_ii_normals.cpp @@ -55,10 +55,10 @@ IntegralImageNormalEstimation ne; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST(PCL, IntegralImage1D) { - const unsigned width = 640; - const unsigned height = 480; - const unsigned max_window_size = 5; - const unsigned min_window_size = 1; + constexpr unsigned width = 640; + constexpr unsigned height = 480; + constexpr unsigned max_window_size = 5; + constexpr unsigned min_window_size = 1; IntegralImage2D integral_image1(true); // calculate second order IntegralImage2D integral_image2(false);// calculate just first order (other if branch) @@ -268,10 +268,10 @@ TEST(PCL, IntegralImage1D) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST(PCL, IntegralImage3D) { - const unsigned width = 640; - const unsigned height = 480; - const unsigned max_window_size = 5; - const unsigned min_window_size = 1; + constexpr unsigned width = 640; + constexpr unsigned height = 480; + constexpr unsigned max_window_size = 5; + constexpr unsigned min_window_size = 1; IntegralImage2D integral_image3(true); unsigned element_stride = 4; unsigned row_stride = width * element_stride + 1; diff --git a/test/features/test_pfh_estimation.cpp b/test/features/test_pfh_estimation.cpp index 98673c4139a..f63450ab2cb 100644 --- a/test/features/test_pfh_estimation.cpp +++ b/test/features/test_pfh_estimation.cpp @@ -476,7 +476,7 @@ TEST (PCL, GFPFH) PointCloud::Ptr cloud (new PointCloud()); - const unsigned num_classes = 3; + constexpr unsigned num_classes = 3; // Build a cubic shape with a hole and changing labels. for (int z = -10; z < 10; ++z) diff --git a/test/filters/test_crop_hull.cpp b/test/filters/test_crop_hull.cpp index ebe169ae65c..17e87e06f0e 100644 --- a/test/filters/test_crop_hull.cpp +++ b/test/filters/test_crop_hull.cpp @@ -58,7 +58,7 @@ createTestDataSuite( std::function outside_point_generator) { std::vector test_data_suite; - size_t const chunk_size = 1000; + constexpr size_t 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); diff --git a/test/filters/test_farthest_point_sampling.cpp b/test/filters/test_farthest_point_sampling.cpp index 9606c07eb7e..e1d0a961993 100644 --- a/test/filters/test_farthest_point_sampling.cpp +++ b/test/filters/test_farthest_point_sampling.cpp @@ -19,8 +19,8 @@ using namespace pcl; PointCloud::Ptr cloud_in (new PointCloud); -const static int CLOUD_SIZE = 10; -const static int SAMPLE_SIZE = CLOUD_SIZE -1; +constexpr int CLOUD_SIZE = 10; +constexpr int SAMPLE_SIZE = CLOUD_SIZE - 1; std::vector x_values; TEST (FarthestPointSampling, farthest_point_sampling) diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index 4932be95afe..15fdea56ddb 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -2302,7 +2302,7 @@ TEST (NormalRefinement, Filters) const float vp_z = cloud_organized_nonan.sensor_origin_[2]; // Search parameters - const int k = 5; + constexpr int k = 5; std::vector k_indices; std::vector > k_sqr_distances; diff --git a/test/filters/test_uniform_sampling.cpp b/test/filters/test_uniform_sampling.cpp index f9410a9e04d..50a3446c036 100644 --- a/test/filters/test_uniform_sampling.cpp +++ b/test/filters/test_uniform_sampling.cpp @@ -44,7 +44,7 @@ TEST(UniformSampling, extractRemovedIndices) { using namespace pcl::common; - const int SEED = 1234; + constexpr int SEED = 1234; CloudGenerator> generator; UniformGenerator::Parameters x_params(0, 1, SEED + 1); generator.setParametersForX(x_params); diff --git a/test/geometry/test_iterator.cpp b/test/geometry/test_iterator.cpp index 0ff5cbc6395..4e8eda16ed8 100644 --- a/test/geometry/test_iterator.cpp +++ b/test/geometry/test_iterator.cpp @@ -245,8 +245,8 @@ TEST (PCL, LineIterator8NeighborsGeneral) unsigned center_y = 50; unsigned length = 45; - const unsigned angular_resolution = 180; - float d_alpha = float(M_PI / angular_resolution); + constexpr unsigned angular_resolution = 180; + constexpr float d_alpha = float(M_PI / angular_resolution); for (unsigned idx = 0; idx < angular_resolution; ++idx) { auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5); @@ -269,8 +269,8 @@ TEST (PCL, LineIterator4NeighborsGeneral) unsigned center_y = 50; unsigned length = 45; - const unsigned angular_resolution = 360; - float d_alpha = float(2.0 * M_PI / angular_resolution); + constexpr unsigned angular_resolution = 360; + constexpr float d_alpha = float(2.0 * M_PI / angular_resolution); for (unsigned idx = 0; idx < angular_resolution; ++idx) { auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5); diff --git a/test/geometry/test_mesh_common_functions.h b/test/geometry/test_mesh_common_functions.h index f61ed0a86a7..6f7291f9ad9 100644 --- a/test/geometry/test_mesh_common_functions.h +++ b/test/geometry/test_mesh_common_functions.h @@ -46,8 +46,8 @@ //////////////////////////////////////////////////////////////////////////////// // Abort circulating if the number of evaluations is too damn high. -const unsigned int max_number_polygon_vertices = 100; -const unsigned int max_number_boundary_vertices = 100; +constexpr unsigned int max_number_polygon_vertices = 100; +constexpr unsigned int max_number_boundary_vertices = 100; //////////////////////////////////////////////////////////////////////////////// diff --git a/test/geometry/test_quad_mesh.cpp b/test/geometry/test_quad_mesh.cpp index 0a958f6e215..3bafedb1827 100644 --- a/test/geometry/test_quad_mesh.cpp +++ b/test/geometry/test_quad_mesh.cpp @@ -221,7 +221,7 @@ TYPED_TEST (TestQuadMesh, OneQuad) TYPED_TEST (TestQuadMesh, NineQuads) { using Mesh = typename TestFixture::Mesh; - const int int_max = std::numeric_limits ::max (); + constexpr int int_max = std::numeric_limits::max(); // Order // - - - // diff --git a/test/gpu/octree/performance.cpp b/test/gpu/octree/performance.cpp index 0d72a55313e..794f5e17a2b 100644 --- a/test/gpu/octree/performance.cpp +++ b/test/gpu/octree/performance.cpp @@ -131,7 +131,7 @@ TEST(PCL_OctreeGPU, performance) // build opencv octree #ifdef HAVE_OPENCV cv::Octree octree_opencv; - const static int opencv_octree_points_per_leaf = 32; + constexpr int opencv_octree_points_per_leaf = 32; std::vector opencv_points(data.size()); std::transform(data.cbegin(), data.cend(), opencv_points.begin(), DataGenerator::ConvPoint()); @@ -143,7 +143,7 @@ TEST(PCL_OctreeGPU, performance) //// Radius search performance /// - const int max_answers = 500; + constexpr int max_answers = 500; float dist; //host buffers diff --git a/test/gpu/octree/test_host_radius_search.cpp b/test/gpu/octree/test_host_radius_search.cpp index a16c6d59a23..2fd7b175c2f 100644 --- a/test/gpu/octree/test_host_radius_search.cpp +++ b/test/gpu/octree/test_host_radius_search.cpp @@ -136,7 +136,7 @@ TEST(PCL_OctreeGPU, hostRadiusSearch) int main (int argc, char** argv) { - const int device = 0; + constexpr int device = 0; pcl::gpu::setDevice(device); pcl::gpu::printShortCudaDeviceInfo(device); testing::InitGoogleTest (&argc, argv); diff --git a/test/gpu/octree/test_knn_search.cpp b/test/gpu/octree/test_knn_search.cpp index c21ba65c640..d5c5a36c99a 100644 --- a/test/gpu/octree/test_knn_search.cpp +++ b/test/gpu/octree/test_knn_search.cpp @@ -81,8 +81,8 @@ TEST(PCL_OctreeGPU, exactNeighbourSearch) data.shared_radius = data.cube_size/30.f; data.printParams(); - const float host_octree_resolution = 25.f; - const int k = 1; // only this is supported + constexpr float host_octree_resolution = 25.f; + constexpr int k = 1; // only this is supported //generate data(); diff --git a/test/gpu/octree/test_radius_search.cpp b/test/gpu/octree/test_radius_search.cpp index 9288760311a..c9ad5caecab 100644 --- a/test/gpu/octree/test_radius_search.cpp +++ b/test/gpu/octree/test_radius_search.cpp @@ -68,7 +68,7 @@ TEST(PCL_OctreeGPU, batchRadiusSearch) data.shared_radius = data.cube_size/30.f; data.printParams(); - const int max_answers = 333; + constexpr int max_answers = 333; //generate data(); diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 091e8ed82f0..1809f2c1835 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -124,7 +124,7 @@ 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; + constexpr double MAX_XYZ = 1.0; srand(static_cast (time(nullptr))); // iterate over all pre-defined compression profiles for (int compression_profile = pcl::io::LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR; diff --git a/test/io/test_ply_mesh_io.cpp b/test/io/test_ply_mesh_io.cpp index fae86a9324f..8525f8d7491 100644 --- a/test/io/test_ply_mesh_io.cpp +++ b/test/io/test_ply_mesh_io.cpp @@ -293,8 +293,8 @@ TEST (PCL, PLYPolygonMeshSpecificFieldOrder) add_field(mesh.cloud.fields, "rgba", 24, pcl::PCLPointField::PointFieldTypes::UINT32); mesh.cloud.height = mesh.cloud.width = 1; mesh.cloud.data.resize(28); - const float x = 0.0, y = 1.0, z = 2.0, normal_x = 1.0, normal_y = 0.0, normal_z = 0.0; - const std::uint32_t rgba = 0x326496; + constexpr float x = 0.0, y = 1.0, z = 2.0, normal_x = 1.0, normal_y = 0.0, normal_z = 0.0; + constexpr std::uint32_t rgba = 0x326496; memcpy(&mesh.cloud.data[0], &x, sizeof(float)); memcpy(&mesh.cloud.data[4], &y, sizeof(float)); memcpy(&mesh.cloud.data[8], &z, sizeof(float)); diff --git a/test/io/test_range_coder.cpp b/test/io/test_range_coder.cpp index c17fd738c11..543a55ae197 100644 --- a/test/io/test_range_coder.cpp +++ b/test/io/test_range_coder.cpp @@ -58,7 +58,7 @@ TEST (PCL, Adaptive_Range_Coder_Test) unsigned long readByteLen; // vector size - const unsigned int vectorSize = 10000; + constexpr unsigned int vectorSize = 10000; inputData.resize(vectorSize); outputData.resize(vectorSize); diff --git a/test/kdtree/test_kdtree.cpp b/test/kdtree/test_kdtree.cpp index 903b889c5ed..8f6831b5246 100644 --- a/test/kdtree/test_kdtree.cpp +++ b/test/kdtree/test_kdtree.cpp @@ -242,7 +242,7 @@ TEST (PCL, KdTreeFLANN_setPointRepresentation) MyPoint p (50.0f, 50.0f, 50.0f); // Find k nearest neighbors - const int k = 10; + constexpr int k = 10; pcl::Indices k_indices (k); std::vector k_distances (k); kdtree.nearestKSearch (p, k, k_indices, k_distances); diff --git a/test/keypoints/test_iss_3d.cpp b/test/keypoints/test_iss_3d.cpp index eff8cb42c9b..14bbe71772a 100644 --- a/test/keypoints/test_iss_3d.cpp +++ b/test/keypoints/test_iss_3d.cpp @@ -74,7 +74,7 @@ TEST (PCL, ISSKeypoint3D_WBE) // // Compare to previously validated output // - const std::size_t correct_nr_keypoints = 6; + constexpr std::size_t correct_nr_keypoints = 6; const float correct_keypoints[correct_nr_keypoints][3] = { // { x, y, z} @@ -130,7 +130,7 @@ TEST (PCL, ISSKeypoint3D_BE) // // Compare to previously validated output // - const std::size_t correct_nr_keypoints = 5; + constexpr std::size_t correct_nr_keypoints = 5; const float correct_keypoints[correct_nr_keypoints][3] = { // { x, y, z} diff --git a/test/keypoints/test_keypoints.cpp b/test/keypoints/test_keypoints.cpp index a65887826c1..a845d396970 100644 --- a/test/keypoints/test_keypoints.cpp +++ b/test/keypoints/test_keypoints.cpp @@ -99,7 +99,7 @@ TEST (PCL, SIFTKeypoint) ASSERT_EQ (keypoints.height, 1); // Compare to previously validated output - const std::size_t correct_nr_keypoints = 5; + constexpr std::size_t correct_nr_keypoints = 5; const float correct_keypoints[correct_nr_keypoints][4] = { // { x, y, z, scale } @@ -123,14 +123,14 @@ TEST (PCL, SIFTKeypoint) TEST (PCL, SIFTKeypoint_radiusSearch) { - const int nr_scales_per_octave = 3; - const float scale = 0.02f; + constexpr int nr_scales_per_octave = 3; + constexpr float scale = 0.02f; KdTreeFLANN::Ptr tree_ (new KdTreeFLANN); auto cloud = cloud_xyzi->makeShared (); ApproximateVoxelGrid voxel_grid; - const float s = 1.0 * scale; + constexpr float s = 1.0 * scale; voxel_grid.setLeafSize (s, s, s); voxel_grid.setInputCloud (cloud); voxel_grid.filter (*cloud); @@ -138,12 +138,11 @@ TEST (PCL, SIFTKeypoint_radiusSearch) const PointCloud & input = *cloud; KdTreeFLANN & tree = *tree_; - const float base_scale = scale; std::vector scales (nr_scales_per_octave + 3); for (int i_scale = 0; i_scale <= nr_scales_per_octave + 2; ++i_scale) { - scales[i_scale] = base_scale * std::pow (2.0f, static_cast (i_scale-1) / nr_scales_per_octave); + scales[i_scale] = scale * std::pow (2.0f, static_cast (i_scale-1) / nr_scales_per_octave); } Eigen::MatrixXf diff_of_gauss; @@ -151,9 +150,9 @@ TEST (PCL, SIFTKeypoint_radiusSearch) std::vector nn_dist; diff_of_gauss.resize (input.size (), scales.size () - 1); - const float max_radius = 0.10f; + constexpr float max_radius = 0.10f; - const std::size_t i_point = 500; + constexpr std::size_t i_point = 500; tree.radiusSearch (i_point, max_radius, nn_indices, nn_dist); // Are they all unique? diff --git a/test/octree/test_octree.cpp b/test/octree/test_octree.cpp index e1502480a5a..128ebb2266a 100644 --- a/test/octree/test_octree.cpp +++ b/test/octree/test_octree.cpp @@ -555,7 +555,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_Test) srand (static_cast (time (nullptr))); - const unsigned int test_runs = 20; + constexpr unsigned int test_runs = 20; for (unsigned int j = 0; j < test_runs; j++) { @@ -636,7 +636,7 @@ TEST (PCL, Octree2Buf_Base_Double_Buffering_XOR_Test) srand (static_cast (time (nullptr))); - const unsigned int test_runs = 15; + constexpr unsigned int test_runs = 15; for (unsigned int j = 0; j < test_runs; j++) { @@ -1616,10 +1616,10 @@ TEST (PCL, Octree_Pointcloud_Adjacency) TEST (PCL, Octree_Pointcloud_Bounds) { - const double SOME_RESOLUTION (10 + 1/3.0); - const int SOME_DEPTH (4); - const double DESIRED_MAX = ((1< tree (SOME_RESOLUTION); tree.defineBoundingBox (DESIRED_MIN, DESIRED_MIN, DESIRED_MIN, DESIRED_MAX, DESIRED_MAX, DESIRED_MAX); @@ -1630,8 +1630,8 @@ TEST (PCL, Octree_Pointcloud_Bounds) ASSERT_GE (max_x, DESIRED_MAX); ASSERT_GE (DESIRED_MIN, min_x); - const double LARGE_MIN = 1e7-45*SOME_RESOLUTION; - const double LARGE_MAX = 1e7-5*SOME_RESOLUTION; + constexpr double LARGE_MIN = 1e7 - 45 * SOME_RESOLUTION; + constexpr double LARGE_MAX = 1e7 - 5 * SOME_RESOLUTION; tree.defineBoundingBox (LARGE_MIN, LARGE_MIN, LARGE_MIN, LARGE_MAX, LARGE_MAX, LARGE_MAX); tree.getBoundingBox (min_x, min_y, min_z, max_x, max_y, max_z); const auto depth = tree.getTreeDepth (); diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index 83d23565aa6..c44e042dff3 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -1259,7 +1259,7 @@ struct OctreePointCloudAdjacencyBeginEndIteratorsTest // Generate Point Cloud typename PointCloudT::Ptr cloud (new PointCloudT (100, 1)); - const float max_inv = 1.f / float (RAND_MAX); + constexpr float max_inv = 1.f / float (RAND_MAX); for (std::size_t i = 0; i < 100; ++i) { const PointT pt (10.f * (float (std::rand ()) * max_inv - .5f), @@ -1484,7 +1484,7 @@ struct OctreePointCloudSierpinskiTest std::vector > voxels (generateSierpinskiVoxelExtremities (v_min, v_max, depth_)); // The number of points in each voxel - unsigned int total_nb_pt = 100000; + constexpr unsigned int total_nb_pt = 100000; unsigned int nb_pt_in_voxel = total_nb_pt / pow (4, depth_); // Replicable results @@ -1493,7 +1493,7 @@ struct OctreePointCloudSierpinskiTest // Fill the point cloud for (const auto& voxel : voxels) { - const static float eps = std::numeric_limits::epsilon (); + constexpr float eps = std::numeric_limits::epsilon (); double x_min = voxel.first.x () + eps; double y_min = voxel.first.y () + eps; double z_min = voxel.first.z () + eps; diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index 0abba40b025..8a890212bc0 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -67,7 +67,7 @@ using namespace pcl::outofcore; // For doing exhaustive checks this is set low remove those, and this can be // set much higher -const static std::uint64_t numPts (10000); +constexpr std::uint64_t numPts (10000); constexpr std::uint32_t rngseed = 0xAAFF33DD; @@ -702,7 +702,7 @@ TEST_F (OutofcoreTest, PointCloud2_Constructors) const Eigen::Vector3d min (-100.1, -100.1, -100.1); const Eigen::Vector3d max (100.1, 100.1, 100.1); - const std::uint64_t depth = 2; + constexpr std::uint64_t depth = 2; //create a point cloud pcl::PointCloud::Ptr test_cloud (new pcl::PointCloud ()); @@ -833,7 +833,7 @@ TEST_F (OutofcoreTest, PointCloud2_QueryBoundingBox) const Eigen::Vector3d min (-100.1, -100.1, -100.1); const Eigen::Vector3d max (100.1, 100.1, 100.1); - const std::uint64_t depth = 2; + constexpr std::uint64_t depth = 2; //create a point cloud pcl::PointCloud::Ptr test_cloud (new pcl::PointCloud ()); @@ -885,7 +885,7 @@ TEST_F (OutofcoreTest, PointCloud2_Query) const Eigen::Vector3d min (-100.1, -100.1, -100.1); const Eigen::Vector3d max (100.1, 100.1, 100.1); - const std::uint64_t depth = 2; + constexpr std::uint64_t depth = 2; //create a point cloud pcl::PointCloud::Ptr test_cloud (new pcl::PointCloud ()); diff --git a/test/registration/test_fpcs_ia_data.h b/test/registration/test_fpcs_ia_data.h index bd80457df13..ec3c8229e49 100644 --- a/test/registration/test_fpcs_ia_data.h +++ b/test/registration/test_fpcs_ia_data.h @@ -1,9 +1,9 @@ #pragma once -const int nr_threads = 1; -const float approx_overlap = 0.9f; -const float delta = 1.f; -const int nr_samples = 100; +constexpr int nr_threads = 1; +constexpr float approx_overlap = 0.9f; +constexpr float delta = 1.f; +constexpr int nr_samples = 100; const float transform_from_fpcs [4][4] = { { -0.0019f, 0.8266f, -0.5628f, -0.0378f }, diff --git a/test/registration/test_kfpcs_ia.cpp b/test/registration/test_kfpcs_ia.cpp index 3148e2f64f5..ed709afc7b0 100644 --- a/test/registration/test_kfpcs_ia.cpp +++ b/test/registration/test_kfpcs_ia.cpp @@ -73,7 +73,7 @@ TEST (PCL, KFPCSInitialAlignment) kfpcs_ia.setScoreThreshold (abort_score); // repeat alignment 2 times to increase probability to ~99.99% - const float max_angle3d = 0.1745f, max_translation3d = 1.f; + constexpr float max_angle3d = 0.1745f, max_translation3d = 1.f; float angle3d = std::numeric_limits::max(), translation3d = std::numeric_limits::max(); for (int i = 0; i < 2; i++) { diff --git a/test/registration/test_kfpcs_ia_data.h b/test/registration/test_kfpcs_ia_data.h index 59a29d5b8fe..4b7e8905630 100644 --- a/test/registration/test_kfpcs_ia_data.h +++ b/test/registration/test_kfpcs_ia_data.h @@ -1,9 +1,9 @@ #pragma once -const int nr_threads = 1; -const float voxel_size = 0.1f; -const float approx_overlap = 0.9f; -const float abort_score = 0.0f; +constexpr int nr_threads = 1; +constexpr float voxel_size = 0.1f; +constexpr float approx_overlap = 0.9f; +constexpr float abort_score = 0.0f; const float transformation_office1_office2 [4][4] = { { -0.6946f, -0.7194f, -0.0051f, -3.6352f }, diff --git a/test/registration/test_registration_api_data.h b/test/registration/test_registration_api_data.h index f1a934f3c13..0386cc4dc32 100644 --- a/test/registration/test_registration_api_data.h +++ b/test/registration/test_registration_api_data.h @@ -1,6 +1,6 @@ #pragma once -const int nr_original_correspondences = 397; +constexpr int nr_original_correspondences = 397; const int correspondences_original[397][2] = { { 0, 61 }, { 1, 50 }, @@ -401,7 +401,7 @@ const int correspondences_original[397][2] = { { 396, 353 }, }; -const int nr_reciprocal_correspondences = 53; +constexpr int nr_reciprocal_correspondences = 53; const int correspondences_reciprocal[53][2] = { { 1, 50 }, { 2, 51 }, @@ -458,8 +458,8 @@ const int correspondences_reciprocal[53][2] = { { 366, 334 }, }; -const int nr_correspondences_result_rej_dist = 97; -const float rej_dist_max_dist = 0.01f; +constexpr int nr_correspondences_result_rej_dist = 97; +constexpr float rej_dist_max_dist = 0.01f; const int correspondences_dist[97][2] = { { 1, 50 }, { 2, 51 }, @@ -560,9 +560,9 @@ const int correspondences_dist[97][2] = { { 367, 334 }, }; -const int nr_correspondences_result_rej_median_dist = 139; -const float rej_median_factor = 0.5f; -const float rej_median_distance = 0.000465391f; +constexpr int nr_correspondences_result_rej_median_dist = 139; +constexpr float rej_median_factor = 0.5f; +constexpr float rej_median_distance = 0.000465391f; const int correspondences_median_dist[139][2] = { { 0, 61 }, { 1, 50 }, @@ -705,7 +705,7 @@ const int correspondences_median_dist[139][2] = { { 368, 335 }, }; -const int nr_correspondences_result_rej_one_to_one = 103; +constexpr int nr_correspondences_result_rej_one_to_one = 103; const int correspondences_one_to_one[103][2] = { { 177, 27 }, { 180, 32 }, @@ -812,9 +812,9 @@ const int correspondences_one_to_one[103][2] = { { 327, 360 }, }; -const int nr_correspondences_result_rej_sac = 97; -const double rej_sac_max_dist = 0.01; -const int rej_sac_max_iter = 1000; +constexpr int nr_correspondences_result_rej_sac = 97; +constexpr double rej_sac_max_dist = 0.01; +constexpr int rej_sac_max_iter = 1000; const int correspondences_sac[97][2] = { { 1, 50 }, { 2, 51 }, @@ -915,8 +915,8 @@ const int correspondences_sac[97][2] = { { 390, 334 }, }; -const int nr_correspondences_result_rej_trimmed = 198; -const float rej_trimmed_overlap = 0.5; +constexpr int nr_correspondences_result_rej_trimmed = 198; +constexpr float rej_trimmed_overlap = 0.5; const int correspondences_trimmed[198][2] = { { 260, 286 }, { 271, 299 }, diff --git a/test/sample_consensus/test_sample_consensus.cpp b/test/sample_consensus/test_sample_consensus.cpp index 5d56c571cb6..6580283faae 100644 --- a/test/sample_consensus/test_sample_consensus.cpp +++ b/test/sample_consensus/test_sample_consensus.cpp @@ -97,7 +97,7 @@ TYPED_TEST(SacTest, InfiniteLoop) { using namespace std::chrono_literals; - const unsigned point_count = 100; + constexpr unsigned point_count = 100; PointCloud cloud; cloud.resize (point_count); for (unsigned idx = 0; idx < point_count; ++idx) diff --git a/test/sample_consensus/test_sample_consensus_line_models.cpp b/test/sample_consensus/test_sample_consensus_line_models.cpp index 40ddd4a5c6d..aa88fada96a 100644 --- a/test/sample_consensus/test_sample_consensus_line_models.cpp +++ b/test/sample_consensus/test_sample_consensus_line_models.cpp @@ -159,9 +159,9 @@ TEST (SampleConsensusModelLine, SampleValidationPointsEqual) // being printed a 1000 times without any chance of success. // The order is chosen such that with a known, fixed rng-state/-seed all // validation steps are actually exercised. - const pcl::index_t firstKnownEqualPoint = 0; - const pcl::index_t secondKnownEqualPoint = 1; - const pcl::index_t cheatPointIndex = 2; + constexpr pcl::index_t firstKnownEqualPoint = 0; + constexpr pcl::index_t secondKnownEqualPoint = 1; + constexpr pcl::index_t cheatPointIndex = 2; cloud[firstKnownEqualPoint].getVector3fMap () << 0.1f, 0.0f, 0.0f; cloud[secondKnownEqualPoint].getVector3fMap () << 0.1f, 0.0f, 0.0f; @@ -258,7 +258,7 @@ TEST (SampleConsensusModelParallelLine, RANSAC) cloud[15].getVector3fMap () << -1.05f, 5.01f, 5.0f; // Create a shared line model pointer directly - const double eps = 0.1; //angle eps in radians + constexpr double eps = 0.1; // angle eps in radians const Eigen::Vector3f axis (0, 0, 1); SampleConsensusModelParallelLinePtr model (new SampleConsensusModelParallelLine (cloud.makeShared ())); model->setAxis (axis); diff --git a/test/sample_consensus/test_sample_consensus_plane_models.cpp b/test/sample_consensus/test_sample_consensus_plane_models.cpp index 82141b3aaa3..750797b1c22 100644 --- a/test/sample_consensus/test_sample_consensus_plane_models.cpp +++ b/test/sample_consensus/test_sample_consensus_plane_models.cpp @@ -144,10 +144,10 @@ TEST (SampleConsensusModelPlane, SampleValidationPointsCollinear) // being printed a 1000 times without any chance of success. // The order is chosen such that with a known, fixed rng-state/-seed all // validation steps are actually exercised. - const pcl::index_t firstCollinearPointIndex = 0; - const pcl::index_t secondCollinearPointIndex = 1; - const pcl::index_t thirdCollinearPointIndex = 2; - const pcl::index_t cheatPointIndex = 3; + constexpr pcl::index_t firstCollinearPointIndex = 0; + constexpr pcl::index_t secondCollinearPointIndex = 1; + constexpr pcl::index_t thirdCollinearPointIndex = 2; + constexpr pcl::index_t cheatPointIndex = 3; cloud[firstCollinearPointIndex].getVector3fMap () << 0.1f, 0.1f, 0.1f; cloud[secondCollinearPointIndex].getVector3fMap () << 0.2f, 0.2f, 0.2f; @@ -357,8 +357,8 @@ TEST (SampleConsensusModelNormalParallelPlane, RANSAC) SampleConsensusModelNormalParallelPlanePtr model (new SampleConsensusModelNormalParallelPlane (cloud.makeShared ())); model->setInputNormals (normals.makeShared ()); - const float max_angle_rad = 0.01f; - const float angle_eps = 0.001f; + constexpr float max_angle_rad = 0.01f; + constexpr float angle_eps = 0.001f; model->setEpsAngle (max_angle_rad); // Test true axis diff --git a/test/search/test_search.cpp b/test/search/test_search.cpp index 79e4e19d62e..208caea499c 100644 --- a/test/search/test_search.cpp +++ b/test/search/test_search.cpp @@ -69,16 +69,16 @@ using namespace pcl; #if EXCESSIVE_TESTING /** \brief number of points used for creating unordered point clouds */ -const unsigned int unorganized_point_count = 100000; +constexpr unsigned int unorganized_point_count = 100000; /** \brief number of search operations on ordered point clouds*/ -const unsigned int query_count = 5000; +constexpr unsigned int query_count = 5000; #else /** \brief number of points used for creating unordered point clouds */ -const unsigned int unorganized_point_count = 1200; +constexpr unsigned int unorganized_point_count = 1200; /** \brief number of search operations on ordered point clouds*/ -const unsigned int query_count = 100; +constexpr unsigned int query_count = 100; #endif /** \brief organized point cloud*/ diff --git a/test/surface/test_moving_least_squares.cpp b/test/surface/test_moving_least_squares.cpp index fb15467ef71..7095b64d3d8 100644 --- a/test/surface/test_moving_least_squares.cpp +++ b/test/surface/test_moving_least_squares.cpp @@ -128,8 +128,8 @@ TEST (PCL, MovingLeastSquares) // EXPECT_NEAR ((*mls_normals)[10].curvature, 0.019003, 1e-3); // EXPECT_EQ (mls_normals->size (), 457); - const float voxel_size = 0.005f; - const int num_dilations = 5; + constexpr float voxel_size = 0.005f; + constexpr int num_dilations = 5; mls_upsampling.setUpsamplingMethod (MovingLeastSquares::VOXEL_GRID_DILATION); mls_upsampling.setDilationIterations (num_dilations); mls_upsampling.setDilationVoxelSize (voxel_size); diff --git a/tools/crop_to_hull.cpp b/tools/crop_to_hull.cpp index df7543d16db..58efaed03ab 100644 --- a/tools/crop_to_hull.cpp +++ b/tools/crop_to_hull.cpp @@ -52,7 +52,7 @@ using namespace pcl::console; using PointT = PointXYZ; using CloudT = PointCloud; -const static double default_alpha = 1e3f; +constexpr double default_alpha = 1e3f; static void printHelp (int, char **argv) diff --git a/tools/mesh_sampling.cpp b/tools/mesh_sampling.cpp index 1ba164261d5..00c07bc1ac4 100644 --- a/tools/mesh_sampling.cpp +++ b/tools/mesh_sampling.cpp @@ -182,8 +182,8 @@ using namespace pcl; using namespace pcl::io; using namespace pcl::console; -const int default_number_samples = 100000; -const float default_leaf_size = 0.01f; +constexpr int default_number_samples = 100000; +constexpr float default_leaf_size = 0.01f; void printHelp (int, char **argv) diff --git a/tools/obj_rec_ransac_accepted_hypotheses.cpp b/tools/obj_rec_ransac_accepted_hypotheses.cpp index 4c2ec7010e4..ea5447ac2ea 100644 --- a/tools/obj_rec_ransac_accepted_hypotheses.cpp +++ b/tools/obj_rec_ransac_accepted_hypotheses.cpp @@ -469,7 +469,7 @@ main (int argc, char** argv) { printf ("\nUsage: ./obj_rec_ransac_accepted_hypotheses \n\n"); - const int num_params = 4; + constexpr int num_params = 4; float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/, 1/*n_hypotheses_to_show*/}; std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle", "n_hypotheses_to_show"}; diff --git a/tools/obj_rec_ransac_model_opps.cpp b/tools/obj_rec_ransac_model_opps.cpp index d06c2f6bc74..d82cbfb1630 100644 --- a/tools/obj_rec_ransac_model_opps.cpp +++ b/tools/obj_rec_ransac_model_opps.cpp @@ -76,7 +76,7 @@ main (int argc, char** argv) { printf ("\nUsage: ./pcl_obj_rec_ransac_model_opps \n\n"); - const int num_params = 3; + constexpr int num_params = 3; float parameters[num_params] = {10.0f/*pair width*/, 5.0f/*voxel size*/, 5.0f/*max co-planarity angle*/}; std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"}; diff --git a/tools/obj_rec_ransac_result.cpp b/tools/obj_rec_ransac_result.cpp index 12987d7535b..884dea61bd4 100644 --- a/tools/obj_rec_ransac_result.cpp +++ b/tools/obj_rec_ransac_result.cpp @@ -106,7 +106,7 @@ main (int argc, char** argv) { printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps \n\n"); - const int num_params = 3; + constexpr int num_params = 3; float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/}; std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"}; diff --git a/tools/obj_rec_ransac_scene_opps.cpp b/tools/obj_rec_ransac_scene_opps.cpp index f3df089c131..70ddfe42a65 100644 --- a/tools/obj_rec_ransac_scene_opps.cpp +++ b/tools/obj_rec_ransac_scene_opps.cpp @@ -96,7 +96,7 @@ main (int argc, char** argv) { printf ("\nUsage: ./pcl_obj_rec_ransac_scene_opps \n\n"); - const int num_params = 3; + constexpr int num_params = 3; float parameters[num_params] = {40.0f/*pair width*/, 5.0f/*voxel size*/, 15.0f/*max co-planarity angle*/}; std::string parameter_names[num_params] = {"pair_width", "voxel_size", "max_coplanarity_angle"}; diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 80ffb3c21ff..792e9334021 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -82,7 +82,7 @@ getTotalSystemMemory () const int BUFFER_SIZE = int (getTotalSystemMemory () / (640 * 480) / 2); #else -const int BUFFER_SIZE = 200; +constexpr int BUFFER_SIZE = 200; #endif int buff_size = BUFFER_SIZE; diff --git a/tools/train_linemod_template.cpp b/tools/train_linemod_template.cpp index 4c186acc0b8..0bee446cfdf 100644 --- a/tools/train_linemod_template.cpp +++ b/tools/train_linemod_template.cpp @@ -118,8 +118,8 @@ maskForegroundPoints (const PointCloudXYZRGBA::ConstPtr & input, } // Find the dominant plane between the specified near/far thresholds - const float distance_threshold = 0.02f; - const int max_iterations = 500; + constexpr float distance_threshold = 0.02f; + constexpr int max_iterations = 500; pcl::SACSegmentation seg; seg.setOptimizeCoefficients (true); seg.setModelType (pcl::SACMODEL_PLANE); diff --git a/tracking/include/pcl/tracking/impl/tracking.hpp b/tracking/include/pcl/tracking/impl/tracking.hpp index 2fe9bbfd282..626b2cff911 100644 --- a/tracking/include/pcl/tracking/impl/tracking.hpp +++ b/tracking/include/pcl/tracking/impl/tracking.hpp @@ -86,7 +86,7 @@ struct EIGEN_ALIGN16 ParticleXYZRPY : public _ParticleXYZRPY { // Scales 1.0 radians of variance in RPY sampling into equivalent units for // quaternion sampling. - const float scale_factor = 0.2862; + constexpr float scale_factor = 0.2862; float a = sampleNormal(0, scale_factor * cov[3]); float b = sampleNormal(0, scale_factor * cov[4]); From 9237a6b59b866e3a556c604bf5ba876010f5e562 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 17 Dec 2022 14:34:13 +0100 Subject: [PATCH 014/288] Add support for Boost 1.81 --- PCLConfig.cmake.in | 2 +- cmake/pcl_find_boost.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index ddf93eb64c1..12b1cdb2fe0 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -96,7 +96,7 @@ macro(find_boost) set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" - "1.80.0" "1.80" + "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index b60fafae456..2efcf3cbecf 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -14,7 +14,7 @@ else() endif() set(Boost_ADDITIONAL_VERSIONS - "1.80.0" "1.80" + "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") From d54167f69b513a804e39f53f560f86221de9493b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 18 Dec 2022 14:18:04 +0100 Subject: [PATCH 015/288] Fix some broken links and use more https --- .../pcl/apps/in_hand_scanner/opengl_viewer.h | 2 +- common/include/pcl/common/impl/common.hpp | 2 +- .../pcl/common/polynomial_calculations.h | 6 ++-- doc/doxygen/pcl.doxy | 2 +- doc/tutorials/content/depth_sense_grabber.rst | 2 +- doc/tutorials/content/ensenso_cameras.rst | 2 +- doc/tutorials/content/fpfh_estimation.rst | 2 +- doc/tutorials/content/gasd_estimation.rst | 2 +- doc/tutorials/content/hdl_grabber.rst | 2 +- doc/tutorials/content/kdtree_search.rst | 2 +- doc/tutorials/content/pcd_file_format.rst | 10 +++---- doc/tutorials/content/pcl_plotter.rst | 2 +- doc/tutorials/content/pfh_estimation.rst | 2 +- doc/tutorials/content/planar_segmentation.rst | 2 +- .../content/random_sample_consensus.rst | 2 +- doc/tutorials/content/vfh_estimation.rst | 2 +- doc/tutorials/content/visualization.rst | 2 +- doc/tutorials/content/walkthrough.rst | 30 +++++++++---------- filters/include/pcl/filters/convolution.h | 2 +- .../pcl/filters/impl/conditional_removal.hpp | 2 +- gpu/kinfu/tools/plot_camera_poses.m | 2 +- io/include/pcl/io/tar.h | 2 +- kdtree/kdtree.doxy | 4 +-- keypoints/keypoints.doxy | 2 +- registration/include/pcl/registration/bfgs.h | 2 +- sample_consensus/sample_consensus.doxy | 4 +-- surface/include/pcl/surface/texture_mapping.h | 2 +- tools/pcd_viewer.cpp | 4 +-- 28 files changed, 51 insertions(+), 51 deletions(-) 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 d9b94d72fe8..78d0fe29b68 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 @@ -57,7 +57,7 @@ namespace pcl { namespace ihs { namespace detail { /** \brief Mesh format more efficient for visualization than the half-edge data - * structure. \see http://en.wikipedia.org/wiki/Polygon_mesh#Face-vertex_meshes + * structure. \see https://en.wikipedia.org/wiki/Polygon_mesh#Face-vertex_meshes * * \note Only triangles are currently supported. */ diff --git a/common/include/pcl/common/impl/common.hpp b/common/include/pcl/common/impl/common.hpp index b4e80224aba..97edfbace0b 100644 --- a/common/include/pcl/common/impl/common.hpp +++ b/common/include/pcl/common/impl/common.hpp @@ -388,7 +388,7 @@ pcl::getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc double p2p1 = (p2 - p1).norm (), p3p2 = (p3 - p2).norm (), p1p3 = (p1 - p3).norm (); // Calculate the area of the triangle using Heron's formula - // (http://en.wikipedia.org/wiki/Heron's_formula) + // (https://en.wikipedia.org/wiki/Heron's_formula) double semiperimeter = (p2p1 + p3p2 + p1p3) / 2.0; double area = sqrt (semiperimeter * (semiperimeter - p2p1) * (semiperimeter - p3p2) * (semiperimeter - p1p3)); // Compute the radius of the circumscribed circle diff --git a/common/include/pcl/common/polynomial_calculations.h b/common/include/pcl/common/polynomial_calculations.h index 26d5cc7be13..7e91206ef91 100644 --- a/common/include/pcl/common/polynomial_calculations.h +++ b/common/include/pcl/common/polynomial_calculations.h @@ -64,17 +64,17 @@ namespace pcl // =====PUBLIC METHODS===== /** Solves an equation of the form ax^4 + bx^3 + cx^2 +dx + e = 0 - * See http://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method */ + * See https://en.wikipedia.org/wiki/Quartic_equation#Summary_of_Ferrari.27s_method */ inline void solveQuarticEquation (real a, real b, real c, real d, real e, std::vector& roots) const; /** Solves an equation of the form ax^3 + bx^2 + cx + d = 0 - * See http://en.wikipedia.org/wiki/Cubic_equation */ + * See https://en.wikipedia.org/wiki/Cubic_equation */ inline void solveCubicEquation (real a, real b, real c, real d, std::vector& roots) const; /** Solves an equation of the form ax^2 + bx + c = 0 - * See http://en.wikipedia.org/wiki/Quadratic_equation */ + * See https://en.wikipedia.org/wiki/Quadratic_equation */ inline void solveQuadraticEquation (real a, real b, real c, std::vector& roots) const; diff --git a/doc/doxygen/pcl.doxy b/doc/doxygen/pcl.doxy index 94a39d69719..359856681b3 100644 --- a/doc/doxygen/pcl.doxy +++ b/doc/doxygen/pcl.doxy @@ -12,7 +12,7 @@ recognize objects in the world based on their geometric appearance, and create surfaces from point clouds and visualize them -- to name a few. PCL is released under the terms of the +href="https://en.wikipedia.org/wiki/BSD_licenses#3-clause_license_.28.22New_BSD_License.22_or_.22Modified_BSD_License.22.29"> BSD license and is open source software. It is free for commercial and research use. diff --git a/doc/tutorials/content/depth_sense_grabber.rst b/doc/tutorials/content/depth_sense_grabber.rst index f03456e7724..41125fb50e9 100644 --- a/doc/tutorials/content/depth_sense_grabber.rst +++ b/doc/tutorials/content/depth_sense_grabber.rst @@ -71,7 +71,7 @@ DepthSense Viewer The grabber is accompanied by an example tool `pcl_depth_sense_viewer `_ which can be used to view and save point clouds coming from a DepthSense device. -Internally it uses the `DepthSenseGrabber `_ +Internally it uses the `DepthSenseGrabber `_ class that implements the standard PCL grabber interface. You can run the tool with `--help` option to view the usage guide. diff --git a/doc/tutorials/content/ensenso_cameras.rst b/doc/tutorials/content/ensenso_cameras.rst index 257c3648663..1f59383c1f3 100644 --- a/doc/tutorials/content/ensenso_cameras.rst +++ b/doc/tutorials/content/ensenso_cameras.rst @@ -38,7 +38,7 @@ Using the example ================= The `pcl_ensenso_viewer `_ example shows how to -display a point cloud grabbed from an Ensenso device using the `EnsensoGrabber `_ class. +display a point cloud grabbed from an Ensenso device using the `EnsensoGrabber `_ class. Note that this program opens the TCP port of the nxLib tree, this allows you to open the nxLib tree with the nxTreeEdit program (port 24000). The capture parameters (exposure, gain etc..) are set to default values. diff --git a/doc/tutorials/content/fpfh_estimation.rst b/doc/tutorials/content/fpfh_estimation.rst index a5aa5a3ed49..1ee1d797590 100644 --- a/doc/tutorials/content/fpfh_estimation.rst +++ b/doc/tutorials/content/fpfh_estimation.rst @@ -84,7 +84,7 @@ Estimating FPFH features ------------------------ Fast Point Feature Histograms are implemented in PCL as part of the -`pcl_features `_ +`pcl_features `_ library. The default FPFH implementation uses 11 binning subdivisions (e.g., each of the diff --git a/doc/tutorials/content/gasd_estimation.rst b/doc/tutorials/content/gasd_estimation.rst index d8d1aa64078..bc28188c385 100644 --- a/doc/tutorials/content/gasd_estimation.rst +++ b/doc/tutorials/content/gasd_estimation.rst @@ -69,7 +69,7 @@ Estimating GASD features ------------------------ The Globally Aligned Spatial Distribution is implemented in PCL as part of the -`pcl_features `_ +`pcl_features `_ library. The default values for color GASD parameters are: :math:`m_s=6` (half size of 3), :math:`l_s=1`, :math:`m_c=4` (half size of 2) and :math:`l_c=12` and no histogram interpolation (INTERP_NONE). This results in an array of 984 float values. These are stored in a **pcl::GASDSignature984** point type. The default values for shape only GASD parameters are: :math:`m_s=8` (half size of 4), :math:`l_s=1` and trilinear histogram interpolation (INTERP_TRILINEAR). This results in an array of 512 float values, which may be stored in a **pcl::GASDSignature512** point type. It is also possible to use quadrilinear histogram interpolation (INTERP_QUADRILINEAR). diff --git a/doc/tutorials/content/hdl_grabber.rst b/doc/tutorials/content/hdl_grabber.rst index 3b0401f58ac..ba1b9f500a4 100644 --- a/doc/tutorials/content/hdl_grabber.rst +++ b/doc/tutorials/content/hdl_grabber.rst @@ -46,7 +46,7 @@ PCAP Files `Wireshark `_ is a popular Network Packet Analyzer Program which is available for most platforms, including Linux, MacOS and Windows. This tool uses a defacto -standard network packet capture file format called `PCAP `_. +standard network packet capture file format called `PCAP `_. Many publicly available Velodyne HDL packet captures use this PCAP file format as a means of recording and playback. These PCAP files can be used with the HDL Grabber if PCL is compiled with PCAP support. diff --git a/doc/tutorials/content/kdtree_search.rst b/doc/tutorials/content/kdtree_search.rst index c6cf9db8688..08183c911cc 100644 --- a/doc/tutorials/content/kdtree_search.rst +++ b/doc/tutorials/content/kdtree_search.rst @@ -146,4 +146,4 @@ Once you have run it you should see something similar to this:: 356.962 247.285 514.959 (squared distance: 50423.7) 282.065 509.488 516.216 (squared distance: 50730.4) -.. [Wikipedia] http://en.wikipedia.org/wiki/K-d_tree +.. [Wikipedia] https://en.wikipedia.org/wiki/K-d_tree diff --git a/doc/tutorials/content/pcd_file_format.rst b/doc/tutorials/content/pcd_file_format.rst index 688da23b86f..3413e28c618 100644 --- a/doc/tutorials/content/pcd_file_format.rst +++ b/doc/tutorials/content/pcd_file_format.rst @@ -22,15 +22,15 @@ graphics and computational geometry communities in particular, have created numerous formats to describe arbitrary polygons and point clouds acquired using laser scanners. Some of these formats include: -* `PLY `_ - a polygon file format, developed at Stanford University by Turk et al +* `PLY `_ - a polygon file format, developed at Stanford University by Turk et al -* `STL `_ - a file format native to the stereolithography CAD software created by 3D Systems +* `STL `_ - a file format native to the stereolithography CAD software created by 3D Systems -* `OBJ `_ - a geometry definition file format first developed by Wavefront Technologies +* `OBJ `_ - a geometry definition file format first developed by Wavefront Technologies -* `X3D `_ - the ISO standard XML-based file format for representing 3D computer graphics data +* `X3D `_ - the ISO standard XML-based file format for representing 3D computer graphics data -* `and many others `_ +* `and many others `_ All the above file formats suffer from several shortcomings, as explained in the next sections -- which is natural, as they were created for a different diff --git a/doc/tutorials/content/pcl_plotter.rst b/doc/tutorials/content/pcl_plotter.rst index 97cdd49e4f1..68f66de8317 100644 --- a/doc/tutorials/content/pcl_plotter.rst +++ b/doc/tutorials/content/pcl_plotter.rst @@ -5,7 +5,7 @@ PCLPlotter PCLPlotter provides a very straightforward and easy interface for plotting graphs. One can visualize all sort of important plots - from polynomial functions to histograms - inside the library without going to any other software (like MATLAB). -Please go through the `documentation `_ when some specific concepts are introduced in this tutorial to know the exact method signatures. +Please go through the `documentation `_ when some specific concepts are introduced in this tutorial to know the exact method signatures. The code for the visualization of a plot are usually as simple as the following snippet. diff --git a/doc/tutorials/content/pfh_estimation.rst b/doc/tutorials/content/pfh_estimation.rst index 423d2a8ef9d..0f67e4571bf 100644 --- a/doc/tutorials/content/pfh_estimation.rst +++ b/doc/tutorials/content/pfh_estimation.rst @@ -116,7 +116,7 @@ Estimating PFH features ----------------------- Point Feature Histograms are implemented in PCL as part of the `pcl_features -`_ library. +`_ library. The default PFH implementation uses 5 binning subdivisions (e.g., each of the four feature values will use this many bins from its value interval), and does diff --git a/doc/tutorials/content/planar_segmentation.rst b/doc/tutorials/content/planar_segmentation.rst index c5b5b17a044..c12e26bf36e 100644 --- a/doc/tutorials/content/planar_segmentation.rst +++ b/doc/tutorials/content/planar_segmentation.rst @@ -63,7 +63,7 @@ In this tutorial, we will use the RANSAC method (pcl::SAC_RANSAC) as the robust Our decision is motivated by RANSAC's simplicity (other robust estimators use it as a base and add additional, more complicated concepts). For more information about RANSAC, check its `Wikipedia page -`_. +`_. Finally: diff --git a/doc/tutorials/content/random_sample_consensus.rst b/doc/tutorials/content/random_sample_consensus.rst index ed5dad498ae..fb9ceb018a9 100644 --- a/doc/tutorials/content/random_sample_consensus.rst +++ b/doc/tutorials/content/random_sample_consensus.rst @@ -123,4 +123,4 @@ It will show you the result of applying RandomSampleConsensus to this data set w :align: center :height: 400px -.. [WikipediaRANSAC] http://en.wikipedia.org/wiki/RANSAC +.. [WikipediaRANSAC] https://en.wikipedia.org/wiki/RANSAC diff --git a/doc/tutorials/content/vfh_estimation.rst b/doc/tutorials/content/vfh_estimation.rst index 78fef51ecee..f396770114f 100644 --- a/doc/tutorials/content/vfh_estimation.rst +++ b/doc/tutorials/content/vfh_estimation.rst @@ -59,7 +59,7 @@ Estimating VFH features ----------------------- The Viewpoint Feature Histogram is implemented in PCL as part of the -`pcl_features `_ +`pcl_features `_ library. The default VFH implementation uses 45 binning subdivisions for each of the diff --git a/doc/tutorials/content/visualization.rst b/doc/tutorials/content/visualization.rst index 19624090c96..4754a7c5503 100644 --- a/doc/tutorials/content/visualization.rst +++ b/doc/tutorials/content/visualization.rst @@ -43,7 +43,7 @@ accompanying the library. Due to historical reasons, PCL 1.x stores RGB data as a packed float (to preserve backward compatibility). To learn more about this, please see the `PointXYZRGB - `_. + `_. Simple Cloud Visualization -------------------------- diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index 7cd28fec69f..d6da4390c32 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -69,7 +69,7 @@ Filters .. image:: images/statistical_removal_2.jpg -**Documentation:** http://docs.pointclouds.org/trunk/group__filters.html +**Documentation:** https://pointclouds.org/documentation/group__filters.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#filtering-tutorial @@ -118,7 +118,7 @@ Features | -**Documentation:** http://docs.pointclouds.org/trunk/group__features.html +**Documentation:** https://pointclouds.org/documentation/group__features.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#features-tutorial @@ -154,7 +154,7 @@ Keypoints **Background** - The *keypoints* library contains implementations of two point cloud keypoint detection algorithms. Keypoints (also referred to as `interest points `_) are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined detection criterion. Typically, the number of interest points in a point cloud will be much smaller than the total number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the keypoints and descriptors can be used to form a compact—yet descriptive—representation of the original data. + The *keypoints* library contains implementations of two point cloud keypoint detection algorithms. Keypoints (also referred to as `interest points `_) are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined detection criterion. Typically, the number of interest points in a point cloud will be much smaller than the total number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the keypoints and descriptors can be used to form a compact—yet descriptive—representation of the original data. The figure below shows the output of NARF keypoints extraction from a range image: @@ -162,7 +162,7 @@ Keypoints | -**Documentation:** http://docs.pointclouds.org/trunk/group__keypoints.html +**Documentation:** https://pointclouds.org/documentation/group__keypoints.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#keypoints-tutorial @@ -212,7 +212,7 @@ Registration | -**Documentation:** http://docs.pointclouds.org/trunk/group__registration.html +**Documentation:** https://pointclouds.org/documentation/group__registration.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#registration-tutorial @@ -249,9 +249,9 @@ Kd-tree A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial `_. - The *kdtree* library provides the kd-tree data-structure, using `FLANN `_, that allows for fast `nearest neighbor searches `_. + The *kdtree* library provides the kd-tree data-structure, using `FLANN `_, that allows for fast `nearest neighbor searches `_. - A `Kd-tree `_ (k-dimensional tree) is a space-partitioning data structure that stores a set of k-dimensional points in a tree structure that enables efficient range searches and nearest neighbor searches. Nearest neighbor searches are a core operation when working with point cloud data and can be used to find correspondences between groups of points or feature descriptors or to define the local neighborhood around a point or points. + A `Kd-tree `_ (k-dimensional tree) is a space-partitioning data structure that stores a set of k-dimensional points in a tree structure that enables efficient range searches and nearest neighbor searches. Nearest neighbor searches are a core operation when working with point cloud data and can be used to find correspondences between groups of points or feature descriptors or to define the local neighborhood around a point or points. .. image:: images/3dtree.png @@ -259,7 +259,7 @@ Kd-tree | -**Documentation:** http://docs.pointclouds.org/trunk/group__kdtree.html +**Documentation:** https://pointclouds.org/documentation/group__kdtree.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#kdtree-tutorial @@ -299,7 +299,7 @@ Octree | -**Documentation:** http://docs.pointclouds.org/trunk/group__octree.html +**Documentation:** https://pointclouds.org/documentation/group__octree.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#octree-tutorial @@ -340,7 +340,7 @@ Segmentation | -**Documentation:** http://docs.pointclouds.org/trunk/group__segmentation.html +**Documentation:** https://pointclouds.org/documentation/group__segmentation.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#segmentation-tutorial @@ -386,7 +386,7 @@ Sample Consensus | -**Documentation:** http://docs.pointclouds.org/trunk/group__sample__consensus.html +**Documentation:** https://pointclouds.org/documentation/group__sample__consensus.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#sample-consensus @@ -432,7 +432,7 @@ Surface | -**Documentation:** http://docs.pointclouds.org/trunk/group__surface.html +**Documentation:** https://pointclouds.org/documentation/group__surface.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#surface-tutorial @@ -513,7 +513,7 @@ I/O | -**Documentation:** http://docs.pointclouds.org/trunk/group__io.html +**Documentation:** https://pointclouds.org/documentation/group__io.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#i-o @@ -580,7 +580,7 @@ Visualization | -**Documentation:** http://docs.pointclouds.org/trunk/group__visualization.html +**Documentation:** https://pointclouds.org/documentation/group__visualization.html **Tutorials:** http://pointclouds.org/documentation/tutorials/#visualization-tutorial @@ -751,7 +751,7 @@ This section provides a quick reference for some of the common tools in PCL. ``pcl_pcd2vtk input.pcd output.vtk`` - * ``pcl_pcd2ply``: converts PCD (Point Cloud Data) files to the `PLY format `_. + * ``pcl_pcd2ply``: converts PCD (Point Cloud Data) files to the `PLY format `_. **Usage example:** diff --git a/filters/include/pcl/filters/convolution.h b/filters/include/pcl/filters/convolution.h index 85bc5826353..b60904f6751 100644 --- a/filters/include/pcl/filters/convolution.h +++ b/filters/include/pcl/filters/convolution.h @@ -48,7 +48,7 @@ namespace pcl /** Convolution is a mathematical operation on two functions f and g, * producing a third function that is typically viewed as a modified * version of one of the original functions. - * see http://en.wikipedia.org/wiki/Convolution. + * see https://en.wikipedia.org/wiki/Convolution. * * The class provides rows, column and separate convolving operations * of a point cloud. diff --git a/filters/include/pcl/filters/impl/conditional_removal.hpp b/filters/include/pcl/filters/impl/conditional_removal.hpp index 560aca39e61..16da3accb9c 100644 --- a/filters/include/pcl/filters/impl/conditional_removal.hpp +++ b/filters/include/pcl/filters/impl/conditional_removal.hpp @@ -310,7 +310,7 @@ pcl::PackedHSIComparison::evaluate (const PointT &point) const g_ = static_cast (rgb_val_ >> 8); b_ = static_cast (rgb_val_); - // definitions taken from http://en.wikipedia.org/wiki/HSL_and_HSI + // definitions taken from https://en.wikipedia.org/wiki/HSL_and_HSI float hx = (2.0f * r_ - g_ - b_) / 4.0f; // hue x component -127 to 127 float hy = static_cast (g_ - b_) * 111.0f / 255.0f; // hue y component -111 to 111 h_ = static_cast (std::atan2(hy, hx) * 128.0f / M_PI); diff --git a/gpu/kinfu/tools/plot_camera_poses.m b/gpu/kinfu/tools/plot_camera_poses.m index 4df0dce1a23..213dd8d2d49 100644 --- a/gpu/kinfu/tools/plot_camera_poses.m +++ b/gpu/kinfu/tools/plot_camera_poses.m @@ -68,7 +68,7 @@ function coord(h,r,t) end function R=q2rot(q) -% conversion code from http://en.wikipedia.org/wiki/Rotation_matrix%Quaternion +% conversion code from https://en.wikipedia.org/wiki/Rotation_matrix%Quaternion Nq = q(1)^2 + q(2)^2 + q(3)^2 + q(4)^2; if Nq>0; s=2/Nq; else s=0; end X = q(2)*s; Y = q(3)*s; Z = q(4)*s; diff --git a/io/include/pcl/io/tar.h b/io/include/pcl/io/tar.h index 210ecc96820..fbe997d07d0 100644 --- a/io/include/pcl/io/tar.h +++ b/io/include/pcl/io/tar.h @@ -44,7 +44,7 @@ namespace pcl namespace io { /** \brief A TAR file's header, as described on - * http://en.wikipedia.org/wiki/Tar_%28file_format%29. + * https://en.wikipedia.org/wiki/Tar_%28file_format%29. */ struct TARHeader { diff --git a/kdtree/kdtree.doxy b/kdtree/kdtree.doxy index 9bf527c3206..2cf493823b7 100644 --- a/kdtree/kdtree.doxy +++ b/kdtree/kdtree.doxy @@ -5,9 +5,9 @@ The pcl_kdtree library provides the kd-tree data-structure, using FLANN, - that allows for fast nearest neighbor searches. + that allows for fast nearest neighbor searches. - A Kd-tree (k-dimensional tree) is a space-partitioning data + A Kd-tree (k-dimensional tree) is a space-partitioning data structure that stores a set of k-dimensional points in a tree structure that enables efficient range searches and nearest neighbor searches. Nearest neighbor searches are a core operation when working with point cloud data and can be used to find correspondences between groups of points or feature descriptors or to define the local neighborhood diff --git a/keypoints/keypoints.doxy b/keypoints/keypoints.doxy index f3f79b71c28..7c363a29ef8 100644 --- a/keypoints/keypoints.doxy +++ b/keypoints/keypoints.doxy @@ -4,7 +4,7 @@ \section secKeypointsPresentation Overview The pcl_keypoints library contains implementations of two point cloud keypoint detection algorithms. - Keypoints (also referred to as interest points) + Keypoints (also referred to as interest points) are points in an image or point cloud that are stable, distinctive, and can be identified using a well-defined detection criterion. Typically, the number of interest points in a point cloud will be much smaller than the total number of points in the cloud, and when used in combination with local feature descriptors at each keypoint, the diff --git a/registration/include/pcl/registration/bfgs.h b/registration/include/pcl/registration/bfgs.h index 1d35fa2d7e8..3bf653b526a 100644 --- a/registration/include/pcl/registration/bfgs.h +++ b/registration/include/pcl/registration/bfgs.h @@ -110,7 +110,7 @@ struct BFGSDummyFunctor { /** * BFGS stands for Broyden–Fletcher–Goldfarb–Shanno (BFGS) method for solving * unconstrained nonlinear optimization problems. - * For further details please visit: http://en.wikipedia.org/wiki/BFGS_method + * For further details please visit: https://en.wikipedia.org/wiki/BFGS_method * The method provided here is almost similar to the one provided by GSL. * It reproduces Fletcher's original algorithm in Practical Methods of Optimization * algorithms : 2.6.2 and 2.6.4 and uses the same politics in GSL with cubic diff --git a/sample_consensus/sample_consensus.doxy b/sample_consensus/sample_consensus.doxy index 28b06caedee..914722bb28b 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 be + 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 @@ -37,7 +37,7 @@ The following list describes the robust sample consensus estimators implemented:

    -
  • SAC_RANSAC - RANdom SAmple Consensus
  • +
  • SAC_RANSAC - RANdom SAmple Consensus
  • SAC_LMEDS - Least Median of Squares
  • SAC_MSAC - M-Estimator SAmple Consensus
  • SAC_RRANSAC - Randomized RANSAC
  • diff --git a/surface/include/pcl/surface/texture_mapping.h b/surface/include/pcl/surface/texture_mapping.h index 0700ccd3c98..caff3c2e836 100644 --- a/surface/include/pcl/surface/texture_mapping.h +++ b/surface/include/pcl/surface/texture_mapping.h @@ -355,7 +355,7 @@ namespace pcl mapTexture2Face (const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3); /** \brief Returns the circumcenter of a triangle and the circle's radius. - * \details see http://en.wikipedia.org/wiki/Circumcenter for formulas. + * \details see https://en.wikipedia.org/wiki/Circumcenter for formulas. * \param[in] p1 first point of the triangle. * \param[in] p2 second point of the triangle. * \param[in] p3 third point of the triangle. diff --git a/tools/pcd_viewer.cpp b/tools/pcd_viewer.cpp index 8ed0062a2b1..82664b676e3 100644 --- a/tools/pcd_viewer.cpp +++ b/tools/pcd_viewer.cpp @@ -129,10 +129,10 @@ printHelp (int, char **argv) print_info ("\n"); print_info (" -immediate_rendering 0/1 = use immediate mode rendering to draw the data (default: "); print_value ("disabled"); print_info (")\n"); print_info (" Note: the use of immediate rendering will enable the visualization of larger datasets at the expense of extra RAM.\n"); - print_info (" See http://en.wikipedia.org/wiki/Immediate_mode for more information.\n"); + print_info (" See https://en.wikipedia.org/wiki/Immediate_mode for more information.\n"); print_info (" -vbo_rendering 0/1 = use OpenGL 1.4+ Vertex Buffer Objects for rendering (default: "); print_value ("disabled"); print_info (")\n"); print_info (" Note: the use of VBOs will enable the visualization of larger datasets at the expense of extra RAM.\n"); - print_info (" See http://en.wikipedia.org/wiki/Vertex_Buffer_Object for more information.\n"); + print_info (" See https://en.wikipedia.org/wiki/Vertex_Buffer_Object for more information.\n"); print_info ("\n"); print_info (" -use_point_picking = enable the usage of picking points on screen (default "); print_value ("disabled"); print_info (")\n"); print_info ("\n"); From c3d6d5cb33edfdf93f12ee7208ead9cadfdebe58 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 18 Dec 2022 14:57:29 +0100 Subject: [PATCH 016/288] Replace deprecated includes in tutorials --- doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp | 2 +- .../content/sources/iccv2011/include/feature_estimation.h | 2 +- .../content/sources/iccv2011/src/correspondence_viewer.cpp | 2 +- doc/tutorials/content/sources/iccv2011/src/tutorial.cpp | 2 +- .../content/sources/iros2011/include/feature_estimation.h | 2 +- .../sources/iros2011/include/solution/feature_estimation.h | 2 +- .../content/sources/iros2011/src/correspondence_viewer.cpp | 2 +- .../normal_estimation_using_integral_images.cpp | 2 +- .../pairwise_incremental_registration.cpp | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp b/doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp index d262b8dcffd..ac484b7f3f7 100644 --- a/doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp +++ b/doc/tutorials/content/sources/cloud_viewer/cloud_viewer.cpp @@ -1,6 +1,6 @@ #include #include -#include +#include #include int user_data; diff --git a/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h b/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h index 92d7d84c23f..983c56a6f2c 100644 --- a/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h +++ b/doc/tutorials/content/sources/iccv2011/include/feature_estimation.h @@ -2,7 +2,7 @@ #include "typedefs.h" -#include +#include #include #include #include diff --git a/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp b/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp index 3ba7056d215..ba4465d66be 100644 --- a/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/correspondence_viewer.cpp @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include /* A few functions to help load up the points */ diff --git a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp index f5f8a7744a3..a0ffa106e08 100644 --- a/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp +++ b/doc/tutorials/content/sources/iccv2011/src/tutorial.cpp @@ -3,7 +3,7 @@ #include #include -#include +#include #include #include diff --git a/doc/tutorials/content/sources/iros2011/include/feature_estimation.h b/doc/tutorials/content/sources/iros2011/include/feature_estimation.h index 0f2f40824f8..764a13b20a2 100644 --- a/doc/tutorials/content/sources/iros2011/include/feature_estimation.h +++ b/doc/tutorials/content/sources/iros2011/include/feature_estimation.h @@ -2,7 +2,7 @@ #include "typedefs.h" -#include +#include #include #include #include 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 6249aaa20da..07dd3809ba4 100644 --- a/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h +++ b/doc/tutorials/content/sources/iros2011/include/solution/feature_estimation.h @@ -2,7 +2,7 @@ #include "typedefs.h" -#include +#include #include #include #include diff --git a/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp b/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp index 3ba7056d215..ba4465d66be 100644 --- a/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp +++ b/doc/tutorials/content/sources/iros2011/src/correspondence_viewer.cpp @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include /* A few functions to help load up the points */ diff --git a/doc/tutorials/content/sources/normal_estimation_using_integral_images/normal_estimation_using_integral_images.cpp b/doc/tutorials/content/sources/normal_estimation_using_integral_images/normal_estimation_using_integral_images.cpp index 5d796a501c0..a5726fcc93c 100644 --- a/doc/tutorials/content/sources/normal_estimation_using_integral_images/normal_estimation_using_integral_images.cpp +++ b/doc/tutorials/content/sources/normal_estimation_using_integral_images/normal_estimation_using_integral_images.cpp @@ -1,6 +1,6 @@ #include #include -#include +#include #include #include diff --git a/doc/tutorials/content/sources/pairwise_incremental_registration/pairwise_incremental_registration.cpp b/doc/tutorials/content/sources/pairwise_incremental_registration/pairwise_incremental_registration.cpp index 6f841165c10..834ea301225 100644 --- a/doc/tutorials/content/sources/pairwise_incremental_registration/pairwise_incremental_registration.cpp +++ b/doc/tutorials/content/sources/pairwise_incremental_registration/pairwise_incremental_registration.cpp @@ -52,7 +52,7 @@ #include #include -#include +#include #include From e09805520f3bf2de18f422e92654fa9736644cc1 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 18 Dec 2022 14:59:19 +0100 Subject: [PATCH 017/288] Add missing return statements --- common/include/pcl/common/impl/generate.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/common/include/pcl/common/impl/generate.hpp b/common/include/pcl/common/impl/generate.hpp index 3337d49a754..ea137ae316d 100644 --- a/common/include/pcl/common/impl/generate.hpp +++ b/common/include/pcl/common/impl/generate.hpp @@ -111,21 +111,21 @@ CloudGenerator::setParametersForZ (const GeneratorParameters template const typename CloudGenerator::GeneratorParameters& CloudGenerator::getParametersForX () const { - x_generator_.getParameters (); + return x_generator_.getParameters (); } template const typename CloudGenerator::GeneratorParameters& CloudGenerator::getParametersForY () const { - y_generator_.getParameters (); + return y_generator_.getParameters (); } template const typename CloudGenerator::GeneratorParameters& CloudGenerator::getParametersForZ () const { - z_generator_.getParameters (); + return z_generator_.getParameters (); } @@ -230,14 +230,14 @@ CloudGenerator::setParametersForY (const GeneratorPara template const typename CloudGenerator::GeneratorParameters& CloudGenerator::getParametersForX () const { - x_generator_.getParameters (); + return x_generator_.getParameters (); } template const typename CloudGenerator::GeneratorParameters& CloudGenerator::getParametersForY () const { - y_generator_.getParameters (); + return y_generator_.getParameters (); } From e268704c8c4e991086281bcfdc2317f0977e5ecc Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Tue, 20 Dec 2022 20:45:24 +0100 Subject: [PATCH 018/288] Fix randomly failing search tests (organized and octree) (#5555) * Fix randomly failing search tests (organized and octree) For some random seeds, these tests were failing because of numerical imprecision (points very close to the search radius). Now the tests have a tolerance, and the number of points returned by `radiusSearch` must be between a lower and upper bound (computed via brute force) * Fix typo --- test/search/precise_distances.h | 23 ++++++++ test/search/test_octree.cpp | 48 +++++++---------- test/search/test_organized.cpp | 51 ++++++------------ test/search/test_organized_index.cpp | 81 +++++++++++----------------- 4 files changed, 89 insertions(+), 114 deletions(-) create mode 100644 test/search/precise_distances.h diff --git a/test/search/precise_distances.h b/test/search/precise_distances.h new file mode 100644 index 00000000000..7e02e87f510 --- /dev/null +++ b/test/search/precise_distances.h @@ -0,0 +1,23 @@ +namespace pcl_tests { +// Here we want very precise distance functions, 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 +squared_point_distance(const PointT& p1, const PointT& p2) +{ + const double x_diff = (static_cast(p1.x) - static_cast(p2.x)), + y_diff = (static_cast(p1.y) - static_cast(p2.y)), + z_diff = (static_cast(p1.z) - static_cast(p2.z)); + return (x_diff * x_diff + y_diff * y_diff + z_diff * z_diff); +} + +template inline double +point_distance(const PointT& p1, const PointT& p2) +{ + const double x_diff = (static_cast(p1.x) - static_cast(p2.x)), + y_diff = (static_cast(p1.y) - static_cast(p2.y)), + z_diff = (static_cast(p1.z) - static_cast(p2.z)); + return std::sqrt(x_diff * x_diff + y_diff * y_diff + z_diff * z_diff); +} +} // namespace pcl_tests diff --git a/test/search/test_octree.cpp b/test/search/test_octree.cpp index 78b7eb7328d..6da19e3fd50 100644 --- a/test/search/test_octree.cpp +++ b/test/search/test_octree.cpp @@ -41,6 +41,9 @@ #include #include #include // for pcl::search::Octree +#include "precise_distances.h" // for point_distance, squared_point_distance + +#define TOLERANCE 0.000001 using namespace pcl; using namespace octree; @@ -119,9 +122,7 @@ TEST (PCL, Octree_Pointcloud_Nearest_K_Neighbour_Search) // push all points and their distance to the search point into a priority queue - bruteforce approach. for (std::size_t i = 0; i < cloudIn->size (); i++) { - double pointDist = (((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) + - ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) + - ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z)); + const auto pointDist = pcl_tests::squared_point_distance((*cloudIn)[i], searchPoint); prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, static_cast (i)); @@ -276,7 +277,6 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search) // instantiate point clouds PointCloud::Ptr cloudIn (new PointCloud ()); - PointCloud::Ptr cloudOut (new PointCloud ()); const unsigned int seed = time (nullptr); srand (seed); @@ -301,25 +301,21 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search) static_cast (5.0 * (rand () / static_cast (RAND_MAX)))); } - pcl::search::Search* octree = new pcl::search::Octree (0.001); + pcl::search::Octree octree(0.001); // build octree - double pointDist; double searchRadius = 5.0 * rand () / static_cast (RAND_MAX); // bruteforce radius search - std::vector cloudSearchBruteforce; + std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; for (std::size_t i = 0; i < cloudIn->size (); i++) { - pointDist = std::sqrt ( - ((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) - + ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) - + ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z)); - - if (pointDist <= searchRadius) - { - // add point candidates to vector list - cloudSearchBruteforce.push_back (static_cast (i)); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[i], searchPoint); + if (pointDist <= (searchRadius+TOLERANCE)) { + ++cloudSearchBruteforce_size_upper; + if (pointDist <= (searchRadius-TOLERANCE)) { + ++cloudSearchBruteforce_size_lower; + } } } @@ -327,25 +323,21 @@ TEST (PCL, Octree_Pointcloud_Neighbours_Within_Radius_Search) std::vector cloudNWRRadius; // execute octree radius search - octree->setInputCloud (cloudIn); - octree->radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius); + octree.setInputCloud (cloudIn); + octree.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius); - ASSERT_EQ ( cloudNWRRadius.size() , cloudSearchBruteforce.size()); + ASSERT_GE ( cloudNWRRadius.size() , cloudSearchBruteforce_size_lower); + ASSERT_LE ( cloudNWRRadius.size() , cloudSearchBruteforce_size_upper); - // check if result from octree radius search can be also found in bruteforce search + // check if results from octree radius search are indeed within the search radius for (const auto& current : cloudNWRSearch) { - pointDist = std::sqrt ( - ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) + - ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) + - ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z) - ); - - ASSERT_LE (pointDist, searchRadius); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[current], searchPoint); + ASSERT_LE (pointDist, (searchRadius+TOLERANCE)); } // check if result limitation works - octree->radiusSearch(searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5); + octree.radiusSearch(searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5); ASSERT_LE (cloudNWRRadius.size(), 5); } } diff --git a/test/search/test_organized.cpp b/test/search/test_organized.cpp index ca7f699d849..ccff2517db4 100644 --- a/test/search/test_organized.cpp +++ b/test/search/test_organized.cpp @@ -44,6 +44,9 @@ #include #include #include // for OrganizedNeighbor +#include "precise_distances.h" // for point_distance, squared_point_distance + +#define TOLERANCE 0.000001 using namespace pcl; @@ -138,9 +141,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) // push all points and their distance to the search point into a priority queue - bruteforce approach. for (std::size_t i = 0; i < cloudIn->size (); i++) { - double pointDist = (((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) + - ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) + - ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z)); + double pointDist = pcl_tests::squared_point_distance((*cloudIn)[i], searchPoint); prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, int (i)); @@ -218,24 +219,20 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search) const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; - double pointDist; double searchRadius = 1.0 * (double (rand ()) / double (RAND_MAX)); // bruteforce radius search - std::vector cloudSearchBruteforce; - cloudSearchBruteforce.clear(); + std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; for (std::size_t i = 0; i < cloudIn->size (); i++) { - pointDist = std::sqrt ( - ((*cloudIn)[i].x - searchPoint.x) * ((*cloudIn)[i].x - searchPoint.x) - + ((*cloudIn)[i].y - searchPoint.y) * ((*cloudIn)[i].y - searchPoint.y) - + ((*cloudIn)[i].z - searchPoint.z) * ((*cloudIn)[i].z - searchPoint.z)); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[i], searchPoint); - if (pointDist <= searchRadius) - { - // add point candidates to vector list - cloudSearchBruteforce.push_back (int (i)); + if (pointDist <= (searchRadius+TOLERANCE)) { + ++cloudSearchBruteforce_size_upper; + if (pointDist <= (searchRadius-TOLERANCE)) { + ++cloudSearchBruteforce_size_lower; + } } } @@ -246,32 +243,16 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search) organizedNeighborSearch.setInputCloud (cloudIn); organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius); - // check if result from organized radius search can be also found in bruteforce search + // check if results from organized radius search are indeed within the search radius for (const auto& current : cloudNWRSearch) { - pointDist = std::sqrt ( - ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) + - ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) + - ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z) - ); - - ASSERT_LE (pointDist, searchRadius); - } - - - // check if bruteforce result from organized radius search can be also found in bruteforce search - for (const auto& current : cloudSearchBruteforce) - { - pointDist = std::sqrt ( - ((*cloudIn)[current].x-searchPoint.x) * ((*cloudIn)[current].x-searchPoint.x) + - ((*cloudIn)[current].y-searchPoint.y) * ((*cloudIn)[current].y-searchPoint.y) + - ((*cloudIn)[current].z-searchPoint.z) * ((*cloudIn)[current].z-searchPoint.z) - ); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[current], searchPoint); - ASSERT_LE (pointDist, searchRadius); + ASSERT_LE (pointDist, (searchRadius+TOLERANCE)); } - ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ()); + ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower); + ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper); // check if result limitation works organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5); diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index 1a7a7ca2e36..fd102c3b705 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -43,21 +43,14 @@ #include #include #include // for OrganizedNeighbor +#include "precise_distances.h" // for point_distance + +#define TOLERANCE 0.000001 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 { @@ -145,7 +138,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search) for (auto it = cloudIn->begin(); it != cloudIn->end(); ++it) { - const auto pointDist = point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(*it, searchPoint); prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it)); pointCandidates.push (pointEntry); } @@ -238,7 +231,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 = point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(*it, searchPoint); prioPointQueueEntry pointEntry (*it, pointDist, std::distance(cloudIn->begin(), it)); pointCandidates.push (pointEntry); } @@ -308,17 +301,17 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) // double searchRadius = 1/10; // bruteforce radius search - std::vector cloudSearchBruteforce; - cloudSearchBruteforce.clear(); + std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) { - const auto pointDist = point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(*it, searchPoint); - if (pointDist <= searchRadius) - { - // add point candidates to vector list - cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it)); + if (pointDist <= (searchRadius+TOLERANCE)) { + ++cloudSearchBruteforce_size_upper; + if (pointDist <= (searchRadius-TOLERANCE)) { + ++cloudSearchBruteforce_size_lower; + } } } @@ -330,22 +323,15 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits::max()); - // check if result from organized radius search can be also found in bruteforce search + // check if results from organized radius search are indeed within the search radius for (const auto it : cloudNWRSearch) { - const auto pointDist = point_distance((*cloudIn)[it], searchPoint); - ASSERT_LE (pointDist, searchRadius); - } - - - // check if bruteforce result from organized radius search can be also found in bruteforce search - for (const auto it : cloudSearchBruteforce) - { - const auto pointDist = point_distance((*cloudIn)[it], searchPoint); - ASSERT_LE (pointDist, searchRadius); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[it], searchPoint); + ASSERT_LE (pointDist, (searchRadius+TOLERANCE)); } - ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ()); + ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower); + ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper); // check if result limitation works organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5); @@ -409,7 +395,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 = point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(*it, searchPoint); if (pointDist <= searchRadius) { @@ -513,36 +499,29 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; // bruteforce radius search - std::vector cloudSearchBruteforce; - cloudSearchBruteforce.clear(); + std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) { - const auto pointDist = point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(*it, searchPoint); - if (pointDist <= searchRadius) - { - // add point candidates to vector list - cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it)); + if (pointDist <= (searchRadius+TOLERANCE)) { + ++cloudSearchBruteforce_size_upper; + if (pointDist <= (searchRadius-TOLERANCE)) { + ++cloudSearchBruteforce_size_lower; + } } } - // check if result from organized radius search can be also found in bruteforce search + // check if results from organized radius search are indeed within the search radius for (const auto it : cloudNWRSearch) { - const auto pointDist = point_distance((*cloudIn)[it], searchPoint); - ASSERT_LE (pointDist, searchRadius); - } - - - // check if bruteforce result from organized radius search can be also found in bruteforce search - for (const auto it : cloudSearchBruteforce) - { - const auto pointDist = point_distance((*cloudIn)[it], searchPoint); - ASSERT_LE (pointDist, searchRadius); + const auto pointDist = pcl_tests::point_distance((*cloudIn)[it], searchPoint); + ASSERT_LE (pointDist, (searchRadius+TOLERANCE)); } - ASSERT_EQ (cloudNWRRadius.size() , cloudSearchBruteforce.size ()); + ASSERT_GE (cloudNWRRadius.size() , cloudSearchBruteforce_size_lower); + ASSERT_LE (cloudNWRRadius.size() , cloudSearchBruteforce_size_upper); // check if result limitation works organizedNeighborSearch.radiusSearch (searchPoint, searchRadius, cloudNWRSearch, cloudNWRRadius, 5); From 225bc851192861225ffd4901dccb5c72aaf1ee3c Mon Sep 17 00:00:00 2001 From: root Date: Sat, 22 Oct 2022 08:11:23 +0200 Subject: [PATCH 019/288] Use initialization list instead of ctor body (useInitializationList) --- .../pipeline/local_recognizer.h | 3 +- apps/cloud_composer/src/items/cloud_item.cpp | 2 +- .../pcl/apps/render_views_tesselated_sphere.h | 3 +- .../src/transformCommand.cpp | 4 +- common/include/pcl/common/impl/random.hpp | 8 +- features/include/pcl/features/grsd.h | 2 +- filters/include/pcl/filters/fast_bilateral.h | 2 +- octree/include/pcl/octree/octree_nodes.h | 17 ++-- outofcore/src/visualization/camera.cpp | 14 ++-- outofcore/src/visualization/viewport.cpp | 2 +- .../face_detection/rf_face_detector_trainer.h | 82 +++++++------------ recognition/src/cg/hough_3d.cpp | 5 +- simulation/src/glsl_shader.cpp | 2 +- simulation/src/model.cpp | 7 +- simulation/src/sum_reduce.cpp | 4 +- stereo/src/stereo_grabber.cpp | 4 +- test/search/test_organized.cpp | 2 +- test/search/test_organized_index.cpp | 2 +- visualization/src/image_viewer.cpp | 5 +- visualization/src/pcl_plotter.cpp | 12 ++- 20 files changed, 75 insertions(+), 107 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h index 32f9fbd7c01..8aece90423d 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/local_recognizer.h @@ -195,13 +195,12 @@ class PCL_EXPORTS LocalRecognitionPipeline { } public: - LocalRecognitionPipeline() + LocalRecognitionPipeline() : search_model_("") { use_cache_ = false; threshold_accept_model_hypothesis_ = 0.2f; ICP_iterations_ = 30; kdtree_splits_ = 512; - search_model_ = ""; VOXEL_SIZE_ICP_ = 0.0025f; compute_table_plane_ = false; } diff --git a/apps/cloud_composer/src/items/cloud_item.cpp b/apps/cloud_composer/src/items/cloud_item.cpp index 8f70e6b0f0f..d955fff374a 100644 --- a/apps/cloud_composer/src/items/cloud_item.cpp +++ b/apps/cloud_composer/src/items/cloud_item.cpp @@ -14,6 +14,7 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name, const Eigen::Quaternionf& orientation, bool make_templated_cloud) : CloudComposerItem (std::move(name)) + , cloud_blob_ptr_ (cloud_ptr) , origin_ (origin) , orientation_ (orientation) , template_cloud_set_ (false) @@ -25,7 +26,6 @@ pcl::cloud_composer::CloudItem::CloudItem (QString name, // qDebug () << "Cloud size before passthrough : "<width<<"x"<height; // qDebug () << "Cloud size after passthrough : "<width<<"x"<height; - cloud_blob_ptr_ = cloud_ptr; pcl::PCLPointCloud2::ConstPtr const_cloud_ptr = cloud_ptr; this->setData (QVariant::fromValue (const_cloud_ptr), ItemDataRole::CLOUD_BLOB); this->setData (QVariant::fromValue (origin_), ItemDataRole::ORIGIN); diff --git a/apps/include/pcl/apps/render_views_tesselated_sphere.h b/apps/include/pcl/apps/render_views_tesselated_sphere.h index cc59e3b0b4c..b121e497b13 100644 --- a/apps/include/pcl/apps/render_views_tesselated_sphere.h +++ b/apps/include/pcl/apps/render_views_tesselated_sphere.h @@ -51,7 +51,7 @@ class PCL_EXPORTS RenderViewsTesselatedSphere { }; public: - RenderViewsTesselatedSphere() + RenderViewsTesselatedSphere() : campos_constraints_func_(camPosConstraintsAllTrue()) { resolution_ = 150; tesselation_level_ = 1; @@ -60,7 +60,6 @@ class PCL_EXPORTS RenderViewsTesselatedSphere { radius_sphere_ = 1.f; compute_entropy_ = false; gen_organized_ = false; - campos_constraints_func_ = camPosConstraintsAllTrue(); } void diff --git a/apps/point_cloud_editor/src/transformCommand.cpp b/apps/point_cloud_editor/src/transformCommand.cpp index 34da2014e5b..8ed83d7a143 100644 --- a/apps/point_cloud_editor/src/transformCommand.cpp +++ b/apps/point_cloud_editor/src/transformCommand.cpp @@ -50,9 +50,9 @@ TransformCommand::TransformCommand(const ConstSelectionPtr& selection_ptr, float translate_z) : selection_ptr_(selection_ptr), cloud_ptr_(std::move(cloud_ptr)), translate_x_(translate_x), translate_y_(translate_y), - translate_z_(translate_z) + translate_z_(translate_z), + internal_selection_ptr_(new Selection(*selection_ptr)) { - internal_selection_ptr_ = SelectionPtr(new Selection(*selection_ptr)); std::copy(matrix, matrix + MATRIX_SIZE, transform_matrix_); const float *cloud_matrix = cloud_ptr_->getMatrix(); std::copy(cloud_matrix, cloud_matrix + MATRIX_SIZE, cloud_matrix_); diff --git a/common/include/pcl/common/impl/random.hpp b/common/include/pcl/common/impl/random.hpp index a53d5226cb9..68f9ab9133d 100644 --- a/common/include/pcl/common/impl/random.hpp +++ b/common/include/pcl/common/impl/random.hpp @@ -51,9 +51,9 @@ namespace common template UniformGenerator::UniformGenerator(T min, T max, std::uint32_t seed) - : distribution_ (min, max) + : parameters_ ({min, max, seed}) + , distribution_ (min, max) { - parameters_ = Parameters (min, max, seed); if(parameters_.seed != static_cast (-1)) rng_.seed (seed); } @@ -111,9 +111,9 @@ UniformGenerator::setParameters (const Parameters& parameters) template NormalGenerator::NormalGenerator(T mean, T sigma, std::uint32_t seed) - : distribution_ (mean, sigma) + : parameters_ ({mean, sigma, seed}) + , distribution_ (mean, sigma) { - parameters_ = Parameters (mean, sigma, seed); if(parameters_.seed != static_cast (-1)) rng_.seed (seed); } diff --git a/features/include/pcl/features/grsd.h b/features/include/pcl/features/grsd.h index 9d4ba3b677c..f9d18051c1d 100644 --- a/features/include/pcl/features/grsd.h +++ b/features/include/pcl/features/grsd.h @@ -88,9 +88,9 @@ namespace pcl /** \brief Constructor. */ GRSDEstimation () + : relative_coordinates_all_(getAllNeighborCellIndices()) { feature_name_ = "GRSDEstimation"; - relative_coordinates_all_ = getAllNeighborCellIndices (); }; /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature diff --git a/filters/include/pcl/filters/fast_bilateral.h b/filters/include/pcl/filters/fast_bilateral.h index 25e4f2e02c5..d71879fdd3f 100644 --- a/filters/include/pcl/filters/fast_bilateral.h +++ b/filters/include/pcl/filters/fast_bilateral.h @@ -116,11 +116,11 @@ namespace pcl { public: Array3D (const std::size_t width, const std::size_t height, const std::size_t depth) + : v_({(width*height*depth), Eigen::Vector2f (0.0f, 0.0f), Eigen::aligned_allocator()}) { x_dim_ = width; y_dim_ = height; z_dim_ = depth; - v_ = std::vector > (width*height*depth, Eigen::Vector2f (0.0f, 0.0f)); } inline Eigen::Vector2f& diff --git a/octree/include/pcl/octree/octree_nodes.h b/octree/include/pcl/octree/octree_nodes.h index 6775ac8111c..447449782a4 100644 --- a/octree/include/pcl/octree/octree_nodes.h +++ b/octree/include/pcl/octree/octree_nodes.h @@ -84,10 +84,9 @@ class OctreeLeafNode : public OctreeNode { OctreeLeafNode() : OctreeNode() {} /** \brief Copy constructor. */ - OctreeLeafNode(const OctreeLeafNode& source) : OctreeNode() - { - container_ = source.container_; - } + OctreeLeafNode(const OctreeLeafNode& source) + : OctreeNode(), container_(source.container_) + {} /** \brief Empty deconstructor. */ @@ -180,17 +179,11 @@ template class OctreeBranchNode : public OctreeNode { public: /** \brief Empty constructor. */ - OctreeBranchNode() : OctreeNode() - { - // reset pointer to child node vectors - child_node_array_ = {}; - } + OctreeBranchNode() : OctreeNode() {} - /** \brief Empty constructor. */ + /** \brief Copy constructor. */ OctreeBranchNode(const OctreeBranchNode& source) : OctreeNode() { - child_node_array_ = {}; - for (unsigned char i = 0; i < 8; ++i) if (source.child_node_array_[i]) { child_node_array_[i] = source.child_node_array_[i]->deepCopy(); diff --git a/outofcore/src/visualization/camera.cpp b/outofcore/src/visualization/camera.cpp index cf051c38bbf..cee7fdaf1a4 100644 --- a/outofcore/src/visualization/camera.cpp +++ b/outofcore/src/visualization/camera.cpp @@ -20,10 +20,11 @@ // Operators // ----------------------------------------------------------------------------- -Camera::Camera (std::string name) : - Object (name), display_ (false) +Camera::Camera (std::string name) + : Object (name) + , camera_ (vtkSmartPointer::New ()) + , display_ (false) { - camera_ = vtkSmartPointer::New (); camera_->SetClippingRange(0.0001, 100000); camera_actor_ = vtkSmartPointer::New (); @@ -43,10 +44,11 @@ Camera::Camera (std::string name) : hull_actor_->GetProperty ()->SetOpacity (0.25); } -Camera::Camera (std::string name, vtkSmartPointer camera) : - Object (name), display_ (false) +Camera::Camera (std::string name, vtkSmartPointer camera) + : Object (name) + , camera_ (camera) + , display_ (false) { - camera_ = camera; camera_->SetClippingRange(0.0001, 100000); camera_actor_ = vtkSmartPointer::New (); diff --git a/outofcore/src/visualization/viewport.cpp b/outofcore/src/visualization/viewport.cpp index 82c8f67fa54..0620f4242fe 100644 --- a/outofcore/src/visualization/viewport.cpp +++ b/outofcore/src/visualization/viewport.cpp @@ -25,8 +25,8 @@ // ----------------------------------------------------------------------------- Viewport::Viewport (vtkSmartPointer window, double xmin/*=0.0*/, double ymin/*=0.0*/, double xmax/*=1.0*/, double ymax/*=1.0*/) + : renderer_ (vtkSmartPointer::New ()) { - renderer_ = vtkSmartPointer::New (); renderer_->SetViewport (xmin, ymin, xmax, ymax); renderer_->GradientBackgroundOn (); renderer_->SetBackground (.1, .1, .1); diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h index 2fb4d80408b..32b68f3203a 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h @@ -16,65 +16,45 @@ namespace pcl class PCL_EXPORTS RFFaceDetectorTrainer { private: - int w_size_; - int max_patch_size_; - int stride_sw_; - int ntrees_; - std::string forest_filename_; - int nfeatures_; - float thres_face_; - int num_images_; - float trans_max_variance_; + int w_size_ {80}; + int max_patch_size_ {40}; + int stride_sw_ {4}; + int ntrees_ {10}; + std::string forest_filename_ {"forest.txt"}; + int nfeatures_ {10000}; + float thres_face_ {1.f}; + int num_images_ {1000}; + float trans_max_variance_ {1600.f}; std::size_t min_votes_size_; - int used_for_pose_; - bool use_normals_; - std::string directory_; - float HEAD_ST_DIAMETER_; - float larger_radius_ratio_; - std::vector > head_center_votes_; - std::vector > > head_center_votes_clustered_; - std::vector > > head_center_original_votes_clustered_; - std::vector > angle_votes_; - std::vector uncertainties_; - std::vector > head_clusters_centers_; - std::vector > head_clusters_rotation_; - - pcl::PointCloud::Ptr input_; - pcl::PointCloud::Ptr face_heat_map_; + int used_for_pose_ {std::numeric_limits::max ()}; + bool use_normals_ {false}; + std::string directory_ {""}; + float HEAD_ST_DIAMETER_ {0.2364f}; + float larger_radius_ratio_ {1.5f}; + std::vector > head_center_votes_{}; + std::vector > > head_center_votes_clustered_{}; + std::vector > > head_center_original_votes_clustered_{}; + std::vector > angle_votes_{}; + std::vector uncertainties_{}; + std::vector > head_clusters_centers_{}; + std::vector > head_clusters_rotation_{}; + + pcl::PointCloud::Ptr input_{}; + pcl::PointCloud::Ptr face_heat_map_{}; using NodeType = face_detection::RFTreeNode; - pcl::DecisionForest forest_; + pcl::DecisionForest forest_{}; - std::string model_path_; - bool pose_refinement_; - int icp_iterations_; + std::string model_path_ {"face_mesh.ply"}; + bool pose_refinement_ {false}; + int icp_iterations_{}; - pcl::PointCloud::Ptr model_original_; - float res_; + pcl::PointCloud::Ptr model_original_{}; + float res_ {0.005f}; public: - RFFaceDetectorTrainer() - { - w_size_ = 80; - max_patch_size_ = 40; - stride_sw_ = 4; - ntrees_ = 10; - forest_filename_ = std::string ("forest.txt"); - nfeatures_ = 10000; - thres_face_ = 1.f; - num_images_ = 1000; - trans_max_variance_ = 1600.f; - used_for_pose_ = std::numeric_limits::max (); - use_normals_ = false; - directory_ = std::string (""); - HEAD_ST_DIAMETER_ = 0.2364f; - larger_radius_ratio_ = 1.5f; - face_heat_map_.reset (); - model_path_ = std::string ("face_mesh.ply"); - pose_refinement_ = false; - res_ = 0.005f; - } + RFFaceDetectorTrainer() = default; virtual ~RFFaceDetectorTrainer() = default; diff --git a/recognition/src/cg/hough_3d.cpp b/recognition/src/cg/hough_3d.cpp index 0e591a0ed18..758046dbb55 100644 --- a/recognition/src/cg/hough_3d.cpp +++ b/recognition/src/cg/hough_3d.cpp @@ -48,10 +48,9 @@ PCL_INSTANTIATE_PRODUCT(Hough3DGrouping, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::P //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// pcl::recognition::HoughSpace3D::HoughSpace3D (const Eigen::Vector3d &min_coord, const Eigen::Vector3d &bin_size, const Eigen::Vector3d &max_coord) + : min_coord_ (min_coord) + , bin_size_ (bin_size) { - min_coord_ = min_coord; - bin_size_ = bin_size; - for (int i = 0; i < 3; ++i) { bin_count_[i] = static_cast (std::ceil ((max_coord[i] - min_coord_[i]) / bin_size_[i])); diff --git a/simulation/src/glsl_shader.cpp b/simulation/src/glsl_shader.cpp index ca6443a0fa7..4eed218b3af 100644 --- a/simulation/src/glsl_shader.cpp +++ b/simulation/src/glsl_shader.cpp @@ -30,7 +30,7 @@ readTextFile(const char* filename) return buf; } -pcl::simulation::gllib::Program::Program() { program_id_ = glCreateProgram(); } +pcl::simulation::gllib::Program::Program() : program_id_(glCreateProgram()) {} pcl::simulation::gllib::Program::~Program() = default; diff --git a/simulation/src/model.cpp b/simulation/src/model.cpp index d1bf600e09f..93c468e9ed1 100644 --- a/simulation/src/model.cpp +++ b/simulation/src/model.cpp @@ -288,10 +288,11 @@ pcl::simulation::Quad::render() const } pcl::simulation::TexturedQuad::TexturedQuad(int width, int height) -: width_(width), height_(height) +: width_(width) +, height_(height) +, program_( + gllib::Program::loadProgramFromFile("single_texture.vert", "single_texture.frag")) { - program_ = - gllib::Program::loadProgramFromFile("single_texture.vert", "single_texture.frag"); program_->use(); Eigen::Matrix MVP; MVP.setIdentity(); diff --git a/simulation/src/sum_reduce.cpp b/simulation/src/sum_reduce.cpp index 20105624cbe..e4b95bfe6c9 100644 --- a/simulation/src/sum_reduce.cpp +++ b/simulation/src/sum_reduce.cpp @@ -3,12 +3,10 @@ using namespace pcl::simulation; pcl::simulation::SumReduce::SumReduce(int width, int height, int levels) -: levels_(levels), width_(width), height_(height) +: levels_(levels), width_(width), height_(height), sum_program_(new gllib::Program()) { std::cout << "SumReduce: levels: " << levels_ << std::endl; - // Load shader - sum_program_ = gllib::Program::Ptr(new gllib::Program()); // TODO: to remove file dependency include the shader source in the binary if (!sum_program_->addShaderFile("sum_score.vert", gllib::VERTEX)) { std::cout << "Failed loading vertex shader" << std::endl; diff --git a/stereo/src/stereo_grabber.cpp b/stereo/src/stereo_grabber.cpp index 2be9bf1699d..0cdcab10a81 100644 --- a/stereo/src/stereo_grabber.cpp +++ b/stereo/src/stereo_grabber.cpp @@ -78,11 +78,11 @@ pcl::StereoGrabberBase::StereoGrabberImpl::StereoGrabberImpl( , frames_per_second_(frames_per_second) , repeat_(repeat) , running_(false) +, pair_files_({pair_files}) , time_trigger_(1.0 / static_cast(std::max(frames_per_second, 0.001f)), [this] { trigger(); }) , valid_(false) { - pair_files_.push_back(pair_files); pair_iterator_ = pair_files_.begin(); } @@ -96,11 +96,11 @@ pcl::StereoGrabberBase::StereoGrabberImpl::StereoGrabberImpl( , frames_per_second_(frames_per_second) , repeat_(repeat) , running_(false) +, pair_files_(files) , time_trigger_(1.0 / static_cast(std::max(frames_per_second, 0.001f)), [this] { trigger(); }) , valid_(false) { - pair_files_ = files; pair_iterator_ = pair_files_.begin(); } diff --git a/test/search/test_organized.cpp b/test/search/test_organized.cpp index ca7f699d849..684b4345ab8 100644 --- a/test/search/test_organized.cpp +++ b/test/search/test_organized.cpp @@ -54,8 +54,8 @@ class prioPointQueueEntry prioPointQueueEntry () = default; prioPointQueueEntry (PointXYZ& point_arg, double pointDistance_arg, int pointIdx_arg) + : point_ (point_arg) { - point_ = point_arg; pointDistance_ = pointDistance_arg; pointIdx_ = pointIdx_arg; } diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index 1a7a7ca2e36..a5158cdae5e 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -64,8 +64,8 @@ class prioPointQueueEntry public: prioPointQueueEntry () = default; prioPointQueueEntry (PointXYZ& point_arg, double pointDistance_arg, int pointIdx_arg) + : point_ (point_arg) { - point_ = point_arg; pointDistance_ = pointDistance_arg; pointIdx_ = pointIdx_arg; } diff --git a/visualization/src/image_viewer.cpp b/visualization/src/image_viewer.cpp index 588eb6ca85b..45486570916 100644 --- a/visualization/src/image_viewer.cpp +++ b/visualization/src/image_viewer.cpp @@ -54,7 +54,8 @@ ////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::ImageViewer::ImageViewer (const std::string& window_title) - : mouse_command_ (vtkSmartPointer::New ()) + : interactor_ (vtkSmartPointer ::Take (vtkRenderWindowInteractorFixNew ())) + , mouse_command_ (vtkSmartPointer::New ()) , keyboard_command_ (vtkSmartPointer::New ()) , win_ (vtkSmartPointer::New ()) , ren_ (vtkSmartPointer::New ()) @@ -65,8 +66,6 @@ pcl::visualization::ImageViewer::ImageViewer (const std::string& window_title) , timer_id_ () , algo_ (vtkSmartPointer::New ()) { - interactor_ = vtkSmartPointer ::Take (vtkRenderWindowInteractorFixNew ()); - // Prepare for image flip algo_->SetInterpolationModeToCubic (); algo_->PreserveImageExtentOn (); diff --git a/visualization/src/pcl_plotter.cpp b/visualization/src/pcl_plotter.cpp index afa6a932c06..afe4ec6741b 100644 --- a/visualization/src/pcl_plotter.cpp +++ b/visualization/src/pcl_plotter.cpp @@ -64,14 +64,12 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::PCLPlotter::PCLPlotter (char const *name) + : view_ (vtkSmartPointer::New ()) + , chart_(vtkSmartPointer::New()) + , color_series_(vtkSmartPointer::New ()) + , exit_loop_timer_(vtkSmartPointer::New ()) + , exit_callback_(vtkSmartPointer::New ()) { - //constructing - view_ = vtkSmartPointer::New (); - chart_=vtkSmartPointer::New(); - color_series_ = vtkSmartPointer::New (); - exit_loop_timer_ = vtkSmartPointer::New (); - exit_callback_ = vtkSmartPointer::New (); - //connecting and mandatory bookkeeping view_->GetScene ()->AddItem (chart_); view_->GetRenderWindow ()->SetWindowName (name); From 9a994222f6d840682eeb80aaef762bbbe60c2acb Mon Sep 17 00:00:00 2001 From: "lilong.huang" Date: Thu, 8 Dec 2022 10:18:31 +0800 Subject: [PATCH 020/288] unit test for PCLVisualizer with PointXYZRGB --- test/visualization/test_visualization.cpp | 30 +++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/test/visualization/test_visualization.cpp b/test/visualization/test_visualization.cpp index 5a8b83e1fa9..fd21aa7e4dc 100644 --- a/test/visualization/test_visualization.cpp +++ b/test/visualization/test_visualization.cpp @@ -191,6 +191,36 @@ TEST (PCL, PCLVisualizer_getPointCloudRenderingProperties) EXPECT_EQ (b, 0.); } +// This test was added to make sure the dynamic_cast in updateColorHandlerIndex works correctly +// (see https://github.com/PointCloudLibrary/pcl/issues/5545) +TEST(PCL, PCLVisualizer_updateColorHandlerIndex) { + // create + visualization::PCLVisualizer::Ptr viewer_ptr( + new visualization::PCLVisualizer); + // generates points + common::CloudGenerator> + generator; + PointCloud::Ptr rgb_cloud_ptr(new PointCloud()); + generator.fill(3, 1, *rgb_cloud_ptr); + + PCLPointCloud2::Ptr rgb_cloud2_ptr(new PCLPointCloud2()); + toPCLPointCloud2(*rgb_cloud_ptr, *rgb_cloud2_ptr); + + // add cloud + const std::string cloud_name = "RGB_cloud"; + visualization::PointCloudColorHandlerRGBField::Ptr + color_handler_ptr( + new visualization::PointCloudColorHandlerRGBField( + rgb_cloud2_ptr)); + viewer_ptr->addPointCloud(rgb_cloud2_ptr, + color_handler_ptr, + Eigen::Vector4f::Zero(), + Eigen::Quaternionf(), + cloud_name, + 0); + EXPECT_TRUE(viewer_ptr->updateColorHandlerIndex(cloud_name, 0)); +} + /* ---[ */ int main (int argc, char** argv) From bb214e2f177af7a6b18295ba2c05dd5d7a6167ae Mon Sep 17 00:00:00 2001 From: SunBlack Date: Thu, 22 Dec 2022 16:02:04 +0100 Subject: [PATCH 021/288] Require at least MSVC 2017 --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 42ea83b98a8..b63a78858fd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -26,6 +26,10 @@ endif() project(PCL VERSION 1.13.0.99) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) +if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) + message(FATAL_ERROR "The compiler versions prior to Visual Studio version 2017 are not supported. Please upgrade to a newer version or another compiler!") +endif() + ### ---[ Find universal dependencies set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake/Modules/" ${CMAKE_MODULE_PATH}) From d6edd9e00174f2be589e28d45c83fb26cb07a2af Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 23 Dec 2022 10:14:38 +0100 Subject: [PATCH 022/288] Fix memory problems and memory leaks --- .../pipeline/impl/local_recognizer.hpp | 2 ++ .../click_trackball_interactor_style.cpp | 4 ++-- io/src/ifs_io.cpp | 5 +++-- .../include/pcl/tracking/impl/pyramidal_klt.hpp | 2 ++ visualization/src/point_cloud_handlers.cpp | 15 +++++++++------ 5 files changed, 18 insertions(+), 10 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp index 0bd6b9d6ecf..e2476ef149f 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp @@ -293,6 +293,8 @@ pcl::rec_3d_framework::LocalRecognitionPipeline:: oh.feature_distances_ = feat_dist; object_hypotheses[oh.model_.id_] = oh; } + delete[] indices.ptr(); + delete[] distances.ptr(); } } diff --git a/apps/cloud_composer/src/point_selectors/click_trackball_interactor_style.cpp b/apps/cloud_composer/src/point_selectors/click_trackball_interactor_style.cpp index 141c5d3d79c..791e0218ad6 100644 --- a/apps/cloud_composer/src/point_selectors/click_trackball_interactor_style.cpp +++ b/apps/cloud_composer/src/point_selectors/click_trackball_interactor_style.cpp @@ -53,7 +53,6 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnLeftButtonUp () vtkSmartPointer selected_actor = vtkActor::SafeDownCast(this->InteractionProp); if (selected_actor) { - ManipulationEvent* manip_event = new ManipulationEvent (); //Fetch the actor we manipulated selected_actor->GetMatrix (end_matrix_); @@ -71,6 +70,7 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnLeftButtonUp () } if ( !manipulated_id.isEmpty() ) { + ManipulationEvent* manip_event = new ManipulationEvent (); manip_event->addManipulation (manipulated_id, start_matrix_, end_matrix_); this->InvokeEvent (this->manipulation_complete_event_, manip_event); } @@ -88,7 +88,6 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnRightButtonUp () vtkSmartPointer selected_actor = vtkActor::SafeDownCast(this->InteractionProp); if (selected_actor) { - ManipulationEvent* manip_event = new ManipulationEvent (); //Fetch the actor we manipulated selected_actor->GetMatrix (end_matrix_); @@ -106,6 +105,7 @@ pcl::cloud_composer::ClickTrackballStyleInteractor::OnRightButtonUp () } if ( !manipulated_id.isEmpty() ) { + ManipulationEvent* manip_event = new ManipulationEvent (); manip_event->addManipulation (manipulated_id, start_matrix_, end_matrix_); this->InvokeEvent (this->manipulation_complete_event_, manip_event); } diff --git a/io/src/ifs_io.cpp b/io/src/ifs_io.cpp index 998e1fecdf5..5246b9c7c5f 100644 --- a/io/src/ifs_io.cpp +++ b/io/src/ifs_io.cpp @@ -284,13 +284,14 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int fs.read (reinterpret_cast(&length_of_keyword), sizeof (std::uint32_t)); char *keyword = new char [length_of_keyword]; fs.read (keyword, sizeof (char) * length_of_keyword); - if (strcmp (keyword, "TRIANGLES")) + const bool keyword_is_triangles = (strcmp (keyword, "TRIANGLES") == 0); + delete[] keyword; + if (!keyword_is_triangles) { PCL_ERROR ("[pcl::IFSReader::read] File %s is does not contain facets!\n", file_name.c_str ()); fs.close (); return (-1); } - delete[] keyword; // Read the number of facets std::uint32_t nr_facets; fs.read (reinterpret_cast(&nr_facets), sizeof (std::uint32_t)); diff --git a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp index 4ee37e28d39..29d0fc9b6f8 100644 --- a/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp +++ b/tracking/include/pcl/tracking/impl/pyramidal_klt.hpp @@ -225,6 +225,8 @@ PyramidalKLTTracker::derivatives(const FloatImage& src, grad_y_row[x] = (trow1[x + 1] + trow1[x - 1]) * 3 + trow1[x] * 10; } } + delete[] row0; + delete[] row1; } /////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/visualization/src/point_cloud_handlers.cpp b/visualization/src/point_cloud_handlers.cpp index ee9f06cf4ed..06d3d53ae74 100644 --- a/visualization/src/point_cloud_handlers.cpp +++ b/visualization/src/point_cloud_handlers.cpp @@ -181,9 +181,10 @@ pcl::visualization::PointCloudColorHandlerRGBField::getColo } if (j != 0) scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE); - else + else { scalars->SetNumberOfTuples (0); - //delete [] colors; + delete [] colors; + } return scalars; } @@ -565,9 +566,10 @@ pcl::visualization::PointCloudColorHandlerRGBAField::getCol } if (j != 0) scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE); - else + else { scalars->SetNumberOfTuples (0); - //delete [] colors; + delete [] colors; + } return scalars; } @@ -670,9 +672,10 @@ pcl::visualization::PointCloudColorHandlerLabelField::getCo } if (j != 0) scalars->SetArray (colors, j, 0, vtkUnsignedCharArray::VTK_DATA_ARRAY_DELETE); - else + else { scalars->SetNumberOfTuples (0); - //delete [] colors; + delete [] colors; + } return scalars; } From 7287da79a7fd0fced3922ef612d79bc5b7264ca5 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 23 Dec 2022 10:42:15 +0100 Subject: [PATCH 023/288] Fix bump_post_release It produced something like ros.99 instead of 1.13.0.99 --- .dev/scripts/bump_post_release.bash | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/.dev/scripts/bump_post_release.bash b/.dev/scripts/bump_post_release.bash index a89235c68a6..4cca90af3dc 100755 --- a/.dev/scripts/bump_post_release.bash +++ b/.dev/scripts/bump_post_release.bash @@ -1,10 +1,9 @@ #! /usr/bin/env bash -new_version=$(git tag | sort -rV | head -1 | cut -d- -f 2).99 - # Mac users either use gsed or add "" after -i if ls | grep README -q; then - sed -i "s,VERSION [0-9.]*),VERSION ${new_version})," CMakeLists.txt + # Just add .99 at the end of the version + sed -i "s,PCL VERSION [0-9.]*,&.99," CMakeLists.txt else echo "Don't think this is the root directory" 1>&2 exit 4 From 8b9fc03418fa17745213bb7d55e3a148807948cf Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 23 Dec 2022 11:37:12 +0100 Subject: [PATCH 024/288] Fix multiple small errors and make improvements - Simplify tools/image_viewer.cpp - OrganizedFastMesh: add test whether input is organized - extractEuclideanClusters: replace exit (should not be used in libraries) - OrganizedPointCloudCompression: add return in case of stream error --- .../impl/organized_pointcloud_compression.hpp | 3 +++ registration/include/pcl/registration/bfgs.h | 4 ++-- .../include/pcl/segmentation/impl/extract_clusters.hpp | 3 +-- .../include/pcl/surface/impl/organized_fast_mesh.hpp | 8 ++++++++ tools/image_viewer.cpp | 10 +++------- 5 files changed, 17 insertions(+), 11 deletions(-) diff --git a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp index 12072da075a..f86425e2ab4 100644 --- a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp +++ b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp @@ -335,6 +335,9 @@ namespace pcl // decode PNG compressed rgb data decodePNGToImage (compressedColor, colorData, png_width, png_height, png_channels); + } else { + PCL_ERROR("[OrganizedPointCloudCompression::decodePointCloud] Unable to find an encoded point cloud in the input stream!\n"); + return false; } if (disparityShift==0.0f) diff --git a/registration/include/pcl/registration/bfgs.h b/registration/include/pcl/registration/bfgs.h index 3bf653b526a..0d3dde69528 100644 --- a/registration/include/pcl/registration/bfgs.h +++ b/registration/include/pcl/registration/bfgs.h @@ -101,7 +101,7 @@ struct BFGSDummyFunctor { virtual void fdf(const VectorType& x, Scalar& f, VectorType& df) = 0; virtual BFGSSpace::Status - checkGradient(const VectorType& g) + checkGradient(const VectorType& /*g*/) { return BFGSSpace::NotStarted; }; @@ -351,7 +351,7 @@ BFGS::minimize(FVectorType& x) BFGSSpace::Status status = minimizeInit(x); do { status = minimizeOneStep(x); - iter++; + ++iter; } while (status == BFGSSpace::Success && iter < parameters.max_iters); return status; } diff --git a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp index f5ec59ad88d..89ee6a01456 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp @@ -122,7 +122,6 @@ pcl::extractEuclideanClusters (const PointCloud &cloud, } ////////////////////////////////////////////////////////////////////////////////////////////// -/** @todo: fix the return value, make sure the exit is not needed anymore*/ template void pcl::extractEuclideanClusters (const PointCloud &cloud, const Indices &indices, @@ -174,7 +173,7 @@ pcl::extractEuclideanClusters (const PointCloud &cloud, if( ret == -1) { PCL_ERROR("[pcl::extractEuclideanClusters] Received error code -1 from radiusSearch\n"); - exit(0); + return; } if (!ret) { diff --git a/surface/include/pcl/surface/impl/organized_fast_mesh.hpp b/surface/include/pcl/surface/impl/organized_fast_mesh.hpp index 1b99b918366..71b4dc59c74 100644 --- a/surface/include/pcl/surface/impl/organized_fast_mesh.hpp +++ b/surface/include/pcl/surface/impl/organized_fast_mesh.hpp @@ -48,6 +48,10 @@ template void pcl::OrganizedFastMesh::performReconstruction (pcl::PolygonMesh &output) { + if (!input_->isOrganized()) { + PCL_ERROR("[OrganizedFastMesh::performReconstruction] Input point cloud must be organized but isn't!\n"); + return; + } reconstructPolygons (output.polygons); // Get the field names @@ -69,6 +73,10 @@ pcl::OrganizedFastMesh::performReconstruction (pcl::PolygonMesh &outpu template void pcl::OrganizedFastMesh::performReconstruction (std::vector &polygons) { + if (!input_->isOrganized()) { + PCL_ERROR("[OrganizedFastMesh::performReconstruction] Input point cloud must be organized but isn't!\n"); + return; + } reconstructPolygons (polygons); } diff --git a/tools/image_viewer.cpp b/tools/image_viewer.cpp index 94e048f8562..9a51397d181 100644 --- a/tools/image_viewer.cpp +++ b/tools/image_viewer.cpp @@ -46,21 +46,17 @@ int main (int, char ** argv) { - pcl::PCDReader reader; - pcl::PCLPointCloud2 cloud; - reader.read (argv[1], cloud); - pcl::PointCloud xyz; - pcl::fromPCLPointCloud2 (cloud, xyz); + pcl::io::loadPCDFile(argv[1], xyz); pcl::visualization::ImageViewer depth_image_viewer_; - float* img = new float[cloud.width * cloud.height]; + float* img = new float[xyz.width * xyz.height]; for (int i = 0; i < static_cast (xyz.size ()); ++i) img[i] = xyz[i].z; depth_image_viewer_.showFloatImage (img, - cloud.width, cloud.height, + xyz.width, xyz.height, std::numeric_limits::min (), // Scale so that the colors look brigher on screen std::numeric_limits::max () / 10, From 205d7e824f20aae446dd7f04907f3b27b74e414d Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 28 Dec 2022 14:41:37 +0100 Subject: [PATCH 025/288] [tools] Remove NaNs from clouds after loading in icp tool Fixes https://github.com/PointCloudLibrary/pcl/issues/5531 --- tools/icp.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/tools/icp.cpp b/tools/icp.cpp index 476b2f1df38..41f51c2e70b 100644 --- a/tools/icp.cpp +++ b/tools/icp.cpp @@ -40,6 +40,7 @@ #include #include #include +#include // for removeNaNFromPointCloud #include #include #include @@ -97,6 +98,8 @@ main (int argc, char **argv) std::cout << "Could not read file" << std::endl; return -1; } + pcl::Indices dummy_indices; + pcl::removeNaNFromPointCloud(*data, *data, dummy_indices); if (!iicp.registerCloud (data)) { From 0843d7284f98535760f6c539841358b44a01441a Mon Sep 17 00:00:00 2001 From: Alex Date: Fri, 30 Dec 2022 10:36:32 +0200 Subject: [PATCH 026/288] Fix pcl:ply_reader_fuzzer: Crash in pcl::PLYReader::read (#5552) * Fixes pcl:ply_reader_fuzzer: Crash in pcl::PLYReader::read https://bugs.chromium.org/p/oss-fuzz/issues/detail?id=50663 The root cause is that `srcIdx` is very big and `srcIdx + cloud_->point_step` leads to integer overflow, that bypasses the `cloud_->data.size()` check. * Update ply_io.cpp --- io/src/ply_io.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index ea6e306b3c9..85d132fef7a 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -647,7 +647,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, } else { - const auto srcIdx = (*range_grid_)[r][0] * cloud_->point_step; + const std::size_t srcIdx = (*range_grid_)[r][0] * cloud_->point_step; if (srcIdx + cloud_->point_step > cloud_->data.size()) { PCL_ERROR ("[pcl::PLYReader::read] invalid data index (%lu)!\n", srcIdx); @@ -746,7 +746,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, } else { - const auto srcIdx = (*range_grid_)[r][0] * cloud_->point_step; + const std::size_t srcIdx = (*range_grid_)[r][0] * cloud_->point_step; if (srcIdx + cloud_->point_step > cloud_->data.size()) { PCL_ERROR ("[pcl::PLYReader::read] invalid data index (%lu)!\n", srcIdx); From 38cbd621d0632895e1bed04841a612f97f574abc Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 31 Dec 2022 15:09:57 +0100 Subject: [PATCH 027/288] Make apps Qt6 compatible --- apps/cloud_composer/src/cloud_composer.cpp | 1 + apps/in_hand_scanner/CMakeLists.txt | 7 +++++++ .../include/pcl/apps/in_hand_scanner/opengl_viewer.h | 4 ++-- apps/in_hand_scanner/src/offline_integration.cpp | 1 + apps/in_hand_scanner/src/opengl_viewer.cpp | 7 ++++--- apps/modeler/src/main_window.cpp | 2 +- apps/point_cloud_editor/CMakeLists.txt | 3 +++ .../pcl/apps/point_cloud_editor/cloudEditorWidget.h | 4 ++-- .../include/pcl/apps/point_cloud_editor/select2DTool.h | 2 +- apps/point_cloud_editor/src/cloud.cpp | 1 - apps/point_cloud_editor/src/cloudEditorWidget.cpp | 6 +----- apps/point_cloud_editor/src/select1DTool.cpp | 1 - cmake/pcl_find_qt.cmake | 2 +- 13 files changed, 24 insertions(+), 17 deletions(-) diff --git a/apps/cloud_composer/src/cloud_composer.cpp b/apps/cloud_composer/src/cloud_composer.cpp index 8529a667827..1302b59819c 100644 --- a/apps/cloud_composer/src/cloud_composer.cpp +++ b/apps/cloud_composer/src/cloud_composer.cpp @@ -10,6 +10,7 @@ #include #include +#include #include #include #include diff --git a/apps/in_hand_scanner/CMakeLists.txt b/apps/in_hand_scanner/CMakeLists.txt index 24d56ba65fb..5c3350ff43b 100644 --- a/apps/in_hand_scanner/CMakeLists.txt +++ b/apps/in_hand_scanner/CMakeLists.txt @@ -91,7 +91,11 @@ PCL_ADD_EXECUTABLE( ${IMPL_INCS} ${UI} BUNDLE) + target_link_libraries("${EXE_NAME}" ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL) +if (${QTX} MATCHES "Qt6") + target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets) +endif() pcl_add_includes("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}" ${INCS}) pcl_add_includes("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}/impl" ${IMPL_INCS}) @@ -108,6 +112,9 @@ PCL_ADD_EXECUTABLE( BUNDLE) target_link_libraries(pcl_offline_integration ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL) +if (${QTX} MATCHES "Qt6") + target_link_libraries(pcl_offline_integration ${QTX}::OpenGLWidgets) +endif() # Add to the compound apps target list(APPEND PCL_APPS_ALL_TARGETS ${PCL_IN_HAND_SCANNER_ALL_TARGETS}) 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 d9b94d72fe8..ee0dd8d0b72 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 @@ -46,7 +46,7 @@ #include #include -#include +#include #include #include @@ -102,7 +102,7 @@ class FaceVertexMesh { * \note Currently you have to derive from this class to use it. Implement the * paintEvent: Call the paint event of this class and declare a QPainter. */ -class PCL_EXPORTS OpenGLViewer : public QGLWidget { +class PCL_EXPORTS OpenGLViewer : public QOpenGLWidget { Q_OBJECT public: diff --git a/apps/in_hand_scanner/src/offline_integration.cpp b/apps/in_hand_scanner/src/offline_integration.cpp index f025e91a669..113a499274e 100644 --- a/apps/in_hand_scanner/src/offline_integration.cpp +++ b/apps/in_hand_scanner/src/offline_integration.cpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include diff --git a/apps/in_hand_scanner/src/opengl_viewer.cpp b/apps/in_hand_scanner/src/opengl_viewer.cpp index 48320e911aa..2002d50276a 100644 --- a/apps/in_hand_scanner/src/opengl_viewer.cpp +++ b/apps/in_hand_scanner/src/opengl_viewer.cpp @@ -56,6 +56,7 @@ #include #include // TODO: PointIHS is not registered +#include #include //////////////////////////////////////////////////////////////////////////////// @@ -101,7 +102,7 @@ pcl::ihs::detail::FaceVertexMesh::FaceVertexMesh(const Mesh& mesh, //////////////////////////////////////////////////////////////////////////////// pcl::ihs::OpenGLViewer::OpenGLViewer(QWidget* parent) -: QGLWidget(parent) +: QOpenGLWidget(parent) , timer_vis_(new QTimer(this)) , colormap_(Colormap::Constant(255)) , vis_conf_norm_(1) @@ -1195,8 +1196,8 @@ pcl::ihs::OpenGLViewer::wheelEvent(QWheelEvent* event) std::max((cam_pivot_ - R_cam_ * o - t_cam_).norm(), .1 / scaling_factor_) / d; // http://doc.qt.digia.com/qt/qwheelevent.html#delta - t_cam_ += - scale * Eigen::Vector3d(R_cam_ * (ez * static_cast(event->delta()))); + t_cam_ += scale * Eigen::Vector3d( + R_cam_ * (ez * static_cast(event->angleDelta().y()))); } } diff --git a/apps/modeler/src/main_window.cpp b/apps/modeler/src/main_window.cpp index b674cadf182..85381af7313 100755 --- a/apps/modeler/src/main_window.cpp +++ b/apps/modeler/src/main_window.cpp @@ -282,7 +282,7 @@ pcl::modeler::MainWindow::updateRecentActions( } recent_items.removeDuplicates(); - int recent_number = std::min(int(MAX_RECENT_NUMBER), recent_items.size()); + int recent_number = std::min(int(MAX_RECENT_NUMBER), recent_items.size()); for (int i = 0; i < recent_number; ++i) { QString text = tr("%1 %2").arg(i + 1).arg(recent_items[i]); recent_actions[i]->setText(text); diff --git a/apps/point_cloud_editor/CMakeLists.txt b/apps/point_cloud_editor/CMakeLists.txt index d46b49f53d2..7374b72e0d7 100644 --- a/apps/point_cloud_editor/CMakeLists.txt +++ b/apps/point_cloud_editor/CMakeLists.txt @@ -87,6 +87,9 @@ PCL_ADD_EXECUTABLE( ${INCS}) target_link_libraries("${EXE_NAME}" ${QTX}::Widgets ${QTX}::OpenGL ${OPENGL_LIBRARIES} ${BOOST_LIBRARIES} pcl_common pcl_io pcl_filters) +if (${QTX} MATCHES "Qt6") + target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets) +endif() PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSYS_NAME}/${SUBSUBSYS_NAME}" ${INCS}) PCL_MAKE_PKGCONFIG(${EXE_NAME} COMPONENT ${SUBSUBSYS_NAME} DESC ${SUBSUBSYS_DESC}) diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h index 7630d224e12..e8fdb0e9280 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h @@ -49,7 +49,7 @@ #include // for pcl::shared_ptr -#include +#include #include @@ -57,7 +57,7 @@ class Selection; /// @brief class declaration for the widget for editing and viewing /// point clouds. -class CloudEditorWidget : public QGLWidget +class CloudEditorWidget : public QOpenGLWidget { Q_OBJECT public: diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h index 985ec4e1469..f48e354552c 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h @@ -40,7 +40,7 @@ #pragma once -#include +#include #include #include diff --git a/apps/point_cloud_editor/src/cloud.cpp b/apps/point_cloud_editor/src/cloud.cpp index 61e82e589f0..5a169e88458 100644 --- a/apps/point_cloud_editor/src/cloud.cpp +++ b/apps/point_cloud_editor/src/cloud.cpp @@ -38,7 +38,6 @@ /// @author Yue Li and Matthew Hielsberg #include -#include #include #include #include diff --git a/apps/point_cloud_editor/src/cloudEditorWidget.cpp b/apps/point_cloud_editor/src/cloudEditorWidget.cpp index 6a8d50f692f..7ba8089f176 100644 --- a/apps/point_cloud_editor/src/cloudEditorWidget.cpp +++ b/apps/point_cloud_editor/src/cloudEditorWidget.cpp @@ -41,8 +41,6 @@ #include #include #include -#include -#include #include @@ -72,8 +70,7 @@ #include CloudEditorWidget::CloudEditorWidget (QWidget *parent) - : QGLWidget(QGLFormat(QGL::DoubleBuffer | QGL::DepthBuffer | - QGL::Rgba | QGL::StencilBuffer), parent), + : QOpenGLWidget(parent), point_size_(2.0f), selected_point_size_(4.0f), cam_fov_(60.0), cam_aspect_(1.0), cam_near_(0.0001), cam_far_(100.0), color_scheme_(COLOR_BY_PURE), is_colored_(false) @@ -116,7 +113,6 @@ CloudEditorWidget::load () tr("Can not load %1.").arg(file_path)); } update(); - updateGL(); } void diff --git a/apps/point_cloud_editor/src/select1DTool.cpp b/apps/point_cloud_editor/src/select1DTool.cpp index cdcf5ceff9e..b60d7ee3509 100644 --- a/apps/point_cloud_editor/src/select1DTool.cpp +++ b/apps/point_cloud_editor/src/select1DTool.cpp @@ -38,7 +38,6 @@ /// @author Yue Li and Matthew Hielsberg #include -#include #include #include #include diff --git a/cmake/pcl_find_qt.cmake b/cmake/pcl_find_qt.cmake index 09192e30d1b..b88758fc396 100644 --- a/cmake/pcl_find_qt.cmake +++ b/cmake/pcl_find_qt.cmake @@ -25,7 +25,7 @@ if(NOT WITH_QT_STR MATCHES "^(AUTO|YES|QT6|QT5)$") endif() if(WITH_QT_STR MATCHES "^(AUTO|YES|QT6)$") - find_package(Qt6 QUIET COMPONENTS Concurrent OpenGL Widgets) + find_package(Qt6 QUIET COMPONENTS Concurrent OpenGL Widgets OpenGLWidgets) set(QT6_FOUND ${Qt6_FOUND}) set(QT_FOUND ${QT6_FOUND}) if (QT6_FOUND) From fa5224d742161ffa82f052878fe1d852236a8779 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 4 Jan 2023 11:44:40 +0100 Subject: [PATCH 028/288] Add new test for LocalMaximum filter --- test/filters/test_local_maximum.cpp | 29 ++++++++++++++++++++++++++--- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/test/filters/test_local_maximum.cpp b/test/filters/test_local_maximum.cpp index dc69cca82b2..3bc10cd6c8d 100644 --- a/test/filters/test_local_maximum.cpp +++ b/test/filters/test_local_maximum.cpp @@ -45,15 +45,13 @@ using namespace pcl; -PointCloud cloud; - ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (Filters, LocalMaximum) { PointCloud cloud_in, cloud_out; cloud_in.height = 1; - cloud_in.width = 3; + cloud_in.width = 4; cloud_in.is_dense = true; cloud_in.resize (4); @@ -73,6 +71,31 @@ TEST (Filters, LocalMaximum) EXPECT_EQ (3, cloud_out.size ()); } +TEST (Filters, LocalMaximum2) // Same as the "LocalMaximum" test above, but the points have a different order +{ + PointCloud cloud_in, cloud_out; + + cloud_in.height = 1; + cloud_in.width = 4; + cloud_in.is_dense = true; + cloud_in.resize (4); + + cloud_in[0].x = 0.5; cloud_in[0].y = 0.5; cloud_in[0].z = 1; // this one should be removed + cloud_in[1].x = 0; cloud_in[1].y = 0; cloud_in[1].z = 0.25; + cloud_in[2].x = 0.25; cloud_in[2].y = 0.25; cloud_in[2].z = 0.5; + cloud_in[3].x = 5; cloud_in[3].y = 5; cloud_in[3].z = 2; + + LocalMaximum lm; + lm.setInputCloud (cloud_in.makeShared ()); + lm.setRadius (1.0f); + lm.filter (cloud_out); + + EXPECT_EQ (0.25f, cloud_out[0].z); + EXPECT_EQ (0.50f, cloud_out[1].z); + EXPECT_EQ (2.00f, cloud_out[2].z); + EXPECT_EQ (3, cloud_out.size ()); +} + /* ---[ */ int main (int argc, char** argv) From 4dbd5c31fd296ad6e0b0e393647c1b9063156603 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 4 Jan 2023 20:31:38 +0100 Subject: [PATCH 029/288] Fix bug in LocalMaximum filter --- filters/include/pcl/filters/impl/local_maximum.hpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/filters/include/pcl/filters/impl/local_maximum.hpp b/filters/include/pcl/filters/impl/local_maximum.hpp index da5e960a024..2b770d3efa9 100644 --- a/filters/include/pcl/filters/impl/local_maximum.hpp +++ b/filters/include/pcl/filters/impl/local_maximum.hpp @@ -121,6 +121,14 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) // not be maximal in their own neighborhood if (point_is_visited[iii] && !point_is_max[iii]) { + if (negative_) { + if (extract_removed_indices_) { + (*removed_indices_)[rii++] = iii; + } + } + else { + indices[oii++] = iii; + } continue; } @@ -146,7 +154,7 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) // Check to see if a neighbor is higher than the query point float query_z = (*input_)[iii].z; - for (std::size_t k = 1; k < radius_indices.size (); ++k) // k = 1 is the first neighbor + for (std::size_t k = 0; k < radius_indices.size (); ++k) // the query point itself is in the (unsorted) radius_indices, but that is okay since we compare with ">" { if ((*input_)[radius_indices[k]].z > query_z) { @@ -160,7 +168,7 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) // visited, excluding them from future consideration as local maxima if (point_is_max[iii]) { - for (std::size_t k = 1; k < radius_indices.size (); ++k) // k = 1 is the first neighbor + for (std::size_t k = 0; k < radius_indices.size (); ++k) // the query point itself is in the (unsorted) radius_indices, but it must also be marked as visited { point_is_visited[radius_indices[k]] = true; } From 02ba7f920e236f7ba823b0e507a91fd5d0c97e86 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 15 Jan 2023 19:51:31 +0100 Subject: [PATCH 030/288] Add tutorial-like test for find_package(PCL) --- .../content/sources/cmake_test/CMakeLists.txt | 15 +++++++++++++++ 1 file changed, 15 insertions(+) create mode 100644 doc/tutorials/content/sources/cmake_test/CMakeLists.txt diff --git a/doc/tutorials/content/sources/cmake_test/CMakeLists.txt b/doc/tutorials/content/sources/cmake_test/CMakeLists.txt new file mode 100644 index 00000000000..7e8db126c77 --- /dev/null +++ b/doc/tutorials/content/sources/cmake_test/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.5 FATAL_ERROR) + +# This is not really a tutorial, but instead tests the behaviour of find_package(PCL) when built together with the other tutorials +project(cmake_test) + +set(BOOST_LIBRARIES "boost_dont_overwrite") +set(Boost_LIBRARIES "boost_dont_overwrite") +find_package(PCL REQUIRED) + +if(NOT "${BOOST_LIBRARIES}" STREQUAL "boost_dont_overwrite") + message(FATAL_ERROR "find_package(PCL) changed the value of BOOST_LIBRARIES") +endif() +if(NOT "${Boost_LIBRARIES}" STREQUAL "boost_dont_overwrite") + message(FATAL_ERROR "find_package(PCL) changed the value of Boost_LIBRARIES") +endif() From bbbe9f862a037828d9b9bdf2fb95f57f492d6ca2 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 16 Jan 2023 14:46:32 +0100 Subject: [PATCH 031/288] Make sure that find_package(PCL) does not leak internals or overwrite variables - Change find_external_library from macro to function, "export" important variables with set(... PARENT_SCOPE) - Changes to FindFLANN.cmake and Findlibusb.cmake so that *_FOUND is defined when the script is called repeatedly - Add logic for pcap and png. Pcap was previously not found, while png was often only found by vtk as a by-product --- PCLConfig.cmake.in | 17 ++++++++++++++--- cmake/Modules/FindFLANN.cmake | 1 + cmake/Modules/Findlibusb.cmake | 3 +++ 3 files changed, 18 insertions(+), 3 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 12b1cdb2fe0..0dd3c4140b5 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -268,7 +268,7 @@ endmacro() # `--> component is induced ==> warn and remove it # from the list -macro(find_external_library _component _lib _is_optional) +function(find_external_library _component _lib _is_optional) if("${_lib}" STREQUAL "boost") find_boost() elseif("${_lib}" STREQUAL "eigen") @@ -299,6 +299,12 @@ macro(find_external_library _component _lib _is_optional) find_glew() elseif("${_lib}" STREQUAL "opengl") find_package(OpenGL) + elseif("${_lib}" STREQUAL "pcap") + find_package(Pcap) + elseif("${_lib}" STREQUAL "png") + find_package(PNG) + else() + message(WARNING "${_lib} is not handled by find_external_library") endif() string(TOUPPER "${_component}" COMPONENT) @@ -306,6 +312,7 @@ macro(find_external_library _component _lib _is_optional) string(REGEX REPLACE "[.-]" "_" LIB ${LIB}) if(${LIB}_FOUND) list(APPEND PCL_${COMPONENT}_INCLUDE_DIRS ${${LIB}_INCLUDE_DIRS}) + set(PCL_${COMPONENT}_INCLUDE_DIRS ${PCL_${COMPONENT}_INCLUDE_DIRS} PARENT_SCOPE) if(${LIB} MATCHES "VTK") if(${${LIB}_VERSION_MAJOR} GREATER_EQUAL 9) @@ -317,12 +324,16 @@ macro(find_external_library _component _lib _is_optional) include(${${LIB}_USE_FILE}) else() list(APPEND PCL_${COMPONENT}_LIBRARY_DIRS "${${LIB}_LIBRARY_DIRS}") + set(PCL_${COMPONENT}_LIBRARY_DIRS ${PCL_${COMPONENT}_LIBRARY_DIRS} PARENT_SCOPE) endif() if(${LIB}_LIBRARIES) list(APPEND PCL_${COMPONENT}_LINK_LIBRARIES "${${LIB}_LIBRARIES}") + set(PCL_${COMPONENT}_LINK_LIBRARIES ${PCL_${COMPONENT}_LINK_LIBRARIES} PARENT_SCOPE) + set(PCL_${LIB}_LIBRARIES ${${LIB}_LIBRARIES} PARENT_SCOPE) # Later appended to PCL_LIBRARIES endif() if(${LIB}_DEFINITIONS AND NOT ${LIB} STREQUAL "VTK") list(APPEND PCL_${COMPONENT}_DEFINITIONS ${${LIB}_DEFINITIONS}) + set(PCL_${COMPONENT}_DEFINITIONS ${PCL_${COMPONENT}_DEFINITIONS} PARENT_SCOPE) endif() else() if("${_is_optional}" STREQUAL "OPTIONAL") @@ -339,7 +350,7 @@ macro(find_external_library _component _lib _is_optional) endif() endif() endif() -endmacro() +endfunction() macro(pcl_check_external_dependency _component) endmacro() @@ -658,7 +669,7 @@ endif() pcl_remove_duplicate_libraries(PCL_COMPONENTS PCL_LIBRARIES) # Add 3rd party libraries, as user code might include our .HPP implementations -list(APPEND PCL_LIBRARIES ${BOOST_LIBRARIES} ${OPENNI_LIBRARIES} ${OPENNI2_LIBRARIES} ${ENSENSO_LIBRARIES} ${davidSDK_LIBRARIES} ${DSSDK_LIBRARIES} ${RSSDK_LIBRARIES} ${RSSDK2_LIBRARIES} ${VTK_LIBRARIES}) +list(APPEND PCL_LIBRARIES ${PCL_BOOST_LIBRARIES} ${PCL_OPENNI_LIBRARIES} ${PCL_OPENNI2_LIBRARIES} ${PCL_ENSENSO_LIBRARIES} ${PCL_davidSDK_LIBRARIES} ${PCL_DSSDK_LIBRARIES} ${PCL_RSSDK_LIBRARIES} ${PCL_RSSDK2_LIBRARIES} ${PCL_VTK_LIBRARIES}) if (TARGET FLANN::FLANN) list(APPEND PCL_LIBRARIES FLANN::FLANN) endif() diff --git a/cmake/Modules/FindFLANN.cmake b/cmake/Modules/FindFLANN.cmake index 9b46b2256f7..16ee72fbe8a 100644 --- a/cmake/Modules/FindFLANN.cmake +++ b/cmake/Modules/FindFLANN.cmake @@ -37,6 +37,7 @@ # Early return if FLANN target is already defined. This makes it safe to run # this script multiple times. if(TARGET FLANN::FLANN) + set(FLANN_FOUND ON) return() endif() diff --git a/cmake/Modules/Findlibusb.cmake b/cmake/Modules/Findlibusb.cmake index aab82269018..8edd001281f 100644 --- a/cmake/Modules/Findlibusb.cmake +++ b/cmake/Modules/Findlibusb.cmake @@ -36,6 +36,8 @@ # Early return if libusb target is already defined. This makes it safe to run # this script multiple times. if(TARGET libusb::libusb) + set(libusb_FOUND ON) + set(LIBUSB_FOUND ON) return() endif() @@ -67,6 +69,7 @@ find_package_handle_standard_args(libusb DEFAULT_MSG libusb_LIBRARIES libusb_INC mark_as_advanced(libusb_INCLUDE_DIRS libusb_LIBRARIES) if(libusb_FOUND) + set(LIBUSB_FOUND ON) add_library(libusb::libusb UNKNOWN IMPORTED) set_target_properties(libusb::libusb PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${libusb_INCLUDE_DIR}") set_target_properties(libusb::libusb PROPERTIES IMPORTED_LOCATION "${libusb_LIBRARIES}") From 2888c5f3b0da09fe1b277e5976fb6db2c7bb42ce Mon Sep 17 00:00:00 2001 From: Rasmus Date: Tue, 17 Jan 2023 10:13:34 +0100 Subject: [PATCH 032/288] Fix potential memory problems in GICP and IncrementalRegistration (#5557) * Add missing aligned operator new to GICP: Matrix4 typedef might be vectorizable when Scalar == float * Add missing aligned operator new to IncrementalRegistration --- registration/include/pcl/registration/gicp.h | 2 ++ .../include/pcl/registration/incremental_registration.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index d33e747c9a5..6694098469e 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -113,6 +113,8 @@ class GeneralizedIterativeClosestPoint typename IterativeClosestPoint::Matrix4; using AngleAxis = typename Eigen::AngleAxis; + PCL_MAKE_ALIGNED_OPERATOR_NEW; + /** \brief Empty constructor. */ GeneralizedIterativeClosestPoint() : k_correspondences_(20) diff --git a/registration/include/pcl/registration/incremental_registration.h b/registration/include/pcl/registration/incremental_registration.h index 04489fde199..a3f035d190f 100644 --- a/registration/include/pcl/registration/incremental_registration.h +++ b/registration/include/pcl/registration/incremental_registration.h @@ -111,6 +111,8 @@ class IncrementalRegistration { /** \brief Set registration instance used to align clouds */ inline void setRegistration(RegistrationPtr); + PCL_MAKE_ALIGNED_OPERATOR_NEW; + protected: /** \brief last registered point cloud */ PointCloudConstPtr last_cloud_; From b3908268b5d31df277c2ca7a4b65009642d4f7d5 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Tue, 17 Jan 2023 01:48:30 -0800 Subject: [PATCH 033/288] Review casts in PCL, Part B (#5508) * Initial application of google-readability-casting * Addressed google-readability-casting escapes * Addressed clang-format violations flagged by CI * More clang-format escapes * Addressed clang-tidy escapes * Fixed compile issue not seen on desktop * Addressed review comments * Fixed clang-tidy complaint * Clarified PCLPointCloud2::concatenate logic * Addressed latest review comments * Addressed latest review comments * Eliminated double casts per review --- .clang-tidy | 4 +- 2d/include/pcl/2d/impl/edge.hpp | 2 +- 2d/include/pcl/2d/impl/kernel.hpp | 9 +- .../pcl/common/impl/bivariate_polynomial.hpp | 12 +- common/include/pcl/common/impl/common.hpp | 8 +- common/include/pcl/common/impl/pca.hpp | 12 +- common/include/pcl/impl/cloud_iterator.hpp | 8 +- .../pcl/range_image/impl/range_image.hpp | 2 +- common/src/PCLPointCloud2.cpp | 18 +- common/src/bearing_angle_image.cpp | 2 +- common/src/colors.cpp | 6 +- common/src/gaussian.cpp | 2 +- common/src/range_image.cpp | 36 +- .../example_difference_of_normals.cpp | 2 +- .../segmentation/example_cpc_segmentation.cpp | 20 +- .../example_lccp_segmentation.cpp | 14 +- examples/segmentation/example_supervoxels.cpp | 14 +- .../include/pcl/features/impl/brisk_2d.hpp | 110 ++--- .../features/impl/integral_image_normal.hpp | 18 +- .../impl/organized_edge_detection.hpp | 24 +- features/include/pcl/features/impl/rsd.hpp | 8 +- features/include/pcl/features/impl/shot.hpp | 6 +- .../include/pcl/features/impl/spin_image.hpp | 12 +- features/src/narf.cpp | 8 +- features/src/range_image_border_extractor.cpp | 4 +- .../pcl/filters/impl/covariance_sampling.hpp | 6 +- .../pcl/filters/impl/extract_indices.hpp | 4 +- .../pcl/filters/impl/frustum_culling.hpp | 26 +- .../filters/impl/sampling_surface_normal.hpp | 2 +- filters/include/pcl/filters/random_sample.h | 4 +- filters/src/voxel_grid.cpp | 2 +- geometry/include/pcl/geometry/mesh_base.h | 17 +- .../compression/impl/entropy_range_coder.hpp | 8 +- io/include/pcl/io/grabber.h | 3 +- io/src/dinast_grabber.cpp | 14 +- io/src/image_grabber.cpp | 8 +- io/src/lzf_image_io.cpp | 20 +- io/src/oni_grabber.cpp | 14 +- io/src/openni2/openni2_video_mode.cpp | 2 +- io/src/openni2_grabber.cpp | 12 +- io/src/openni_camera/openni_device.cpp | 30 +- io/src/openni_grabber.cpp | 12 +- io/src/ply_io.cpp | 12 +- io/src/real_sense_2_grabber.cpp | 4 +- io/src/robot_eye_grabber.cpp | 4 +- io/tools/hdl_grabber_example.cpp | 4 +- io/tools/openni_grabber_depth_example.cpp | 2 +- io/tools/openni_grabber_example.cpp | 4 +- io/tools/openni_pcd_recorder.cpp | 8 +- io/tools/pcd_introduce_nan.cpp | 4 +- keypoints/include/pcl/keypoints/brisk_2d.h | 6 +- .../include/pcl/keypoints/impl/brisk_2d.hpp | 4 +- .../include/pcl/keypoints/impl/harris_3d.hpp | 4 +- .../include/pcl/keypoints/impl/harris_6d.hpp | 2 +- .../include/pcl/keypoints/impl/iss_3d.hpp | 10 +- keypoints/src/agast_2d.cpp | 130 +++--- keypoints/src/brisk_2d.cpp | 404 +++++++++--------- keypoints/src/narf_keypoint.cpp | 32 +- ml/src/permutohedral.cpp | 2 +- ml/src/svm_wrapper.cpp | 13 +- .../pcl/outofcore/impl/octree_base_node.hpp | 2 +- .../pcl/outofcore/octree_disk_container.h | 2 +- outofcore/src/visualization/grid.cpp | 2 +- .../main_ground_based_people_detection.cpp | 4 +- .../ground_based_people_detection_app.hpp | 4 +- .../pcl/people/impl/head_based_subcluster.hpp | 2 +- .../include/pcl/people/impl/height_map_2d.hpp | 16 +- .../pcl/people/impl/person_classifier.hpp | 20 +- people/src/hog.cpp | 24 +- .../pcl/recognition/color_gradient_modality.h | 8 +- .../pcl/recognition/impl/hv/hv_papazov.hpp | 6 +- .../impl/hv/occlusion_reasoning.hpp | 2 +- .../recognition/impl/linemod/line_rgbd.hpp | 8 +- recognition/src/dotmod.cpp | 2 +- recognition/src/linemod.cpp | 12 +- .../registration/correspondence_rejection.h | 5 +- .../default_convergence_criteria.h | 2 +- .../impl/correspondence_rejection_poly.hpp | 2 +- .../include/pcl/registration/impl/gicp.hpp | 13 +- .../include/pcl/registration/impl/ia_fpcs.hpp | 10 +- .../pcl/registration/impl/ia_kfpcs.hpp | 2 +- .../include/pcl/registration/impl/ndt_2d.hpp | 7 +- ...nsformation_estimation_dual_quaternion.hpp | 5 +- registration/include/pcl/registration/ndt.h | 6 +- .../src/correspondence_rejection_trimmed.cpp | 4 +- .../correspondence_rejection_var_trimmed.cpp | 16 +- registration/src/gicp6d.cpp | 3 +- .../include/pcl/search/impl/flann_search.hpp | 12 +- search/include/pcl/search/impl/organized.hpp | 10 +- ...imate_progressive_morphological_filter.hpp | 2 +- ...nized_connected_component_segmentation.hpp | 4 +- .../segmentation/impl/region_growing_rgb.hpp | 6 +- segmentation/src/grabcut_segmentation.cpp | 6 +- simulation/src/sum_reduce.cpp | 4 +- simulation/tools/sim_terminal_demo.cpp | 5 +- simulation/tools/sim_test_simple.cpp | 4 +- simulation/tools/sim_viewer.cpp | 6 +- stereo/src/stereo_adaptive_cost_so.cpp | 2 +- .../3rdparty/poisson4/bspline_data.hpp | 23 +- .../include/pcl/surface/impl/concave_hull.hpp | 2 +- .../pcl/surface/impl/marching_cubes.hpp | 6 +- .../pcl/surface/impl/marching_cubes_rbf.hpp | 2 +- surface/include/pcl/surface/impl/poisson.hpp | 18 +- .../src/3rdparty/poisson4/bspline_data.cpp | 4 +- surface/src/3rdparty/poisson4/geometry.cpp | 32 +- test/common/test_eigen.cpp | 54 +-- test/common/test_io.cpp | 12 +- test/features/test_boundary_estimation.cpp | 16 +- test/features/test_brisk.cpp | 10 +- test/features/test_flare_estimation.cpp | 2 +- test/features/test_gasd_estimation.cpp | 8 +- test/features/test_normal_estimation.cpp | 2 +- test/features/test_pfh_estimation.cpp | 2 +- test/filters/test_clipper.cpp | 28 +- test/filters/test_convolution.cpp | 22 +- test/filters/test_filters.cpp | 8 +- test/geometry/test_iterator.cpp | 34 +- test/io/test_octree_compression.cpp | 6 +- test/io/test_ply_io.cpp | 32 +- test/kdtree/test_kdtree.cpp | 4 +- test/octree/test_octree_iterator.cpp | 14 +- test/outofcore/test_outofcore.cpp | 2 +- test/recognition/test_recognition_cg.cpp | 2 +- .../test_correspondence_estimation.cpp | 4 +- .../test_correspondence_rejectors.cpp | 10 +- test/registration/test_registration.cpp | 6 +- test/registration/test_registration_api.cpp | 18 +- .../test_sample_consensus_plane_models.cpp | 2 +- test/search/test_flann_search.cpp | 8 +- test/search/test_organized.cpp | 16 +- test/search/test_organized_index.cpp | 16 +- test/search/test_search.cpp | 12 +- test/surface/test_concave_hull.cpp | 8 +- test/surface/test_convex_hull.cpp | 8 +- tools/elch.cpp | 4 +- tools/fast_bilateral_filter.cpp | 2 +- tools/image_grabber_saver.cpp | 2 +- tools/image_grabber_viewer.cpp | 4 +- tools/mesh_sampling.cpp | 14 +- tools/mls_smoothing.cpp | 2 +- tools/normal_estimation.cpp | 4 +- tools/octree_viewer.cpp | 2 +- tools/openni2_viewer.cpp | 4 +- tools/openni_image.cpp | 10 +- tools/openni_save_image.cpp | 4 +- tools/openni_viewer.cpp | 4 +- tools/outlier_removal.cpp | 2 +- tools/pcd_grabber_viewer.cpp | 2 +- tools/pcd_viewer.cpp | 2 +- tools/voxel_grid_occlusion_estimation.cpp | 4 +- tools/xyz2pcd.cpp | 2 +- .../impl/kld_adaptive_particle_filter.hpp | 2 +- .../pcl/tracking/impl/particle_filter.hpp | 6 +- .../pcl/visualization/impl/pcl_visualizer.hpp | 6 +- visualization/src/common/common.cpp | 14 +- .../src/common/float_image_utils.cpp | 2 +- visualization/src/image_viewer.cpp | 10 +- visualization/src/pcl_plotter.cpp | 6 +- visualization/src/pcl_visualizer.cpp | 38 +- visualization/src/point_picking_event.cpp | 2 +- visualization/src/window.cpp | 2 +- 161 files changed, 1031 insertions(+), 1022 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index c46134782b3..2a85603d5c8 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,5 +1,5 @@ --- -Checks: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast' -WarningsAsErrors: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast' +Checks: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast,google-readability-casting' +WarningsAsErrors: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast,google-readability-casting' CheckOptions: - {key: modernize-use-auto.MinTypeNameLength, value: 7} diff --git a/2d/include/pcl/2d/impl/edge.hpp b/2d/include/pcl/2d/impl/edge.hpp index a13ead96e88..75e35f94641 100644 --- a/2d/include/pcl/2d/impl/edge.hpp +++ b/2d/include/pcl/2d/impl/edge.hpp @@ -277,7 +277,7 @@ Edge::suppressNonMaxima( // maxima (j, i).intensity = 0; - switch (int(ptedge.direction)) { + switch (static_cast(ptedge.direction)) { case 0: { if (ptedge.magnitude >= edges(j - 1, i).magnitude && ptedge.magnitude >= edges(j + 1, i).magnitude) diff --git a/2d/include/pcl/2d/impl/kernel.hpp b/2d/include/pcl/2d/impl/kernel.hpp index 0be57ff4302..f813e9cf854 100644 --- a/2d/include/pcl/2d/impl/kernel.hpp +++ b/2d/include/pcl/2d/impl/kernel.hpp @@ -106,9 +106,9 @@ kernel::gaussianKernel(pcl::PointCloud& kernel) for (int j = 0; j < kernel_size_; j++) { int iks = (i - kernel_size_ / 2); int jks = (j - kernel_size_ / 2); - kernel(j, i).intensity = - std::exp(float(-double(iks * iks + jks * jks) / sigma_sqr)); - sum += float(kernel(j, i).intensity); + kernel(j, i).intensity = std::exp( + static_cast(-static_cast(iks * iks + jks * jks) / sigma_sqr)); + sum += (kernel(j, i).intensity); } } @@ -132,7 +132,8 @@ kernel::loGKernel(pcl::PointCloud& kernel) for (int j = 0; j < kernel_size_; j++) { int iks = (i - kernel_size_ / 2); int jks = (j - kernel_size_ / 2); - float temp = float(double(iks * iks + jks * jks) / sigma_sqr); + float temp = + static_cast(static_cast(iks * iks + jks * jks) / sigma_sqr); kernel(j, i).intensity = (1.0f - temp) * std::exp(-temp); sum += kernel(j, i).intensity; } diff --git a/common/include/pcl/common/impl/bivariate_polynomial.hpp b/common/include/pcl/common/impl/bivariate_polynomial.hpp index 7e527a6ccf8..9a29abf2b87 100644 --- a/common/include/pcl/common/impl/bivariate_polynomial.hpp +++ b/common/include/pcl/common/impl/bivariate_polynomial.hpp @@ -208,19 +208,19 @@ BivariatePolynomialT::findCriticalPoints (std::vector& x_values, std if (degree == 2) { - real x = (real(2)*parameters[2]*parameters[3] - parameters[1]*parameters[4]) / - (parameters[1]*parameters[1] - real(4)*parameters[0]*parameters[3]), - y = (real(-2)*parameters[0]*x - parameters[2]) / parameters[1]; + real x = (static_cast(2)*parameters[2]*parameters[3] - parameters[1]*parameters[4]) / + (parameters[1]*parameters[1] - static_cast(4)*parameters[0]*parameters[3]), + y = (static_cast(-2)*parameters[0]*x - parameters[2]) / parameters[1]; if (!std::isfinite(x) || !std::isfinite(y)) return; int type = 2; - real det_H = real(4)*parameters[0]*parameters[3] - parameters[1]*parameters[1]; + real det_H = static_cast(4)*parameters[0]*parameters[3] - parameters[1]*parameters[1]; //std::cout << "det(H) = "< real(0)) // Check Hessian determinant + if (det_H > static_cast(0)) // Check Hessian determinant { - if (parameters[0]+parameters[3] < real(0)) // Check Hessian trace + if (parameters[0]+parameters[3] < static_cast(0)) // Check Hessian trace type = 0; else type = 1; diff --git a/common/include/pcl/common/impl/common.hpp b/common/include/pcl/common/impl/common.hpp index 97edfbace0b..10326f0be36 100644 --- a/common/include/pcl/common/impl/common.hpp +++ b/common/include/pcl/common/impl/common.hpp @@ -168,7 +168,7 @@ pcl::getPointsInBox (const pcl::PointCloud &cloud, continue; if (cloud[i].x > max_pt[0] || cloud[i].y > max_pt[1] || cloud[i].z > max_pt[2]) continue; - indices[l++] = int (i); + indices[l++] = static_cast(i); } } // NaN or Inf values could exist => check for them @@ -186,7 +186,7 @@ pcl::getPointsInBox (const pcl::PointCloud &cloud, continue; if (cloud[i].x > max_pt[0] || cloud[i].y > max_pt[1] || cloud[i].z > max_pt[2]) continue; - indices[l++] = int (i); + indices[l++] = static_cast(i); } } indices.resize (l); @@ -210,7 +210,7 @@ pcl::getMaxDistance (const pcl::PointCloud &cloud, const Eigen::Vector4f dist = (pivot_pt3 - pt).norm (); if (dist > max_dist) { - max_idx = int (i); + max_idx = static_cast(i); max_dist = dist; } } @@ -227,7 +227,7 @@ pcl::getMaxDistance (const pcl::PointCloud &cloud, const Eigen::Vector4f dist = (pivot_pt3 - pt).norm (); if (dist > max_dist) { - max_idx = int (i); + max_idx = static_cast(i); max_dist = dist; } } diff --git a/common/include/pcl/common/impl/pca.hpp b/common/include/pcl/common/impl/pca.hpp index fac30862be0..3bebb2be1ea 100644 --- a/common/include/pcl/common/impl/pca.hpp +++ b/common/include/pcl/common/impl/pca.hpp @@ -71,7 +71,7 @@ PCA::initCompute () demeanPointCloud (*input_, *indices_, mean_, cloud_demean); assert (cloud_demean.cols () == int (indices_->size ())); // Compute the product cloud_demean * cloud_demean^T - const Eigen::Matrix3f alpha = (1.f / (float (indices_->size ()) - 1.f)) + const Eigen::Matrix3f alpha = (1.f / (static_cast(indices_->size ()) - 1.f)) * cloud_demean.topRows<3> () * cloud_demean.topRows<3> ().transpose (); // Compute eigen vectors and values @@ -102,7 +102,7 @@ PCA::update (const PointT& input_point, FLAG flag) Eigen::Vector3f input (input_point.x, input_point.y, input_point.z); const std::size_t n = eigenvectors_.cols ();// number of eigen vectors - Eigen::VectorXf meanp = (float(n) * (mean_.head<3>() + input)) / float(n + 1); + Eigen::VectorXf meanp = (static_cast(n) * (mean_.head<3>() + input)) / static_cast(n + 1); Eigen::VectorXf a = eigenvectors_.transpose() * (input - mean_.head<3>()); Eigen::VectorXf y = (eigenvectors_ * a) + mean_.head<3>(); Eigen::VectorXf h = y - input; @@ -113,12 +113,12 @@ PCA::update (const PointT& input_point, FLAG flag) float gamma = h.dot(input - mean_.head<3>()); Eigen::MatrixXf D = Eigen::MatrixXf::Zero (a.size() + 1, a.size() + 1); D.block(0,0,n,n) = a * a.transpose(); - D /= float(n)/float((n+1) * (n+1)); + D /= static_cast(n)/static_cast((n+1) * (n+1)); for(std::size_t i=0; i < a.size(); i++) { - D(i,i)+= float(n)/float(n+1)*eigenvalues_(i); - D(D.rows()-1,i) = float(n) / float((n+1) * (n+1)) * gamma * a(i); + D(i,i)+= static_cast(n)/static_cast(n+1)*eigenvalues_(i); + D(D.rows()-1,i) = static_cast(n) / static_cast((n+1) * (n+1)) * gamma * a(i); D(i,D.cols()-1) = D(D.rows()-1,i); - D(D.rows()-1,D.cols()-1) = float(n)/float((n+1) * (n+1)) * gamma * gamma; + D(D.rows()-1,D.cols()-1) = static_cast(n)/static_cast((n+1) * (n+1)) * gamma * gamma; } Eigen::MatrixXf R(D.rows(), D.cols()); diff --git a/common/include/pcl/impl/cloud_iterator.hpp b/common/include/pcl/impl/cloud_iterator.hpp index c7671b822b3..04c3affaf54 100644 --- a/common/include/pcl/impl/cloud_iterator.hpp +++ b/common/include/pcl/impl/cloud_iterator.hpp @@ -218,12 +218,12 @@ namespace pcl unsigned getCurrentPointIndex () const override { - return (unsigned (iterator_ - cloud_.begin ())); + return (static_cast(iterator_ - cloud_.begin ())); } unsigned getCurrentIndex () const override { - return (unsigned (iterator_ - cloud_.begin ())); + return (static_cast(iterator_ - cloud_.begin ())); } std::size_t size () const override @@ -292,12 +292,12 @@ namespace pcl unsigned getCurrentPointIndex () const override { - return (unsigned (*iterator_)); + return (static_cast(*iterator_)); } unsigned getCurrentIndex () const override { - return (unsigned (iterator_ - indices_.begin ())); + return (static_cast(iterator_ - indices_.begin ())); } std::size_t size () const override diff --git a/common/include/pcl/range_image/impl/range_image.hpp b/common/include/pcl/range_image/impl/range_image.hpp index 5731b4cc70a..866cc2ce96d 100644 --- a/common/include/pcl/range_image/impl/range_image.hpp +++ b/common/include/pcl/range_image/impl/range_image.hpp @@ -661,7 +661,7 @@ RangeImage::getAcutenessValue (const PointWithRange& point1, const PointWithRang float impact_angle = getImpactAngle (point1, point2); if (std::isinf (impact_angle)) return -std::numeric_limits::infinity (); - float ret = 1.0f - float (std::fabs (impact_angle)/ (0.5f*M_PI)); + float ret = 1.0f - static_cast(std::fabs (impact_angle)/ (0.5f*M_PI)); if (impact_angle < 0.0f) ret = -ret; //if (std::abs (ret)>1) diff --git a/common/src/PCLPointCloud2.cpp b/common/src/PCLPointCloud2.cpp index 20d18d66c3a..f5a47a2acfa 100644 --- a/common/src/PCLPointCloud2.cpp +++ b/common/src/PCLPointCloud2.cpp @@ -58,17 +58,13 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi const auto size1 = cloud1.width * cloud1.height; const auto size2 = cloud2.width * cloud2.height; //if one input cloud has no points, but the other input does, just select the cloud with points - switch ((bool (size1) << 1) + bool (size2)) - { - case 1: - cloud1 = cloud2; - PCL_FALLTHROUGH - case 0: - case 2: - cloud1.header.stamp = std::max (cloud1.header.stamp, cloud2.header.stamp); - return (true); - default: - break; + if ((size1 == 0) && (size2 != 0)) { + cloud1 = cloud2; + } + + if ((size1 == 0) || (size2 == 0)) { + cloud1.header.stamp = std::max (cloud1.header.stamp, cloud2.header.stamp); + return true; } // Ideally this should be in PCLPointField class since this is global behavior diff --git a/common/src/bearing_angle_image.cpp b/common/src/bearing_angle_image.cpp index 7c20c81e405..085c20fb9b4 100644 --- a/common/src/bearing_angle_image.cpp +++ b/common/src/bearing_angle_image.cpp @@ -114,7 +114,7 @@ BearingAngleImage::generateBAImage (PointCloud& point_cloud) points[(i + 1) * width + j].y = point_cloud.at (j, i + 1).y; points[(i + 1) * width + j].z = point_cloud.at (j, i + 1).z; // set the gray value for every pixel point - points[(i + 1) * width + j].rgba = ((int)r) << 24 | ((int)g) << 16 | ((int)b) << 8 | 0xff; + points[(i + 1) * width + j].rgba = (static_cast(r)) << 24 | (static_cast(g)) << 16 | (static_cast(b)) << 8 | 0xff; } } } diff --git a/common/src/colors.cpp b/common/src/colors.cpp index 24987bcee84..4d53ab1304d 100644 --- a/common/src/colors.cpp +++ b/common/src/colors.cpp @@ -609,9 +609,9 @@ pcl::getRandomColor (double min, double max) } while (sum <= min || sum >= max); pcl::RGB color; - color.r = std::uint8_t (r * 255.0); - color.g = std::uint8_t (g * 255.0); - color.b = std::uint8_t (b * 255.0); + color.r = static_cast(r * 255.0); + color.g = static_cast(g * 255.0); + color.b = static_cast(b * 255.0); return (color); } diff --git a/common/src/gaussian.cpp b/common/src/gaussian.cpp index e5fef1993b4..69bbd125336 100644 --- a/common/src/gaussian.cpp +++ b/common/src/gaussian.cpp @@ -83,7 +83,7 @@ pcl::GaussianKernel::compute (float sigma, kernel.resize (kernel_width); derivative.resize (kernel_width); const float factor = 0.01f; - float max_gauss = 1.0f, max_deriv = float (sigma * std::exp (-0.5)); + float max_gauss = 1.0f, max_deriv = static_cast(sigma * std::exp (-0.5)); int hw = kernel_width / 2; float sigma_sqr = 1.0f / (2.0f * sigma * sigma); diff --git a/common/src/range_image.cpp b/common/src/range_image.cpp index 342bad4e345..f94221408f1 100644 --- a/common/src/range_image.cpp +++ b/common/src/range_image.cpp @@ -459,9 +459,9 @@ float* RangeImage::getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int pixel_size, float world_size) const { float max_dist = 0.5f*world_size, - cell_size = world_size/float (pixel_size); + cell_size = world_size/static_cast(pixel_size); float world2cell_factor = 1.0f/cell_size, - world2cell_offset = 0.5f*float (pixel_size)-0.5f; + world2cell_offset = 0.5f*static_cast(pixel_size)-0.5f; float cell2world_factor = cell_size, cell2world_offset = -max_dist + 0.5f*cell_size; Eigen::Affine3f inverse_pose = pose.inverse (Eigen::Isometry); @@ -537,11 +537,11 @@ RangeImage::getInterpolatedSurfaceProjection (const Eigen::Affine3f& pose, int p cell3_y = world2cell_factor*point3[1] + world2cell_offset, cell3_z = point3[2]; - int min_cell_x = (std::max) (0, int (pcl_lrint (std::ceil ( (std::min) (cell1_x, (std::min) (cell2_x, cell3_x)))))), - max_cell_x = (std::min) (pixel_size-1, int (pcl_lrint (std::floor ( (std::max) (cell1_x, + int min_cell_x = (std::max) (0, static_cast(pcl_lrint (std::ceil ( (std::min) (cell1_x, (std::min) (cell2_x, cell3_x)))))), + max_cell_x = (std::min) (pixel_size-1, static_cast(pcl_lrint (std::floor ( (std::max) (cell1_x, (std::max) (cell2_x, cell3_x)))))), - min_cell_y = (std::max) (0, int (pcl_lrint (std::ceil ( (std::min) (cell1_y, (std::min) (cell2_y, cell3_y)))))), - max_cell_y = (std::min) (pixel_size-1, int (pcl_lrint (std::floor ( (std::max) (cell1_y, + min_cell_y = (std::max) (0, static_cast(pcl_lrint (std::ceil ( (std::min) (cell1_y, (std::min) (cell2_y, cell3_y)))))), + max_cell_y = (std::min) (pixel_size-1, static_cast(pcl_lrint (std::floor ( (std::max) (cell1_y, (std::max) (cell2_y, cell3_y)))))); if (max_cell_x(height); ++y) { - for (int x=0; x(width); ++x) { int index = y*width+x; getSurfaceAngleChange (x, y, radius, angle_change_image_x[index], angle_change_image_y[index]); @@ -739,9 +739,9 @@ RangeImage::getAcutenessValueImages (int pixel_distance, float*& acuteness_value int size = width*height; acuteness_value_image_x = new float[size]; acuteness_value_image_y = new float[size]; - for (int y=0; y(height); ++y) { - for (int x=0; x(width); ++x) { int index = y*width+x; acuteness_value_image_x[index] = getAcutenessValue (x, y, x+pixel_distance, y); @@ -757,9 +757,9 @@ RangeImage::getImpactAngleImageBasedOnLocalNormals (int radius) const MEASURE_FUNCTION_TIME; int size = width*height; float* impact_angle_image = new float[size]; - for (int y=0; y(height); ++y) { - for (int x=0; x(width); ++x) { impact_angle_image[y*width+x] = getImpactAngleBasedOnLocalNormal (x, y, radius); } @@ -776,9 +776,9 @@ RangeImage::getRangeImageWithSmoothedSurface (int radius, RangeImage& smoothed_r smoothed_range_image = *this; Eigen::Vector3f sensor_pos = getSensorPos (); - for (int y=0; y(height); ++y) { - for (int x=0; x(width); ++x) { PointWithRange& point = smoothed_range_image.getPoint (x, y); if (std::isinf (point.range)) @@ -874,9 +874,9 @@ RangeImage::getOverlap (const RangeImage& other_range_image, const Eigen::Affine reduction(+ : valid_points_counter) \ reduction(+ : hits_counter) \ num_threads(max_no_of_threads) - for (int other_y=0; other_y(other_range_image.height); other_y+=pixel_step) { - for (int other_x=0; other_x(other_range_image.width); other_x+=pixel_step) { const PointWithRange& point = other_range_image.getPoint (other_x, other_y); if (!std::isfinite (point.range)) @@ -920,9 +920,9 @@ RangeImage::getBlurredImageUsingIntegralImage (int blur_radius, float* integral_ RangeImage& blurred_image) const { this->copyTo(blurred_image); - for (int y=0; y(height); ++y) { - for (int x=0; x(width); ++x) { const PointWithRange& old_point = getPoint (x, y); PointWithRange& new_point = blurred_image.getPoint (x, y); diff --git a/examples/features/example_difference_of_normals.cpp b/examples/features/example_difference_of_normals.cpp index 4d2637864e3..d98d68cf5eb 100644 --- a/examples/features/example_difference_of_normals.cpp +++ b/examples/features/example_difference_of_normals.cpp @@ -99,7 +99,7 @@ int main (int argc, char *argv[]) // Create downsampled point cloud for DoN NN search with large scale large_cloud_downsampled = PointCloud::Ptr(new pcl::PointCloud); - constexpr float largedownsample = float(scale2 / decimation); + constexpr float largedownsample = static_cast(scale2/decimation); sor.setLeafSize (largedownsample, largedownsample, largedownsample); sor.filter (*large_cloud_downsampled); std::cout << "Using leaf size of " << largedownsample << " for large scale, " << large_cloud_downsampled->size() << " points" << std::endl; diff --git a/examples/segmentation/example_cpc_segmentation.cpp b/examples/segmentation/example_cpc_segmentation.cpp index 8c9937f094d..bbb357f673a 100644 --- a/examples/segmentation/example_cpc_segmentation.cpp +++ b/examples/segmentation/example_cpc_segmentation.cpp @@ -77,39 +77,39 @@ keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event_arg, if (event_arg.keyUp ()) switch (key) { - case (int) '1': + case static_cast('1'): show_normals = !show_normals; normals_changed = true; break; - case (int) '2': + case static_cast('2'): show_adjacency = !show_adjacency; break; - case (int) '3': + case static_cast('3'): show_supervoxels = !show_supervoxels; break; - case (int) '4': + case static_cast('4'): show_segmentation = !show_segmentation; break; - case (int) '5': + case static_cast('5'): normals_scale *= 1.25; normals_changed = true; break; - case (int) '6': + case static_cast('6'): normals_scale *= 0.8; normals_changed = true; break; - case (int) '7': + case static_cast('7'): line_width += 0.5; line_changed = true; break; - case (int) '8': + case static_cast('8'): if (line_width <= 1) break; line_width -= 0.5; line_changed = true; break; - case (int) 'd': - case (int) 'D': + case static_cast('d'): + case static_cast('D'): show_help = !show_help; break; default: diff --git a/examples/segmentation/example_lccp_segmentation.cpp b/examples/segmentation/example_lccp_segmentation.cpp index 7b92dc79c41..09a811e567e 100644 --- a/examples/segmentation/example_lccp_segmentation.cpp +++ b/examples/segmentation/example_lccp_segmentation.cpp @@ -73,26 +73,26 @@ keyboardEventOccurred (const pcl::visualization::KeyboardEvent& event_arg, if (event_arg.keyUp ()) switch (key) { - case (int) '1': + case static_cast('1'): show_normals = !show_normals; normals_changed = true; break; - case (int) '2': + case static_cast('2'): show_adjacency = !show_adjacency; break; - case (int) '3': + case static_cast('3'): show_supervoxels = !show_supervoxels; break; - case (int) '4': + case static_cast('4'): normals_scale *= 1.25; normals_changed = true; break; - case (int) '5': + case static_cast('5'): normals_scale *= 0.8; normals_changed = true; break; - case (int) 'd': - case (int) 'D': + case static_cast('d'): + case static_cast('D'): show_help = !show_help; break; default: diff --git a/examples/segmentation/example_supervoxels.cpp b/examples/segmentation/example_supervoxels.cpp index 76188bee4f5..11d8ec1420a 100644 --- a/examples/segmentation/example_supervoxels.cpp +++ b/examples/segmentation/example_supervoxels.cpp @@ -42,13 +42,13 @@ keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*) if (event.keyUp ()) switch (key) { - case (int)'1': show_voxel_centroids = !show_voxel_centroids; break; - case (int)'2': show_supervoxels = !show_supervoxels; break; - case (int)'3': show_graph = !show_graph; break; - case (int)'4': show_normals = !show_normals; break; - case (int)'5': show_supervoxel_normals = !show_supervoxel_normals; break; - case (int)'0': show_refined = !show_refined; break; - case (int)'h': case (int)'H': show_help = !show_help; break; + case static_cast('1'): show_voxel_centroids = !show_voxel_centroids; break; + case static_cast('2'): show_supervoxels = !show_supervoxels; break; + case static_cast('3'): show_graph = !show_graph; break; + case static_cast('4'): show_normals = !show_normals; break; + case static_cast('5'): show_supervoxel_normals = !show_supervoxel_normals; break; + case static_cast('0'): show_refined = !show_refined; break; + case static_cast('h'): case static_cast('H'): show_help = !show_help; break; default: break; } diff --git a/features/include/pcl/features/impl/brisk_2d.hpp b/features/include/pcl/features/impl/brisk_2d.hpp index 4b505d309a9..79e738aac11 100644 --- a/features/include/pcl/features/impl/brisk_2d.hpp +++ b/features/include/pcl/features/impl/brisk_2d.hpp @@ -119,7 +119,7 @@ BRISK2DEstimation::generateKernel ( // define the scale discretization: static const float lb_scale = std::log (scalerange_) / std::log (2.0); - static const float lb_scale_step = lb_scale / (float (scales_)); + static const float lb_scale_step = lb_scale / (static_cast(scales_)); scale_list_ = new float[scales_]; size_list_ = new unsigned int[scales_]; @@ -128,20 +128,20 @@ BRISK2DEstimation::generateKernel ( for (unsigned int scale = 0; scale < scales_; ++scale) { - scale_list_[scale] = static_cast (pow (double (2.0), static_cast (float (scale) * lb_scale_step))); + scale_list_[scale] = static_cast (pow ((2.0), static_cast (static_cast(scale) * lb_scale_step))); size_list_[scale] = 0; // generate the pattern points look-up for (std::size_t rot = 0; rot < n_rot_; ++rot) { // this is the rotation of the feature - double theta = double (rot) * 2 * M_PI / double (n_rot_); + double theta = static_cast(rot) * 2 * M_PI / static_cast(n_rot_); for (int ring = 0; ring < static_cast(rings); ++ring) { for (int num = 0; num < number_list[ring]; ++num) { // the actual coordinates on the circle - double alpha = double (num) * 2 * M_PI / double (number_list[ring]); + double alpha = static_cast(num) * 2 * M_PI / static_cast(number_list[ring]); // feature rotation plus angle of the point pattern_iterator->x = scale_list_[scale] * radius_list[ring] * static_cast (std::cos (alpha + theta)); @@ -150,7 +150,7 @@ BRISK2DEstimation::generateKernel ( if (ring == 0) pattern_iterator->sigma = sigma_scale * scale_list_[scale] * 0.5f; else - pattern_iterator->sigma = static_cast (sigma_scale * scale_list_[scale] * (double (radius_list[ring])) * sin (M_PI / double (number_list[ring]))); + pattern_iterator->sigma = static_cast (sigma_scale * scale_list_[scale] * (static_cast(radius_list[ring])) * sin (M_PI / static_cast(number_list[ring]))); // adapt the sizeList if necessary const auto size = static_cast (std::ceil (((scale_list_[scale] * radius_list[ring]) + pattern_iterator->sigma)) + 1); @@ -192,8 +192,8 @@ BRISK2DEstimation::generateKernel ( { // save to long pairs BriskLongPair& longPair = long_pairs_[no_long_pairs_]; - longPair.weighted_dx = int ((dx / (norm_sq)) * 2048.0 + 0.5); - longPair.weighted_dy = int ((dy / (norm_sq)) * 2048.0 + 0.5); + longPair.weighted_dx = static_cast((dx / (norm_sq)) * 2048.0 + 0.5); + longPair.weighted_dy = static_cast((dy / (norm_sq)) * 2048.0 + 0.5); longPair.i = i; longPair.j = j; ++no_long_pairs_; @@ -211,7 +211,7 @@ BRISK2DEstimation::generateKernel ( } // no bits: - strings_ = int (std::ceil ((float (no_short_pairs_)) / 128.0)) * 4 * 4; + strings_ = static_cast(std::ceil ((static_cast(no_short_pairs_)) / 128.0)) * 4 * 4; } @@ -228,8 +228,8 @@ BRISK2DEstimation::smoothedIntensity const BriskPatternPoint& brisk_point = pattern_points_[scale * n_rot_*points_ + rot * points_ + point]; const float xf = brisk_point.x + key_x; const float yf = brisk_point.y + key_y; - const int x = int (xf); - const int y = int (yf); + const int x = static_cast(xf); + const int y = static_cast(yf); const int& imagecols = image_width; // get the sigma: @@ -243,8 +243,8 @@ BRISK2DEstimation::smoothedIntensity if (sigma_half < 0.5) { // interpolation multipliers: - const int r_x = static_cast ((xf - float (x)) * 1024); - const int r_y = static_cast ((yf - float (y)) * 1024); + const int r_x = static_cast ((xf - static_cast(x)) * 1024); + const int r_y = static_cast ((yf - static_cast(y)) * 1024); const int r_x_1 = (1024 - r_x); const int r_y_1 = (1024 - r_y); @@ -252,22 +252,22 @@ BRISK2DEstimation::smoothedIntensity const unsigned char* ptr = static_cast(&image[0]) + x + y * imagecols; // just interpolate: - ret_val = (r_x_1 * r_y_1 * int (*ptr)); + ret_val = (r_x_1 * r_y_1 * static_cast(*ptr)); //+ptr += sizeof (PointInT); ptr++; - ret_val += (r_x * r_y_1 * int (*ptr)); + ret_val += (r_x * r_y_1 * static_cast(*ptr)); //+ptr += (imagecols * sizeof (PointInT)); ptr += imagecols; - ret_val += (r_x * r_y * int (*ptr)); + ret_val += (r_x * r_y * static_cast(*ptr)); //+ptr -= sizeof (PointInT); ptr--; - ret_val += (r_x_1 * r_y * int (*ptr)); + ret_val += (r_x_1 * r_y * static_cast(*ptr)); return (ret_val + 512) / 1024; } @@ -275,7 +275,7 @@ BRISK2DEstimation::smoothedIntensity // scaling: const int scaling = static_cast (4194304.0f / area); - const int scaling2 = static_cast (float (scaling) * area / 1024.0f); + const int scaling2 = static_cast (static_cast(scaling) * area / 1024.0f); // the integral image is larger: const int integralcols = imagecols + 1; @@ -286,26 +286,26 @@ BRISK2DEstimation::smoothedIntensity const float y_1 = yf - sigma_half; const float y1 = yf + sigma_half; - const int x_left = int (x_1 + 0.5); - const int y_top = int (y_1 + 0.5); - const int x_right = int (x1 + 0.5); - const int y_bottom = int (y1 + 0.5); + const int x_left = static_cast(x_1 + 0.5); + const int y_top = static_cast(y_1 + 0.5); + const int x_right = static_cast(x1 + 0.5); + const int y_bottom = static_cast(y1 + 0.5); // overlap area - multiplication factors: - const float r_x_1 = float (x_left) - x_1 + 0.5f; - const float r_y_1 = float (y_top) - y_1 + 0.5f; - const float r_x1 = x1 - float (x_right) + 0.5f; - const float r_y1 = y1 - float (y_bottom) + 0.5f; + const float r_x_1 = static_cast(x_left) - x_1 + 0.5f; + const float r_y_1 = static_cast(y_top) - y_1 + 0.5f; + const float r_x1 = x1 - static_cast(x_right) + 0.5f; + const float r_y1 = y1 - static_cast(y_bottom) + 0.5f; const int dx = x_right - x_left - 1; const int dy = y_bottom - y_top - 1; - const int A = static_cast ((r_x_1 * r_y_1) * float (scaling)); - const int B = static_cast ((r_x1 * r_y_1) * float (scaling)); - const int C = static_cast ((r_x1 * r_y1) * float (scaling)); - const int D = static_cast ((r_x_1 * r_y1) * float (scaling)); - const int r_x_1_i = static_cast (r_x_1 * float (scaling)); - const int r_y_1_i = static_cast (r_y_1 * float (scaling)); - const int r_x1_i = static_cast (r_x1 * float (scaling)); - const int r_y1_i = static_cast (r_y1 * float (scaling)); + const int A = static_cast ((r_x_1 * r_y_1) * static_cast(scaling)); + const int B = static_cast ((r_x1 * r_y_1) * static_cast(scaling)); + const int C = static_cast ((r_x1 * r_y1) * static_cast(scaling)); + const int D = static_cast ((r_x_1 * r_y1) * static_cast(scaling)); + const int r_x_1_i = static_cast (r_x_1 * static_cast(scaling)); + const int r_y_1_i = static_cast (r_y_1 * static_cast(scaling)); + const int r_x1_i = static_cast (r_x1 * static_cast(scaling)); + const int r_y1_i = static_cast (r_y1 * static_cast(scaling)); if (dx + dy > 2) { @@ -315,22 +315,22 @@ BRISK2DEstimation::smoothedIntensity const unsigned char* ptr = static_cast(&image[0]) + x_left + imagecols * y_top; // first the corners: - ret_val = A * int (*ptr); + ret_val = A * static_cast(*ptr); //+ptr += (dx + 1) * sizeof (PointInT); ptr += dx + 1; - ret_val += B * int (*ptr); + ret_val += B * static_cast(*ptr); //+ptr += (dy * imagecols + 1) * sizeof (PointInT); ptr += dy * imagecols + 1; - ret_val += C * int (*ptr); + ret_val += C * static_cast(*ptr); //+ptr -= (dx + 1) * sizeof (PointInT); ptr -= dx + 1; - ret_val += D * int (*ptr); + ret_val += D * static_cast(*ptr); // next the edges: //+int* ptr_integral;// = static_cast (integral.data) + x_left + integralcols * y_top + 1; @@ -377,7 +377,7 @@ BRISK2DEstimation::smoothedIntensity const unsigned char* ptr = static_cast(&image[0]) + x_left + imagecols * y_top; // first row: - ret_val = A * int (*ptr); + ret_val = A * static_cast(*ptr); //+ptr += sizeof (PointInT); ptr++; @@ -387,8 +387,8 @@ BRISK2DEstimation::smoothedIntensity //+for (; ptr < end1; ptr += sizeof (PointInT)) for (; ptr < end1; ptr++) - ret_val += r_y_1_i * int (*ptr); - ret_val += B * int (*ptr); + ret_val += r_y_1_i * static_cast(*ptr); + ret_val += B * static_cast(*ptr); // middle ones: //+ptr += (imagecols - dx - 1) * sizeof (PointInT); @@ -400,7 +400,7 @@ BRISK2DEstimation::smoothedIntensity //+for (; ptr < end_j; ptr += (imagecols - dx - 1) * sizeof (PointInT)) for (; ptr < end_j; ptr += imagecols - dx - 1) { - ret_val += r_x_1_i * int (*ptr); + ret_val += r_x_1_i * static_cast(*ptr); //+ptr += sizeof (PointInT); ptr++; @@ -410,12 +410,12 @@ BRISK2DEstimation::smoothedIntensity //+for (; ptr < end2; ptr += sizeof (PointInT)) for (; ptr < end2; ptr++) - ret_val += int (*ptr) * scaling; + ret_val += static_cast(*ptr) * scaling; - ret_val += r_x1_i * int (*ptr); + ret_val += r_x1_i * static_cast(*ptr); } // last row: - ret_val += D * int (*ptr); + ret_val += D * static_cast(*ptr); //+ptr += sizeof (PointInT); ptr++; @@ -425,9 +425,9 @@ BRISK2DEstimation::smoothedIntensity //+for (; ptr(*ptr); - ret_val += C * int (*ptr); + ret_val += C * static_cast(*ptr); return (ret_val + scaling2 / 2) / scaling2; } @@ -477,14 +477,14 @@ BRISK2DEstimation::compute ( unsigned int basicscale = 0; if (!scale_invariance_enabled_) - basicscale = std::max (static_cast (float (scales_) / lb_scalerange * (std::log2 (1.45f * basic_size_ / (basic_size_06))) + 0.5f), 0); + basicscale = std::max (static_cast (static_cast(scales_) / lb_scalerange * (std::log2 (1.45f * basic_size_ / (basic_size_06))) + 0.5f), 0); for (std::size_t k = 0; k < ksize; k++) { unsigned int scale; if (scale_invariance_enabled_) { - scale = std::max (static_cast (float (scales_) / lb_scalerange * (std::log2 ((*keypoints_)[k].size / (basic_size_06))) + 0.5f), 0); + scale = std::max (static_cast (static_cast(scales_) / lb_scalerange * (std::log2 ((*keypoints_)[k].size / (basic_size_06))) + 0.5f), 0); // saturate if (scale >= scales_) scale = scales_ - 1; kscales[k] = scale; @@ -499,7 +499,7 @@ BRISK2DEstimation::compute ( const int border_x = width - border; const int border_y = height - border; - if (RoiPredicate (float (border), float (border), float (border_x), float (border_y), (*keypoints_)[k])) + if (RoiPredicate (static_cast(border), static_cast(border), static_cast(border_x), static_cast(border_y), (*keypoints_)[k])) { //std::cerr << "remove keypoint" << std::endl; keypoints_->points.erase (beginning + k); @@ -562,8 +562,8 @@ BRISK2DEstimation::compute ( const int& scale = kscales[k]; int shifter = 0; int* pvalues = values; - const float& x = float (kp.x); - const float& y = float (kp.y); + const float& x = (kp.x); + const float& y = (kp.y); if (true) // kp.angle==-1 { if (!rotation_invariance_enabled_) @@ -592,11 +592,11 @@ BRISK2DEstimation::compute ( direction0 += tmp0; direction1 += tmp1; } - kp.angle = std::atan2 (float (direction1), float (direction0)) / float (M_PI) * 180.0f; - theta = static_cast ((float (n_rot_) * kp.angle) / (360.0f) + 0.5f); + kp.angle = std::atan2 (static_cast(direction1), static_cast(direction0)) / static_cast(M_PI) * 180.0f; + theta = static_cast ((static_cast(n_rot_) * kp.angle) / (360.0f) + 0.5f); if (theta < 0) theta += n_rot_; - if (theta >= int (n_rot_)) + if (theta >= static_cast(n_rot_)) theta -= n_rot_; } } @@ -611,7 +611,7 @@ BRISK2DEstimation::compute ( theta = static_cast (n_rot_ * (kp.angle / (360.0)) + 0.5); if (theta < 0) theta += n_rot_; - if (theta >= int (n_rot_)) + if (theta >= static_cast(n_rot_)) theta -= n_rot_; } } diff --git a/features/include/pcl/features/impl/integral_image_normal.hpp b/features/include/pcl/features/impl/integral_image_normal.hpp index ea8aa26250e..43b61bf5912 100644 --- a/features/include/pcl/features/impl/integral_image_normal.hpp +++ b/features/include/pcl/features/impl/integral_image_normal.hpp @@ -511,9 +511,9 @@ pcl::IntegralImageNormalEstimation::computePointNormalMirro auto cb_xyz_sosse = [this] (unsigned p1, unsigned p2, unsigned p3, unsigned p4) { return integral_image_XYZ_.getSecondOrderSumSE (p1, p2, p3, p4); }; sumArea::SecondOrderType>(start_x, start_y, end_x, end_y, width, height, cb_xyz_sosse, so_elements); - center[0] = float (tmp_center[0]); - center[1] = float (tmp_center[1]); - center[2] = float (tmp_center[2]); + center[0] = static_cast(tmp_center[0]); + center[1] = static_cast(tmp_center[1]); + center[2] = static_cast(tmp_center[2]); covariance_matrix.coeffRef (0) = static_cast (so_elements [0]); covariance_matrix.coeffRef (1) = covariance_matrix.coeffRef (3) = static_cast (so_elements [1]); @@ -670,10 +670,10 @@ pcl::IntegralImageNormalEstimation::computePointNormalMirro sumArea(start_x_U, start_y_U, end_x_U, end_y_U, width, height, cb_fosse, mean_U_z); sumArea(start_x_D, start_y_D, end_x_D, end_y_D, width, height, cb_fosse, mean_D_z); - mean_L_z /= float (count_L_z); - mean_R_z /= float (count_R_z); - mean_U_z /= float (count_U_z); - mean_D_z /= float (count_D_z); + mean_L_z /= static_cast(count_L_z); + mean_R_z /= static_cast(count_R_z); + mean_U_z /= static_cast(count_U_z); + mean_D_z /= static_cast(count_D_z); PointInT pointL = (*input_)[point_index_L_y*width + point_index_L_x]; @@ -845,7 +845,7 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con // top and bottom borders // That sets the output density to false! output.is_dense = false; - unsigned border = int(normal_smoothing_size_); + auto border = static_cast(normal_smoothing_size_); PointOutT* vec1 = &output [0]; PointOutT* vec2 = vec1 + input_->width * (input_->height - border); @@ -1027,7 +1027,7 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con if (border_policy_ == BORDER_POLICY_IGNORE) { output.is_dense = false; - unsigned border = int(normal_smoothing_size_); + auto border = static_cast(normal_smoothing_size_); unsigned bottom = input_->height > border ? input_->height - border : 0; unsigned right = input_->width > border ? input_->width - border : 0; if (use_depth_dependent_smoothing_) diff --git a/features/include/pcl/features/impl/organized_edge_detection.hpp b/features/include/pcl/features/impl/organized_edge_detection.hpp index 65e68be5678..90f87ee3f3b 100644 --- a/features/include/pcl/features/impl/organized_edge_detection.hpp +++ b/features/include/pcl/features/impl/organized_edge_detection.hpp @@ -52,7 +52,7 @@ template void pcl::OrganizedEdgeBase::compute (pcl::PointCloud& labels, std::vector& label_indices) const { pcl::Label invalid_pt; - invalid_pt.label = unsigned (0); + invalid_pt.label = static_cast(0); labels.resize (input_->size (), invalid_pt); labels.width = input_->width; labels.height = input_->height; @@ -66,7 +66,7 @@ pcl::OrganizedEdgeBase::compute (pcl::PointCloud& labe template void pcl::OrganizedEdgeBase::assignLabelIndices (pcl::PointCloud& labels, std::vector& label_indices) const { - const auto invalid_label = unsigned (0); + const auto invalid_label = static_cast(0); label_indices.resize (num_of_edgetype_); for (std::size_t idx = 0; idx < input_->size (); idx++) { @@ -98,11 +98,11 @@ pcl::OrganizedEdgeBase::extractEdges (pcl::PointCloud& Neighbor( 0, 1, labels.width ), Neighbor(-1, 1, labels.width - 1)}; - for (int row = 1; row < int(input_->height) - 1; row++) + for (int row = 1; row < static_cast(input_->height) - 1; row++) { - for (int col = 1; col < int(input_->width) - 1; col++) + for (int col = 1; col < static_cast(input_->width) - 1; col++) { - int curr_idx = row*int(input_->width) + col; + int curr_idx = row*static_cast(input_->width) + col; if (!std::isfinite ((*input_)[curr_idx].z)) continue; @@ -179,12 +179,12 @@ pcl::OrganizedEdgeBase::extractEdges (pcl::PointCloud& int s_row = row + static_cast (std::floor (f_dy*static_cast (s_idx))); int s_col = col + static_cast (std::floor (f_dx*static_cast (s_idx))); - if (s_row < 0 || s_row >= int(input_->height) || s_col < 0 || s_col >= int(input_->width)) + if (s_row < 0 || s_row >= static_cast(input_->height) || s_col < 0 || s_col >= static_cast(input_->width)) break; - if (std::isfinite ((*input_)[s_row*int(input_->width)+s_col].z)) + if (std::isfinite ((*input_)[s_row*static_cast(input_->width)+s_col].z)) { - corr_depth = std::abs ((*input_)[s_row*int(input_->width)+s_col].z); + corr_depth = std::abs ((*input_)[s_row*static_cast(input_->width)+s_col].z); break; } } @@ -226,7 +226,7 @@ template void pcl::OrganizedEdgeFromRGB::compute (pcl::PointCloud& labels, std::vector& label_indices) const { pcl::Label invalid_pt; - invalid_pt.label = unsigned (0); + invalid_pt.label = static_cast(0); labels.resize (input_->size (), invalid_pt); labels.width = input_->width; labels.height = input_->height; @@ -249,7 +249,7 @@ pcl::OrganizedEdgeFromRGB::extractEdges (pcl::PointCloudresize (input_->height*input_->width); for (std::size_t i = 0; i < input_->size (); ++i) - (*gray)[i].intensity = float (((*input_)[i].r + (*input_)[i].g + (*input_)[i].b) / 3); + (*gray)[i].intensity = static_cast(((*input_)[i].r + (*input_)[i].g + (*input_)[i].b) / 3); pcl::PointCloud img_edge_rgb; pcl::Edge edge; @@ -274,7 +274,7 @@ template void pcl::OrganizedEdgeFromNormals::compute (pcl::PointCloud& labels, std::vector& label_indices) const { pcl::Label invalid_pt; - invalid_pt.label = unsigned (0); + invalid_pt.label = static_cast(0); labels.resize (input_->size (), invalid_pt); labels.width = input_->width; labels.height = input_->height; @@ -332,7 +332,7 @@ template void pcl::OrganizedEdgeFromRGBNormals::compute (pcl::PointCloud& labels, std::vector& label_indices) const { pcl::Label invalid_pt; - invalid_pt.label = unsigned (0); + invalid_pt.label = static_cast(0); labels.resize (input_->size (), invalid_pt); labels.width = input_->width; labels.height = input_->height; diff --git a/features/include/pcl/features/impl/rsd.hpp b/features/include/pcl/features/impl/rsd.hpp index 5a5f25eeb43..7787eb88523 100644 --- a/features/include/pcl/features/impl/rsd.hpp +++ b/features/include/pcl/features/impl/rsd.hpp @@ -124,8 +124,8 @@ pcl::computeRSD (const pcl::PointCloud &surface, const pcl::PointCloud Amaxt_d += p_max * f; } } - float min_radius = Amint_Amin == 0.0f ? float (plane_radius) : float (std::min (Amint_d/Amint_Amin, plane_radius)); - float max_radius = Amaxt_Amax == 0.0f ? float (plane_radius) : float (std::min (Amaxt_d/Amaxt_Amax, plane_radius)); + float min_radius = Amint_Amin == 0.0f ? static_cast(plane_radius) : static_cast(std::min (Amint_d/Amint_Amin, plane_radius)); + float max_radius = Amaxt_Amax == 0.0f ? static_cast(plane_radius) : static_cast(std::min (Amaxt_d/Amaxt_Amax, plane_radius)); // Small correction of the systematic error of the estimation (based on analysis with nr_subdiv_ = 5) min_radius *= 1.1f; @@ -223,8 +223,8 @@ pcl::computeRSD (const pcl::PointCloud &normals, Amaxt_d += p_max * f; } } - float min_radius = Amint_Amin == 0.0f ? float (plane_radius) : float (std::min (Amint_d/Amint_Amin, plane_radius)); - float max_radius = Amaxt_Amax == 0.0f ? float (plane_radius) : float (std::min (Amaxt_d/Amaxt_Amax, plane_radius)); + float min_radius = Amint_Amin == 0.0f ? static_cast(plane_radius) : static_cast(std::min (Amint_d/Amint_Amin, plane_radius)); + float max_radius = Amaxt_Amax == 0.0f ? static_cast(plane_radius) : static_cast(std::min (Amaxt_d/Amaxt_Amax, plane_radius)); // Small correction of the systematic error of the estimation (based on analysis with nr_subdiv_ = 5) min_radius *= 1.1f; diff --git a/features/include/pcl/features/impl/shot.hpp b/features/include/pcl/features/impl/shot.hpp index 9d6ec0aaba4..6b9f1944b72 100644 --- a/features/include/pcl/features/impl/shot.hpp +++ b/features/include/pcl/features/impl/shot.hpp @@ -114,9 +114,9 @@ pcl::SHOTColorEstimation::RGB2CIELAB (un float vy = y; float vz = z / 1.08883f; - vx = sXYZ_LUT[int(vx*4000)]; - vy = sXYZ_LUT[int(vy*4000)]; - vz = sXYZ_LUT[int(vz*4000)]; + vx = sXYZ_LUT[static_cast(vx*4000)]; + vy = sXYZ_LUT[static_cast(vy*4000)]; + vz = sXYZ_LUT[static_cast(vz*4000)]; L = 116.0f * vy - 16.0f; if (L > 100) diff --git a/features/include/pcl/features/impl/spin_image.hpp b/features/include/pcl/features/impl/spin_image.hpp index 319ea73eb42..857c0a4f597 100644 --- a/features/include/pcl/features/impl/spin_image.hpp +++ b/features/include/pcl/features/impl/spin_image.hpp @@ -179,9 +179,9 @@ pcl::SpinImageEstimation::computeSiForPoint (int i // bilinear interpolation double beta_bin_size = is_radial_ ? (M_PI / 2 / image_width_) : bin_size; - int beta_bin = int(std::floor (beta / beta_bin_size)) + int(image_width_); + int beta_bin = static_cast(std::floor (beta / beta_bin_size)) + static_cast(image_width_); assert (0 <= beta_bin && beta_bin < m_matrix.cols ()); - int alpha_bin = int(std::floor (alpha / bin_size)); + int alpha_bin = static_cast(std::floor (alpha / bin_size)); assert (0 <= alpha_bin && alpha_bin < m_matrix.rows ()); if (alpha_bin == static_cast (image_width_)) // border points @@ -190,15 +190,15 @@ pcl::SpinImageEstimation::computeSiForPoint (int i // HACK: to prevent a > 1 alpha = bin_size * (alpha_bin + 1) - std::numeric_limits::epsilon (); } - if (beta_bin == int(2*image_width_) ) // border points + if (beta_bin == static_cast(2*image_width_) ) // border points { beta_bin--; // HACK: to prevent b > 1 - beta = beta_bin_size * (beta_bin - int(image_width_) + 1) - std::numeric_limits::epsilon (); + beta = beta_bin_size * (beta_bin - static_cast(image_width_) + 1) - std::numeric_limits::epsilon (); } - double a = alpha/bin_size - double(alpha_bin); - double b = beta/beta_bin_size - double(beta_bin-int(image_width_)); + double a = alpha/bin_size - static_cast(alpha_bin); + double b = beta/beta_bin_size - static_cast(beta_bin-static_cast(image_width_)); assert (0 <= a && a <= 1); assert (0 <= b && b <= 1); diff --git a/features/src/narf.cpp b/features/src/narf.cpp index 059dd22ee9c..556e741eccb 100644 --- a/features/src/narf.cpp +++ b/features/src/narf.cpp @@ -136,7 +136,7 @@ Narf::extractDescriptor (int descriptor_size) { float weight_for_first_point = 2.0f; // The weight for the last point is always 1.0f int no_of_beam_points = getNoOfBeamPoints(); - float weight_factor = -2.0f*(weight_for_first_point-1.0f) / ((weight_for_first_point+1.0f)*float(no_of_beam_points-1)), + float weight_factor = -2.0f*(weight_for_first_point-1.0f) / ((weight_for_first_point+1.0f)*static_cast(no_of_beam_points-1)), weight_offset = 2.0f*weight_for_first_point / (weight_for_first_point+1.0f); if (descriptor_size != descriptor_size_) @@ -148,7 +148,7 @@ Narf::extractDescriptor (int descriptor_size) float angle_step_size = deg2rad (360.0f) / static_cast (descriptor_size_); //std::cout << PVARN(no_of_beam_points)<(surface_patch_pixel_size_), cell_factor = 1.0f/cell_size, cell_offset = 0.5f*(surface_patch_world_size_ - cell_size), max_dist = 0.5f*surface_patch_world_size_, @@ -188,7 +188,7 @@ Narf::extractDescriptor (int descriptor_size) float beam_value1=beam_values[beam_value_idx], beam_value2=beam_values[beam_value_idx+1]; - float current_weight = weight_factor*float(beam_value_idx) + weight_offset; + float current_weight = weight_factor*static_cast(beam_value_idx) + weight_offset; float diff = beam_value2-beam_value1; current_cell += current_weight * diff; } @@ -273,7 +273,7 @@ Narf::extractFromRangeImageWithBestRotation (const RangeImage& range_image, cons float* Narf::getBlurredSurfacePatch (int new_pixel_size, int blur_radius) const { - float new_to_old_factor = float(surface_patch_pixel_size_)/float(new_pixel_size); + float new_to_old_factor = static_cast(surface_patch_pixel_size_)/static_cast(new_pixel_size); int new_size = new_pixel_size*new_pixel_size; float* integral_image = new float[new_size]; diff --git a/features/src/range_image_border_extractor.cpp b/features/src/range_image_border_extractor.cpp index ac6a6003247..d44521990b2 100644 --- a/features/src/range_image_border_extractor.cpp +++ b/features/src/range_image_border_extractor.cpp @@ -616,9 +616,9 @@ RangeImageBorderExtractor::blurSurfaceChanges () auto* blurred_directions = new Eigen::Vector3f[range_image.width*range_image.height]; float* blurred_scores = new float[range_image.width*range_image.height]; - for (int y=0; y(range_image.height); ++y) { - for (int x=0; x(range_image.width); ++x) { int index = y*range_image.width + x; Eigen::Vector3f& new_point = blurred_directions[index]; diff --git a/filters/include/pcl/filters/impl/covariance_sampling.hpp b/filters/include/pcl/filters/impl/covariance_sampling.hpp index 0e229710a92..df675d1923f 100644 --- a/filters/include/pcl/filters/impl/covariance_sampling.hpp +++ b/filters/include/pcl/filters/impl/covariance_sampling.hpp @@ -64,7 +64,7 @@ pcl::CovarianceSampling::initCompute () Eigen::Vector3f centroid (0.f, 0.f, 0.f); for (std::size_t p_i = 0; p_i < indices_->size (); ++p_i) centroid += (*input_)[(*indices_)[p_i]].getVector3fMap (); - centroid /= float (indices_->size ()); + centroid /= static_cast(indices_->size ()); scaled_points_.resize (indices_->size ()); double average_norm = 0.0; @@ -74,9 +74,9 @@ pcl::CovarianceSampling::initCompute () average_norm += scaled_points_[p_i].norm (); } - average_norm /= double (scaled_points_.size ()); + average_norm /= static_cast(scaled_points_.size ()); for (std::size_t p_i = 0; p_i < scaled_points_.size (); ++p_i) - scaled_points_[p_i] /= float (average_norm); + scaled_points_[p_i] /= static_cast(average_norm); return (true); } diff --git a/filters/include/pcl/filters/impl/extract_indices.hpp b/filters/include/pcl/filters/impl/extract_indices.hpp index f7550e8ee8c..27a0a859db7 100644 --- a/filters/include/pcl/filters/impl/extract_indices.hpp +++ b/filters/include/pcl/filters/impl/extract_indices.hpp @@ -58,7 +58,7 @@ pcl::ExtractIndices::filterDirectly (PointCloudPtr &cloud) pcl::for_each_type (pcl::detail::FieldAdder (fields)); for (const auto& rii : (*removed_indices_)) // rii = removed indices iterator { - auto pt_index = (uindex_t) rii; + auto pt_index = static_cast(rii); if (pt_index >= input_->size ()) { PCL_ERROR ("[pcl::%s::filterDirectly] The index exceeds the size of the input. Do nothing.\n", @@ -91,7 +91,7 @@ pcl::ExtractIndices::applyFilter (PointCloud &output) pcl::for_each_type (pcl::detail::FieldAdder (fields)); for (const auto ri : *removed_indices_) // ri = removed index { - auto pt_index = (std::size_t)ri; + auto pt_index = static_cast(ri); if (pt_index >= input_->size ()) { PCL_ERROR ("[pcl::%s::applyFilter] The index exceeds the size of the input. Do nothing.\n", diff --git a/filters/include/pcl/filters/impl/frustum_culling.hpp b/filters/include/pcl/filters/impl/frustum_culling.hpp index 3a23feea3f5..1aba5722c10 100644 --- a/filters/include/pcl/filters/impl/frustum_culling.hpp +++ b/filters/include/pcl/filters/impl/frustum_culling.hpp @@ -63,25 +63,25 @@ pcl::FrustumCulling::applyFilter (Indices &indices) Eigen::Vector3f T = camera_pose_.block<3, 1> (0, 3); // The (X, Y, Z) position of the camera w.r.t origin - float fov_lower_bound_rad = float (fov_lower_bound_ * M_PI / 180); // degrees to radians - float fov_upper_bound_rad = float (fov_upper_bound_ * M_PI / 180); // degrees to radians - float fov_left_bound_rad = float (fov_left_bound_ * M_PI / 180); // degrees to radians - float fov_right_bound_rad = float (fov_right_bound_ * M_PI / 180); // degrees to radians + float fov_lower_bound_rad = static_cast(fov_lower_bound_ * M_PI / 180); // degrees to radians + float fov_upper_bound_rad = static_cast(fov_upper_bound_ * M_PI / 180); // degrees to radians + float fov_left_bound_rad = static_cast(fov_left_bound_ * M_PI / 180); // degrees to radians + float fov_right_bound_rad = static_cast(fov_right_bound_ * M_PI / 180); // degrees to radians float roi_xmax = roi_x_ + (roi_w_ / 2); // roi max x float roi_xmin = roi_x_ - (roi_w_ / 2); // roi min x float roi_ymax = roi_y_ + (roi_h_ / 2); // roi max y float roi_ymin = roi_y_ - (roi_h_ / 2); // roi min y - float np_h_u = float(2 * std::tan(fov_lower_bound_rad) * np_dist_ * (roi_ymin - 0.5)); // near plane upper height - float np_h_d = float(2 * std::tan(fov_upper_bound_rad) * np_dist_ * (roi_ymax - 0.5)); // near plane lower height - float np_w_l = float(2 * std::tan(fov_left_bound_rad) * np_dist_ * (roi_xmin - 0.5)); // near plane left width - float np_w_r = float(2 * std::tan(fov_right_bound_rad) * np_dist_ * (roi_xmax - 0.5)); // near plane right width - - float fp_h_u = float(2 * std::tan(fov_lower_bound_rad) * fp_dist_ * (roi_ymin - 0.5)); // far plane upper height - float fp_h_d = float(2 * std::tan(fov_upper_bound_rad) * fp_dist_ * (roi_ymax - 0.5)); // far plane lower height - float fp_w_l = float(2 * std::tan(fov_left_bound_rad) * fp_dist_ * (roi_xmin - 0.5)); // far plane left width - float fp_w_r = float(2 * std::tan(fov_right_bound_rad) * fp_dist_ * (roi_xmax - 0.5)); // far plane right width + float np_h_u = static_cast(2 * std::tan(fov_lower_bound_rad) * np_dist_ * (roi_ymin - 0.5)); // near plane upper height + float np_h_d = static_cast(2 * std::tan(fov_upper_bound_rad) * np_dist_ * (roi_ymax - 0.5)); // near plane lower height + float np_w_l = static_cast(2 * std::tan(fov_left_bound_rad) * np_dist_ * (roi_xmin - 0.5)); // near plane left width + float np_w_r = static_cast(2 * std::tan(fov_right_bound_rad) * np_dist_ * (roi_xmax - 0.5)); // near plane right width + + float fp_h_u = static_cast(2 * std::tan(fov_lower_bound_rad) * fp_dist_ * (roi_ymin - 0.5)); // far plane upper height + float fp_h_d = static_cast(2 * std::tan(fov_upper_bound_rad) * fp_dist_ * (roi_ymax - 0.5)); // far plane lower height + float fp_w_l = static_cast(2 * std::tan(fov_left_bound_rad) * fp_dist_ * (roi_xmin - 0.5)); // far plane left width + float fp_w_r = static_cast(2 * std::tan(fov_right_bound_rad) * fp_dist_ * (roi_xmax - 0.5)); // far plane right width Eigen::Vector3f fp_c (T + view * fp_dist_); // far plane center Eigen::Vector3f fp_tl (fp_c + (up * fp_h_u) - (right * fp_w_l)); // Top left corner of the far plane diff --git a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp index fd3f221e18c..a711bf8cba0 100644 --- a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp +++ b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp @@ -148,7 +148,7 @@ pcl::SamplingSurfaceNormal::samplePartition ( for (const auto& point: cloud) { // TODO: change to Boost random number generators! - const float r = float (std::rand ()) / float (RAND_MAX); + const float r = static_cast(std::rand ()) / static_cast(RAND_MAX); if (r < ratio_) { diff --git a/filters/include/pcl/filters/random_sample.h b/filters/include/pcl/filters/random_sample.h index 44cd2543e0a..672fd68d241 100644 --- a/filters/include/pcl/filters/random_sample.h +++ b/filters/include/pcl/filters/random_sample.h @@ -135,7 +135,7 @@ namespace pcl inline float unifRand () { - return (static_cast(rand () / double (RAND_MAX))); + return (static_cast(rand () / static_cast(RAND_MAX))); //return (((214013 * seed_ + 2531011) >> 16) & 0x7FFF); } }; @@ -226,7 +226,7 @@ namespace pcl inline float unifRand () { - return (static_cast (rand () / double (RAND_MAX))); + return (static_cast (rand () / static_cast(RAND_MAX))); } }; } diff --git a/filters/src/voxel_grid.cpp b/filters/src/voxel_grid.cpp index 4c1566da570..b926499fab4 100644 --- a/filters/src/voxel_grid.cpp +++ b/filters/src/voxel_grid.cpp @@ -406,7 +406,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) } // Fourth pass: compute centroids, insert them into their final position - output.width = std::uint32_t (total); + output.width = static_cast(total); output.row_step = output.point_step * output.width; output.data.resize (output.width * output.point_step); diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index c61da1c67aa..f2ed1a83e05 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -183,7 +183,7 @@ class MeshBase { { vertices_.push_back(Vertex()); this->addData(vertex_data_cloud_, vertex_data, HasVertexData()); - return (VertexIndex(static_cast(this->sizeVertices() - 1))); + return (static_cast(this->sizeVertices() - 1)); } /** @@ -637,29 +637,32 @@ class MeshBase { inline bool isValid(const VertexIndex& idx_vertex) const { - return (idx_vertex >= VertexIndex(0) && - idx_vertex < VertexIndex(int(vertices_.size()))); + return (idx_vertex >= static_cast(0) && + idx_vertex < static_cast(vertices_.size())); } /** \brief Check if the given half-edge index is a valid index into the mesh. */ inline bool isValid(const HalfEdgeIndex& idx_he) const { - return (idx_he >= HalfEdgeIndex(0) && idx_he < HalfEdgeIndex(half_edges_.size())); + return (idx_he >= static_cast(0) && + idx_he < static_cast(half_edges_.size())); } /** \brief Check if the given edge index is a valid index into the mesh. */ inline bool isValid(const EdgeIndex& idx_edge) const { - return (idx_edge >= EdgeIndex(0) && idx_edge < EdgeIndex(half_edges_.size() / 2)); + return (idx_edge >= static_cast(0) && + idx_edge < static_cast(half_edges_.size() / 2)); } /** \brief Check if the given face index is a valid index into the mesh. */ inline bool isValid(const FaceIndex& idx_face) const { - return (idx_face >= FaceIndex(0) && idx_face < FaceIndex(faces_.size())); + return (idx_face >= static_cast(0) && + idx_face < static_cast(faces_.size())); } //////////////////////////////////////////////////////////////////////// @@ -1248,7 +1251,7 @@ class MeshBase { this->addData(half_edge_data_cloud_, he_data, HasHalfEdgeData()); this->addData(edge_data_cloud_, edge_data, HasEdgeData()); - return (HalfEdgeIndex(static_cast(half_edges_.size() - 2))); + return (static_cast(half_edges_.size() - 2)); } //////////////////////////////////////////////////////////////////////// diff --git a/io/include/pcl/compression/impl/entropy_range_coder.hpp b/io/include/pcl/compression/impl/entropy_range_coder.hpp index 65832a0747a..be1190fddb3 100644 --- a/io/include/pcl/compression/impl/entropy_range_coder.hpp +++ b/io/include/pcl/compression/impl/entropy_range_coder.hpp @@ -84,7 +84,7 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector& inpu range *= freq[ch + 1] - freq[ch]; // check range limits - while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast(low) & (bottom - 1)), 1))) { char out = static_cast (low >> 24); range <<= 8; @@ -186,7 +186,7 @@ pcl::AdaptiveRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream range *= freq[symbol + 1] - freq[symbol]; // decode range limits - while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast(low) & (bottom - 1)), 1))) { std::uint8_t ch; inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); @@ -509,7 +509,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector& inputB range *= freq[ch + 1] - freq[ch]; // check range limits - while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast(low) & (bottom - 1)), 1))) { char out = static_cast (low >> 24); range <<= 8; @@ -602,7 +602,7 @@ pcl::StaticRangeCoder::decodeStreamToCharVector (std::istream& inputByteStream_a range *= freq[symbol + 1] - freq[symbol]; // check range limits - while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -int (low) & (bottom - 1)), 1))) + while ((low ^ (low + range)) < top || ((range < bottom) && ((range = -static_cast(low) & (bottom - 1)), 1))) { std::uint8_t ch; inputByteStream_arg.read (reinterpret_cast (&ch), sizeof(char)); diff --git a/io/include/pcl/io/grabber.h b/io/include/pcl/io/grabber.h index c36a00c5552..ce6f55a0890 100644 --- a/io/include/pcl/io/grabber.h +++ b/io/include/pcl/io/grabber.h @@ -262,6 +262,7 @@ namespace pcl operator std::unique_ptr() const { return std::make_unique(); } }; // TODO: remove later for C++17 features: structured bindings and try_emplace + std::string signame{typeid (T).name ()}; #ifdef __cpp_structured_bindings const auto [iterator, success] = #else @@ -275,7 +276,7 @@ namespace pcl #else signals_.emplace ( #endif - std::string (typeid (T).name ()), DefferedPtr ()); + signame, DefferedPtr ()); if (!success) { return nullptr; diff --git a/io/src/dinast_grabber.cpp b/io/src/dinast_grabber.cpp index 4fd28781afd..6ca3c951aa5 100644 --- a/io/src/dinast_grabber.cpp +++ b/io/src/dinast_grabber.cpp @@ -95,7 +95,7 @@ pcl::DinastGrabber::getFramesPerSecond () const { static double last = pcl::getTime (); double now = pcl::getTime (); - float rate = 1 / float(now - last); + float rate = 1 / static_cast(now - last); last = now; return (rate); @@ -158,13 +158,13 @@ pcl::DinastGrabber::setupDevice (int device_position, const int id_vendor, const libusb_get_config_descriptor (devs[i], 0, &config); // Iterate over all interfaces available - for (int f = 0; f < int (config->bNumInterfaces); ++f) + for (int f = 0; f < static_cast(config->bNumInterfaces); ++f) { // Iterate over the number of alternate settings for (int j = 0; j < config->interface[f].num_altsetting; ++j) { // Iterate over the number of end points present - for (int k = 0; k < int (config->interface[f].altsetting[j].bNumEndpoints); ++k) + for (int k = 0; k < static_cast(config->interface[f].altsetting[j].bNumEndpoints); ++k) { if (config->interface[f].altsetting[j].endpoint[k].bmAttributes == LIBUSB_TRANSFER_TYPE_BULK) { @@ -262,7 +262,7 @@ pcl::DinastGrabber::readImage () PCL_DEBUG ("[pcl::DinastGrabber::readImage] Read: %d, size of the buffer: %d\n" ,actual_length, g_buffer_.size ()); // Copy data into the buffer - int back = int (g_buffer_.size ()); + int back = static_cast(g_buffer_.size ()); g_buffer_.resize (back + actual_length); for (int i = 0; i < actual_length; ++i) @@ -375,7 +375,7 @@ pcl::DinastGrabber::USBRxControlData (const unsigned char req_code, int nr_read = libusb_control_transfer (device_handle_, requesttype, req_code, value, index, buffer, static_cast (length), timeout); - if (nr_read != int(length)) + if (nr_read != (length)) PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::USBRxControlData] Control data error"); return (true); @@ -399,7 +399,7 @@ pcl::DinastGrabber::USBTxControlData (const unsigned char req_code, int nr_read = libusb_control_transfer (device_handle_, requesttype, req_code, value, index, buffer, static_cast (length), timeout); - if (nr_read != int(length)) + if (nr_read != (length)) { std::stringstream sstream; sstream << "[pcl::DinastGrabber::USBTxControlData] USB control data error, LIBUSB_ERROR: " << nr_read; @@ -427,7 +427,7 @@ pcl::DinastGrabber::checkHeader () (g_buffer_[i + 4] == 0xBB) && (g_buffer_[i + 5] == 0xBB) && (g_buffer_[i + 6] == 0x77) && (g_buffer_[i + 7] == 0x77)) { - data_ptr = int (i) + sync_packet_size_; + data_ptr = static_cast(i) + sync_packet_size_; break; } } diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 3f787369a56..99529fb3aa9 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -518,8 +518,8 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudVTK (std::size_t idx, { // The 525 factor default is only true for VGA. If not, we should scale scaleFactorX = scaleFactorY = 1/525.f * 640.f / static_cast (dims[0]); - centerX = ((float)dims[0] - 1.f)/2.f; - centerY = ((float)dims[1] - 1.f)/2.f; + centerX = (static_cast(dims[0]) - 1.f)/2.f; + centerY = (static_cast(dims[1]) - 1.f)/2.f; } if(!rgb_image_files_.empty ()) @@ -577,8 +577,8 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudVTK (std::size_t idx, pt.x = pt.y = pt.z = std::numeric_limits::quiet_NaN (); else { - pt.x = ((float)x - centerX) * scaleFactorX * depth; - pt.y = ((float)y - centerY) * scaleFactorY * depth; + pt.x = (static_cast(x) - centerX) * scaleFactorX * depth; + pt.y = (static_cast(y) - centerY) * scaleFactorY * depth; pt.z = depth; } } diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index c9661dd5ccc..78d787ea8fb 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -120,7 +120,7 @@ pcl::io::LZFImageWriter::compress (const char* input, unsigned int compressed_size = pcl::lzfCompress (input, uncompressed_size, &output[header_size], - std::uint32_t (finput_size * 1.5f)); + static_cast(finput_size * 1.5f)); std::uint32_t compressed_final_size = 0; if (compressed_size) @@ -143,7 +143,7 @@ pcl::io::LZFImageWriter::compress (const char* input, memcpy (&output[13], &itype[0], 16); memcpy (&output[29], &compressed_size, sizeof (std::uint32_t)); memcpy (&output[33], &uncompressed_size, sizeof (std::uint32_t)); - compressed_final_size = std::uint32_t (compressed_size + header_size); + compressed_final_size = static_cast(compressed_size + header_size); } return (compressed_final_size); @@ -157,7 +157,7 @@ pcl::io::LZFDepth16ImageWriter::write (const char* data, { // Prepare the compressed depth buffer unsigned int depth_size = width * height * 2; - char* compressed_depth = static_cast (malloc (std::size_t (float (depth_size) * 1.5f + float (LZF_HEADER_SIZE)))); + char* compressed_depth = static_cast (malloc (static_cast(static_cast(depth_size) * 1.5f + static_cast(LZF_HEADER_SIZE)))); std::size_t compressed_size = compress (data, depth_size, @@ -237,9 +237,9 @@ pcl::io::LZFRGB24ImageWriter::write (const char *data, rrggbb[ptr3] = data[i * 3 + 2]; } - char* compressed_rgb = static_cast (malloc (std::size_t (float (rrggbb.size ()) * 1.5f + float (LZF_HEADER_SIZE)))); + char* compressed_rgb = static_cast (malloc (static_cast(static_cast(rrggbb.size ()) * 1.5f + static_cast(LZF_HEADER_SIZE)))); std::size_t compressed_size = compress (reinterpret_cast (&rrggbb[0]), - std::uint32_t (rrggbb.size ()), + static_cast(rrggbb.size ()), width, height, "rgb24", compressed_rgb); @@ -298,9 +298,9 @@ pcl::io::LZFYUV422ImageWriter::write (const char *data, uuyyvv[ptr3] = data[i * 4 + 2]; // v } - char* compressed_yuv = static_cast (malloc (std::size_t (float (uuyyvv.size ()) * 1.5f + float (LZF_HEADER_SIZE)))); + char* compressed_yuv = static_cast (malloc (static_cast(static_cast(uuyyvv.size ()) * 1.5f + static_cast(LZF_HEADER_SIZE)))); std::size_t compressed_size = compress (reinterpret_cast (&uuyyvv[0]), - std::uint32_t (uuyyvv.size ()), + static_cast(uuyyvv.size ()), width, height, "yuv422", compressed_yuv); @@ -324,7 +324,7 @@ pcl::io::LZFBayer8ImageWriter::write (const char *data, const std::string &filename) { unsigned int bayer_size = width * height; - char* compressed_bayer = static_cast (malloc (std::size_t (float (bayer_size) * 1.5f + float (LZF_HEADER_SIZE)))); + char* compressed_bayer = static_cast (malloc (static_cast(static_cast(bayer_size) * 1.5f + static_cast(LZF_HEADER_SIZE)))); std::size_t compressed_size = compress (data, bayer_size, width, height, @@ -467,9 +467,9 @@ pcl::io::LZFImageReader::decompress (const std::vector &input, return (false); } unsigned int tmp_size = pcl::lzfDecompress (static_cast(&input[0]), - std::uint32_t (input.size ()), + static_cast(input.size ()), static_cast(&output[0]), - std::uint32_t (output.size ())); + static_cast(output.size ())); if (tmp_size != output.size ()) { diff --git a/io/src/oni_grabber.cpp b/io/src/oni_grabber.cpp index 76746241fd2..096985861c6 100644 --- a/io/src/oni_grabber.cpp +++ b/io/src/oni_grabber.cpp @@ -372,7 +372,7 @@ ONIGrabber::convertToXYZPointCloud(const openni_wrapper::DepthImage::Ptr& depth_ if (depth_image->getWidth () != depth_width_ || depth_image->getHeight () != depth_height_) { static unsigned buffer_size = 0; - static boost::shared_array depth_buffer ((unsigned short*)nullptr); + static boost::shared_array depth_buffer (nullptr); if (buffer_size < depth_width_ * depth_height_) { @@ -412,7 +412,7 @@ pcl::PointCloud::Ptr ONIGrabber::convertToXYZRGBPointCloud ( const openni_wrapper::DepthImage::Ptr &depth_image) const { static unsigned rgb_array_size = 0; - static boost::shared_array rgb_array((unsigned char*)nullptr); + static boost::shared_array rgb_array(nullptr); static unsigned char* rgb_buffer = nullptr; pcl::PointCloud::Ptr cloud(new pcl::PointCloud); @@ -432,7 +432,7 @@ pcl::PointCloud::Ptr ONIGrabber::convertToXYZRGBPointCloud ( if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_) { static unsigned buffer_size = 0; - static boost::shared_array depth_buffer((unsigned short*)nullptr); + static boost::shared_array depth_buffer(nullptr); if (buffer_size < depth_width_ * depth_height_) { @@ -496,7 +496,7 @@ pcl::PointCloud::Ptr ONIGrabber::convertToXYZRGBAPointCloud ( const openni_wrapper::DepthImage::Ptr &depth_image) const { static unsigned rgb_array_size = 0; - static boost::shared_array rgb_array((unsigned char*)nullptr); + static boost::shared_array rgb_array(nullptr); static unsigned char* rgb_buffer = nullptr; pcl::PointCloud::Ptr cloud (new pcl::PointCloud); @@ -516,7 +516,7 @@ pcl::PointCloud::Ptr ONIGrabber::convertToXYZRGBAPointCloud ( if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_) { static unsigned buffer_size = 0; - static boost::shared_array depth_buffer((unsigned short*)nullptr); + static boost::shared_array depth_buffer(nullptr); if (buffer_size < depth_width_ * depth_height_) { @@ -597,8 +597,8 @@ pcl::PointCloud::Ptr ONIGrabber::convertToXYZIPointCloud(const o if (depth_image->getWidth() != depth_width_ || depth_image->getHeight() != depth_height_) { static unsigned buffer_size = 0; - static boost::shared_array depth_buffer((unsigned short*)nullptr); - static boost::shared_array ir_buffer((unsigned short*)nullptr); + static boost::shared_array depth_buffer(nullptr); + static boost::shared_array ir_buffer(nullptr); if (buffer_size < depth_width_ * depth_height_) { diff --git a/io/src/openni2/openni2_video_mode.cpp b/io/src/openni2/openni2_video_mode.cpp index 145da5d3851..64879294320 100644 --- a/io/src/openni2/openni2_video_mode.cpp +++ b/io/src/openni2/openni2_video_mode.cpp @@ -41,7 +41,7 @@ namespace pcl std::ostream& operator<< (std::ostream& stream, const OpenNI2VideoMode& video_mode) { - stream << "Resolution: " << (int)video_mode.x_resolution_ << "x" << (int)video_mode.y_resolution_ << + stream << "Resolution: " << static_cast(video_mode.x_resolution_) << "x" << static_cast(video_mode.y_resolution_) << "@" << video_mode.frame_rate_ << "Hz Format: "; diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index f9a31c0e83d..fff500446d3 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -533,8 +533,8 @@ pcl::io::OpenNI2Grabber::convertToXYZPointCloud (const DepthImage::Ptr& depth_im float constant_x = 1.0f / device_->getDepthFocalLength (); float constant_y = 1.0f / device_->getDepthFocalLength (); - float centerX = ((float)cloud->width - 1.f) / 2.f; - float centerY = ((float)cloud->height - 1.f) / 2.f; + float centerX = (static_cast(cloud->width) - 1.f) / 2.f; + float centerY = (static_cast(cloud->height) - 1.f) / 2.f; if (std::isfinite (depth_parameters_.focal_length_x)) constant_x = 1.0f / static_cast (depth_parameters_.focal_length_x); @@ -613,8 +613,8 @@ pcl::io::OpenNI2Grabber::convertToXYZRGBPointCloud (const Image::Ptr &image, con // Generate default camera parameters float fx = device_->getDepthFocalLength (); // Horizontal focal length float fy = device_->getDepthFocalLength (); // Vertcal focal length - float cx = ((float)depth_width_ - 1.f) / 2.f; // Center x - float cy = ((float)depth_height_- 1.f) / 2.f; // Center y + float cx = (static_cast(depth_width_) - 1.f) / 2.f; // Center x + float cy = (static_cast(depth_height_)- 1.f) / 2.f; // Center y // Load pre-calibrated camera parameters if they exist if (std::isfinite (depth_parameters_.focal_length_x)) @@ -740,8 +740,8 @@ pcl::io::OpenNI2Grabber::convertToXYZIPointCloud (const IRImage::Ptr &ir_image, float fx = device_->getDepthFocalLength (); // Horizontal focal length float fy = device_->getDepthFocalLength (); // Vertcal focal length - float cx = ((float)cloud->width - 1.f) / 2.f; // Center x - float cy = ((float)cloud->height - 1.f) / 2.f; // Center y + float cx = (static_cast(cloud->width) - 1.f) / 2.f; // Center x + float cy = (static_cast(cloud->height) - 1.f) / 2.f; // Center y // Load pre-calibrated camera parameters if they exist if (std::isfinite (depth_parameters_.focal_length_x)) diff --git a/io/src/openni_camera/openni_device.cpp b/io/src/openni_camera/openni_device.cpp index 69d58fbd4f7..fbd195c7b7b 100644 --- a/io/src/openni_camera/openni_device.cpp +++ b/io/src/openni_camera/openni_device.cpp @@ -394,10 +394,10 @@ void openni_wrapper::OpenNIDevice::InitShiftToDepthConversion () for (std::uint32_t nIndex = 1; nIndex < shift_conversion_parameters_.device_max_shift_; nIndex++) { - auto nShiftValue = (std::int32_t)nIndex; + auto nShiftValue = static_cast(nIndex); - double dFixedRefX = (double) (nShiftValue - nConstShift) / - (double) shift_conversion_parameters_.param_coeff_; + double dFixedRefX = static_cast(nShiftValue - nConstShift) / + static_cast(shift_conversion_parameters_.param_coeff_); dFixedRefX -= 0.375; double dMetric = dFixedRefX * dPlanePixelSize; double dDepth = shift_conversion_parameters_.shift_scale_ * @@ -407,7 +407,7 @@ void openni_wrapper::OpenNIDevice::InitShiftToDepthConversion () if ((dDepth > shift_conversion_parameters_.min_depth_) && (dDepth < shift_conversion_parameters_.max_depth_)) { - shift_to_depth_table_[nIndex] = (std::uint16_t)(dDepth); + shift_to_depth_table_[nIndex] = static_cast(dDepth); } } @@ -429,67 +429,67 @@ openni_wrapper::OpenNIDevice::ReadDeviceParametersFromSensorNode () if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the zero plane distance failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.zero_plane_distance_ = (XnUInt16)nTemp; + shift_conversion_parameters_.zero_plane_distance_ = static_cast(nTemp); status = depth_generator_.GetRealProperty ("ZPPS", dTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the zero plane pixel size failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.zero_plane_pixel_size_ = (XnFloat)dTemp; + shift_conversion_parameters_.zero_plane_pixel_size_ = static_cast(dTemp); status = depth_generator_.GetRealProperty ("LDDIS", dTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the dcmos distance failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.emitter_dcmos_distace_ = (XnFloat)dTemp; + shift_conversion_parameters_.emitter_dcmos_distace_ = static_cast(dTemp); status = depth_generator_.GetIntProperty ("MaxShift", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the max shift parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.max_shift_ = (XnUInt32)nTemp; + shift_conversion_parameters_.max_shift_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("DeviceMaxDepth", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the device max depth parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.device_max_shift_ = (XnUInt32)nTemp; + shift_conversion_parameters_.device_max_shift_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("ConstShift", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the const shift parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.const_shift_ = (XnUInt32)nTemp; + shift_conversion_parameters_.const_shift_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("PixelSizeFactor", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the pixel size factor failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.pixel_size_factor_ = (XnUInt32)nTemp; + shift_conversion_parameters_.pixel_size_factor_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("ParamCoeff", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the param coeff parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.param_coeff_ = (XnUInt32)nTemp; + shift_conversion_parameters_.param_coeff_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("ShiftScale", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the shift scale parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.shift_scale_ = (XnUInt32)nTemp; + shift_conversion_parameters_.shift_scale_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("MinDepthValue", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the min depth value parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.min_depth_ = (XnUInt32)nTemp; + shift_conversion_parameters_.min_depth_ = static_cast(nTemp); status = depth_generator_.GetIntProperty ("MaxDepthValue", nTemp); if (status != XN_STATUS_OK) THROW_OPENNI_EXCEPTION ("reading the max depth value parameter failed. Reason: %s", xnGetStatusString (status)); - shift_conversion_parameters_.max_depth_ = (XnUInt32)nTemp; + shift_conversion_parameters_.max_depth_ = static_cast(nTemp); shift_conversion_parameters_.init_ = true; } diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 8df70a4b4d8..adddad8cc63 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -551,8 +551,8 @@ pcl::OpenNIGrabber::convertToXYZPointCloud (const openni_wrapper::DepthImage::Pt float constant_x = 1.0f / device_->getDepthFocalLength (depth_width_); float constant_y = 1.0f / device_->getDepthFocalLength (depth_width_); - float centerX = ((float)cloud->width - 1.f) / 2.f; - float centerY = ((float)cloud->height - 1.f) / 2.f; + float centerX = (static_cast(cloud->width) - 1.f) / 2.f; + float centerY = (static_cast(cloud->height) - 1.f) / 2.f; if (std::isfinite (depth_focal_length_x_)) constant_x = 1.0f / static_cast (depth_focal_length_x_); @@ -628,8 +628,8 @@ pcl::OpenNIGrabber::convertToXYZRGBPointCloud (const openni_wrapper::Image::Ptr //float constant = 1.0f / device_->getImageFocalLength (depth_width_); float constant_x = 1.0f / device_->getDepthFocalLength (depth_width_); float constant_y = 1.0f / device_->getDepthFocalLength (depth_width_); - float centerX = ((float)cloud->width - 1.f) / 2.f; - float centerY = ((float)cloud->height - 1.f) / 2.f; + float centerX = (static_cast(cloud->width) - 1.f) / 2.f; + float centerY = (static_cast(cloud->height) - 1.f) / 2.f; if (std::isfinite (depth_focal_length_x_)) constant_x = 1.0f / static_cast (depth_focal_length_x_); @@ -743,8 +743,8 @@ pcl::OpenNIGrabber::convertToXYZIPointCloud (const openni_wrapper::IRImage::Ptr //float constant = 1.0f / device_->getImageFocalLength (cloud->width); float constant_x = 1.0f / device_->getImageFocalLength (cloud->width); float constant_y = 1.0f / device_->getImageFocalLength (cloud->width); - float centerX = ((float)cloud->width - 1.f) / 2.f; - float centerY = ((float)cloud->height - 1.f) / 2.f; + float centerX = (static_cast(cloud->width) - 1.f) / 2.f; + float centerY = (static_cast(cloud->height) - 1.f) / 2.f; if (std::isfinite (rgb_focal_length_x_)) constant_x = 1.0f / static_cast (rgb_focal_length_x_); diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 85d132fef7a..c56483ec12f 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -379,16 +379,16 @@ pcl::PLYReader::vertexColorCallback (const std::string& color_name, pcl::io::ply { if ((color_name == "red") || (color_name == "diffuse_red")) { - r_ = std::int32_t (color); + r_ = static_cast(color); rgb_offset_before_ = vertex_offset_before_; } if ((color_name == "green") || (color_name == "diffuse_green")) { - g_ = std::int32_t (color); + g_ = static_cast(color); } if ((color_name == "blue") || (color_name == "diffuse_blue")) { - b_ = std::int32_t (color); + b_ = static_cast(color); std::int32_t rgb = r_ << 16 | g_ << 8 | b_; try { @@ -409,7 +409,7 @@ pcl::PLYReader::vertexAlphaCallback (pcl::io::ply::uint8 alpha) // get anscient rgb value and store it in rgba rgba_ = cloud_->at(vertex_count_, rgb_offset_before_); // append alpha - a_ = std::uint32_t (alpha); + a_ = static_cast(alpha); rgba_ |= a_ << 24; // put rgba back cloud_->at(vertex_count_, rgb_offset_before_) = rgba_; @@ -1536,13 +1536,13 @@ pcl::io::savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh { const auto& color = mesh.cloud.at(i, mesh.cloud.fields[d].offset); - fs << int (color.r) << " " << int (color.g) << " " << int (color.b) << " "; + fs << static_cast(color.r) << " " << static_cast(color.g) << " " << static_cast(color.b) << " "; } else if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::UINT32) && (mesh.cloud.fields[d].name == "rgba")) { const auto& color = mesh.cloud.at(i, mesh.cloud.fields[d].offset); - fs << int (color.r) << " " << int (color.g) << " " << int (color.b) << " " << int (color.a) << " "; + fs << static_cast(color.r) << " " << static_cast(color.g) << " " << static_cast(color.b) << " " << static_cast(color.a) << " "; } else if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && ( mesh.cloud.fields[d].name == "normal_x" || diff --git a/io/src/real_sense_2_grabber.cpp b/io/src/real_sense_2_grabber.cpp index f5dd3ff9566..bd84192f198 100644 --- a/io/src/real_sense_2_grabber.cpp +++ b/io/src/real_sense_2_grabber.cpp @@ -319,8 +319,8 @@ namespace pcl RealSense2Grabber::getTextureIdx (const rs2::video_frame & texture, float u, float v) { const int w = texture.get_width (), h = texture.get_height (); - int x = std::min (std::max (int (u*w + .5f), 0), w - 1); - int y = std::min (std::max (int (v*h + .5f), 0), h - 1); + int x = std::min (std::max (static_cast (u*w + .5f), 0), w - 1); + int y = std::min (std::max (static_cast (v*h + .5f), 0), h - 1); return x * texture.get_bytes_per_pixel () + y * texture.get_stride_in_bytes (); } diff --git a/io/src/robot_eye_grabber.cpp b/io/src/robot_eye_grabber.cpp index 55566141b77..e9ef154ba2f 100644 --- a/io/src/robot_eye_grabber.cpp +++ b/io/src/robot_eye_grabber.cpp @@ -234,11 +234,11 @@ pcl::RobotEyeGrabber::computeXYZI (pcl::PointXYZI& point, unsigned char* point_d buffer = point_data[2] << 8; buffer |= point_data[3]; // Second 2-byte read will be Elevation - el = (signed short int)buffer / 100.0; + el = static_cast(buffer) / 100.0; buffer = point_data[4] << 8; buffer |= point_data[5]; // Third 2-byte read will be Range - range = (signed short int)buffer / 100.0; + range = static_cast(buffer) / 100.0; buffer = point_data[6] << 8; buffer |= point_data[7]; // Fourth 2-byte read will be Intensity diff --git a/io/tools/hdl_grabber_example.cpp b/io/tools/hdl_grabber_example.cpp index f2ae270ffd1..a72574aaeee 100644 --- a/io/tools/hdl_grabber_example.cpp +++ b/io/tools/hdl_grabber_example.cpp @@ -35,7 +35,7 @@ class SimpleHDLGrabber if (++count == 30) { double now = pcl::getTime(); - std::cout << "got sector scan. Avg Framerate " << double(count) / double(now - last) << " Hz" << std::endl; + std::cout << "got sector scan. Avg Framerate " << static_cast(count) / (now - last) << " Hz" << std::endl; count = 0; last = now; } @@ -58,7 +58,7 @@ class SimpleHDLGrabber if (++count == 30) { double now = pcl::getTime (); - std::cout << "got sweep. Avg Framerate " << double(count) / double(now - last) << " Hz" << std::endl; + std::cout << "got sweep. Avg Framerate " << static_cast(count) / (now - last) << " Hz" << std::endl; count = 0; last = now; } diff --git a/io/tools/openni_grabber_depth_example.cpp b/io/tools/openni_grabber_depth_example.cpp index 4f29daf4889..d224b138cc4 100644 --- a/io/tools/openni_grabber_depth_example.cpp +++ b/io/tools/openni_grabber_depth_example.cpp @@ -55,7 +55,7 @@ class SimpleOpenNIProcessor if (++count == 30) { double now = pcl::getTime (); - std::cout << "got depth-image. Average framerate: " << double(count)/double(now - last) << " Hz" << std::endl; + std::cout << "got depth-image. Average framerate: " << static_cast(count)/(now - last) << " Hz" << std::endl; std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl; count = 0; last = now; diff --git a/io/tools/openni_grabber_example.cpp b/io/tools/openni_grabber_example.cpp index 32448bfb2f4..105ca46c929 100644 --- a/io/tools/openni_grabber_example.cpp +++ b/io/tools/openni_grabber_example.cpp @@ -58,7 +58,7 @@ class SimpleOpenNIProcessor if (++count == 30) { double now = pcl::getTime (); - std::cout << "distance of center pixel :" << cloud->points [(cloud->width >> 1) * (cloud->height + 1)].z << " mm. Average framerate: " << double(count)/double(now - last) << " Hz" << std::endl; + std::cout << "distance of center pixel :" << cloud->points [(cloud->width >> 1) * (cloud->height + 1)].z << " mm. Average framerate: " << static_cast(count)/(now - last) << " Hz" << std::endl; count = 0; last = now; } @@ -81,7 +81,7 @@ class SimpleOpenNIProcessor if (++count == 30) { double now = pcl::getTime (); - std::cout << "got synchronized image x depth-image with constant factor: " << constant << ". Average framerate: " << double(count)/double(now - last) << " Hz" << std::endl; + std::cout << "got synchronized image x depth-image with constant factor: " << constant << ". Average framerate: " << static_cast(count)/(now - last) << " Hz" << std::endl; std::cout << "Depth baseline: " << d_img->getBaseline () << " and focal length: " << d_img->getFocalLength () << std::endl; count = 0; last = now; diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp index b4a0206b825..06ff97f7be6 100644 --- a/io/tools/openni_pcd_recorder.cpp +++ b/io/tools/openni_pcd_recorder.cpp @@ -82,16 +82,16 @@ getTotalSystemMemory () } #endif - if (memory > std::uint64_t (std::numeric_limits::max ())) + if (memory > static_cast(std::numeric_limits::max ())) { memory = std::numeric_limits::max (); } print_info ("Total available memory size: %lluMB.\n", memory / 1048576ull); - return std::size_t (memory); + return static_cast(memory); } -const std::size_t BUFFER_SIZE = std::size_t (getTotalSystemMemory () / (640 * 480 * sizeof (pcl::PointXYZRGBA))); +const std::size_t BUFFER_SIZE = static_cast(getTotalSystemMemory () / (640 * 480 * sizeof (pcl::PointXYZRGBA))); #else constexpr std::size_t BUFFER_SIZE = 200; @@ -130,7 +130,7 @@ class PCDBuffer getSize () { std::lock_guard buff_lock (bmutex_); - return (int (buffer_.size ())); + return (static_cast(buffer_.size ())); } inline int diff --git a/io/tools/pcd_introduce_nan.cpp b/io/tools/pcd_introduce_nan.cpp index cedebda3662..c7c517be157 100644 --- a/io/tools/pcd_introduce_nan.cpp +++ b/io/tools/pcd_introduce_nan.cpp @@ -65,8 +65,8 @@ main (int argc, for (auto &point : *cloud) { - int random = 1 + (rand () % (int) (100)); - int random_xyz = 1 + (rand () % (int) (3 - 1 + 1)); + int random = 1 + (rand () % (100)); + int random_xyz = 1 + (rand () % (3 - 1 + 1)); if (random < percentage_of_NaN) { diff --git a/keypoints/include/pcl/keypoints/brisk_2d.h b/keypoints/include/pcl/keypoints/brisk_2d.h index 332015390e1..e32fc258530 100644 --- a/keypoints/include/pcl/keypoints/brisk_2d.h +++ b/keypoints/include/pcl/keypoints/brisk_2d.h @@ -157,8 +157,8 @@ namespace pcl float x, float y, PointOutT &pt) { - int u = int (x); - int v = int (y); + int u = static_cast(x); + int v = static_cast(y); pt.x = pt.y = pt.z = 0; @@ -167,7 +167,7 @@ namespace pcl const PointInT &p3 = (*cloud)(u, v+1); const PointInT &p4 = (*cloud)(u+1, v+1); - float fx = x - float (u), fy = y - float (v); + float fx = x - static_cast(u), fy = y - static_cast(v); float fx1 = 1.0f - fx, fy1 = 1.0f - fy; float w1 = fx1 * fy1, w2 = fx * fy1, w3 = fx1 * fy, w4 = fx * fy; diff --git a/keypoints/include/pcl/keypoints/impl/brisk_2d.hpp b/keypoints/include/pcl/keypoints/impl/brisk_2d.hpp index 68e0b965d9b..f0b0cfa9221 100644 --- a/keypoints/include/pcl/keypoints/impl/brisk_2d.hpp +++ b/keypoints/include/pcl/keypoints/impl/brisk_2d.hpp @@ -69,8 +69,8 @@ template void BriskKeypoint2D::detectKeypoints (PointCloudOut &output) { // image size - const int width = int (input_->width); - const int height = int (input_->height); + const int width = static_cast(input_->width); + const int height = static_cast(input_->height); // destination for intensity data; will be forwarded to BRISK std::vector image_data (width*height); diff --git a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp index 29801e6f292..1daf3875056 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp @@ -148,12 +148,12 @@ pcl::HarrisKeypoint3D::calculateNormalCovar (const } if (count > 0) { - norm2 = _mm_set1_ps (float(count)); + norm2 = _mm_set1_ps (static_cast(count)); vec1 = _mm_div_ps (vec1, norm2); vec2 = _mm_div_ps (vec2, norm2); _mm_store_ps (coefficients, vec1); _mm_store_ps (coefficients + 4, vec2); - coefficients [7] = zz / float(count); + coefficients [7] = zz / static_cast(count); } else std::fill_n(coefficients, 8, 0); diff --git a/keypoints/include/pcl/keypoints/impl/harris_6d.hpp b/keypoints/include/pcl/keypoints/impl/harris_6d.hpp index 066256e5ad9..d5f9a3537c9 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_6d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_6d.hpp @@ -112,7 +112,7 @@ pcl::HarrisKeypoint6D::calculateCombinedCovar (con } if (count > 0) { - float norm = 1.0 / float (count); + float norm = 1.0 / static_cast(count); coefficients[ 0] *= norm; coefficients[ 1] *= norm; coefficients[ 2] *= norm; diff --git a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp index 398bee6e184..744279f89a5 100644 --- a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp @@ -132,7 +132,7 @@ pcl::ISSKeypoint3D::getBoundaryPoints (PointCloudI shared(angle_threshold, boundary_estimator, border_radius, edge_points, input) \ firstprivate(u, v) \ num_threads(threads_) - for (int index = 0; index < int (input.size ()); index++) + for (int index = 0; index < static_cast(input.size ()); index++) { edge_points[index] = false; PointInT current_point = input[index]; @@ -314,7 +314,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut default(none) \ shared(borders) \ num_threads(threads_) - for (int index = 0; index < int (input_->size ()); index++) + for (int index = 0; index < static_cast(input_->size ()); index++) { borders[index] = false; PointInT current_point = (*input_)[index]; @@ -398,7 +398,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut prg_mem[index][d] = omp_mem[tid][d]; } - for (int index = 0; index < int (input_->size ()); index++) + for (int index = 0; index < static_cast(input_->size ()); index++) { if (!borders[index]) { @@ -413,7 +413,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut default(none) \ shared(feat_max) \ num_threads(threads_) - for (int index = 0; index < int (input_->size ()); index++) + for (int index = 0; index < static_cast(input_->size ()); index++) { feat_max [index] = false; PointInT current_point = (*input_)[index]; @@ -445,7 +445,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut default(none) \ shared(feat_max, output) \ num_threads(threads_) - for (int index = 0; index < int (input_->size ()); index++) + for (int index = 0; index < static_cast(input_->size ()); index++) { if (feat_max[index]) #pragma omp critical diff --git a/keypoints/src/agast_2d.cpp b/keypoints/src/agast_2d.cpp index fa2266cc0d6..541d59698f9 100644 --- a/keypoints/src/agast_2d.cpp +++ b/keypoints/src/agast_2d.cpp @@ -115,8 +115,8 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression ( std::vector >::const_iterator curr_corner; int lastRowCorner_ind = 0, next_lastRowCorner_ind = 0; std::vector::iterator nms_flags_p; - int num_corners_all = int (corners_all.size ()); - int n_max_corners = int (corners_nms.capacity ()); + int num_corners_all = static_cast(corners_all.size ()); + int n_max_corners = static_cast(corners_nms.capacity ()); curr_corner = corners_all.begin (); @@ -159,7 +159,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression ( } if (next_lastRow != curr_corner->v) { - next_lastRow = int (curr_corner->v); + next_lastRow = static_cast(curr_corner->v); next_lastRowCorner_ind = curr_corner_ind; } if (lastRow+1 == curr_corner->v) @@ -373,7 +373,7 @@ namespace pcl std::vector >& corners) { int total = 0; - int n_expected_corners = int (corners.capacity ()); + int n_expected_corners = static_cast(corners.capacity ()); pcl::PointUV h; int width_b = img_width - 3; //2, +1 due to faster test x>width_b int height_b = img_height - 2; @@ -409,8 +409,8 @@ namespace pcl else { const T1* const p = im + y * width + x; - const T2 cb = *p + T2 (threshold); - const T2 c_b = *p - T2 (threshold); + const T2 cb = *p + static_cast(threshold); + const T2 c_b = *p - static_cast(threshold); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset5] > cb) @@ -1447,8 +1447,8 @@ namespace pcl else { const T1* const p = im + y * width + x; - const T2 cb = *p + T2 (threshold); - const T2 c_b = *p - T2 (threshold); + const T2 cb = *p + static_cast(threshold); + const T2 c_b = *p - static_cast(threshold); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset5] > cb) @@ -2416,8 +2416,8 @@ namespace pcl corners.reserve (n_expected_corners); } } - h.u = float (x); - h.v = float (y); + h.u = static_cast(x); + h.v = static_cast(y); corners.push_back (h); total++; goto homogeneous; @@ -2435,8 +2435,8 @@ namespace pcl corners.reserve (n_expected_corners); } } - h.u = float (x); - h.v = float (y); + h.u = static_cast(x); + h.v = static_cast(y); corners.push_back (h); total++; goto structured; @@ -3460,14 +3460,14 @@ namespace pcl double score_threshold, const std::array &offset) { - T2 bmin = T2 (score_threshold); - T2 bmax = T2 (im_bmax); // 255; - int b_test = int ((bmax + bmin) / 2); + T2 bmin = static_cast(score_threshold); + T2 bmax = static_cast(im_bmax); // 255; + int b_test = static_cast ((bmax + bmin) / 2); while (true) { - const T2 cb = *p + T2 (b_test); - const T2 c_b = *p - T2 (b_test); + const T2 cb = *p + static_cast (b_test); + const T2 c_b = *p - static_cast (b_test); if (AgastDetector7_12s_is_a_corner(p, cb, c_b, offset[0], @@ -3483,16 +3483,16 @@ namespace pcl offset[10], offset[11])) { - bmin = T2 (b_test); + bmin = static_cast (b_test); } else { - bmax = T2 (b_test); + bmax = static_cast (b_test); } if (bmin == bmax - 1 || bmin == bmax) - return (int (bmin)); - b_test = int ((bmin + bmax) / 2); + return (static_cast (bmin)); + b_test = static_cast ((bmin + bmax) / 2); } } } // namespace agast @@ -3523,14 +3523,14 @@ pcl::keypoints::agast::AgastDetector7_12s::initPattern () void pcl::keypoints::agast::AgastDetector7_12s::detect (const unsigned char* im, std::vector > & corners) const { - return (AgastDetector7_12s_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (AgastDetector7_12s_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// void pcl::keypoints::agast::AgastDetector7_12s::detect (const float* im, std::vector > & corners) const { - return (AgastDetector7_12s_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (AgastDetector7_12s_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// @@ -3567,10 +3567,10 @@ namespace pcl std::vector >& corners) { int total = 0; - int n_expected_corners = int (corners.capacity ()); + int n_expected_corners = static_cast(corners.capacity ()); pcl::PointUV h; - int xsize_b = int (img_width) - 2; - int ysize_b = int (img_height) - 1; + int xsize_b = (img_width) - 2; + int ysize_b = (img_height) - 1; std::int_fast16_t offset0, offset1, offset2, offset3, offset4, offset5, offset6, offset7; int width; @@ -3584,7 +3584,7 @@ namespace pcl offset5 = offset[5]; offset6 = offset[6]; offset7 = offset[7]; - width = int (img_width); + width = (img_width); for (int y = 1; y < ysize_b; y++) { @@ -3599,8 +3599,8 @@ namespace pcl else { const T1* const p = im + y * width + x; - const T2 cb = *p + T2 (threshold); - const T2 c_b = *p - T2 (threshold); + const T2 cb = *p + static_cast(threshold); + const T2 c_b = *p - static_cast(threshold); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset3] > cb) @@ -3935,8 +3935,8 @@ namespace pcl else { const T1* const p = im + y * width + x; - const T2 cb = *p + T2 (threshold); - const T2 c_b = *p - T2 (threshold); + const T2 cb = *p + static_cast(threshold); + const T2 c_b = *p - static_cast(threshold); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset3] > cb) @@ -4289,8 +4289,8 @@ namespace pcl corners.reserve (n_expected_corners); } } - h.u = float (x); - h.v = float (y); + h.u = static_cast(x); + h.v = static_cast(y); corners.push_back (h); total++; goto homogeneous; @@ -4308,8 +4308,8 @@ namespace pcl corners.reserve (n_expected_corners); } } - h.u = float (x); - h.v = float (y); + h.u = static_cast(x); + h.v = static_cast(y); corners.push_back (h); total++; goto structured; @@ -4444,14 +4444,14 @@ namespace pcl double score_threshold, const std::array &offset) { - T2 bmin = T2 (score_threshold); - T2 bmax = T2 (im_bmax); - int b_test = int ((bmax + bmin) / 2); + T2 bmin = static_cast(score_threshold); + T2 bmax = static_cast(im_bmax); + int b_test = static_cast ((bmax + bmin) / 2); while (true) { - const T2 cb = *p + T2 (b_test); - const T2 c_b = *p - T2 (b_test); + const T2 cb = *p + static_cast (b_test); + const T2 c_b = *p - static_cast (b_test); if (AgastDetector5_8_is_a_corner(p, cb, c_b, offset[0], @@ -4463,16 +4463,16 @@ namespace pcl offset[6], offset[7])) { - bmin = T2 (b_test); + bmin = static_cast (b_test); } else { - bmax = T2 (b_test); + bmax = static_cast (b_test); } if (bmin == bmax - 1 || bmin == bmax) - return (int (bmin)); - b_test = int ((bmin + bmax) / 2); + return (static_cast (bmin)); + b_test = static_cast ((bmin + bmax) / 2); } } } // namespace agast @@ -4498,14 +4498,14 @@ pcl::keypoints::agast::AgastDetector5_8::initPattern () void pcl::keypoints::agast::AgastDetector5_8::detect (const unsigned char* im, std::vector > & corners) const { - return (AgastDetector5_8_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (AgastDetector5_8_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// void pcl::keypoints::agast::AgastDetector5_8::detect (const float* im, std::vector > & corners) const { - return (AgastDetector5_8_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (AgastDetector5_8_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// @@ -4542,10 +4542,10 @@ namespace pcl std::vector >& corners) { int total = 0; - int n_expected_corners = int (corners.capacity ()); + int n_expected_corners = static_cast(corners.capacity ()); pcl::PointUV h; - int xsize_b = int (img_width) - 4; - int ysize_b = int (img_height) - 3; + int xsize_b = (img_width) - 4; + int ysize_b = (img_height) - 3; std::int_fast16_t offset0, offset1, offset2, offset3, offset4, offset5, offset6, offset7, offset8, offset9, offset10, offset11, offset12, offset13, offset14, offset15; int width; @@ -4567,7 +4567,7 @@ namespace pcl offset13 = offset[13]; offset14 = offset[14]; offset15 = offset[15]; - width = int (img_width); + width = (img_width); for (int y = 3; y < ysize_b; y++) { @@ -4580,8 +4580,8 @@ namespace pcl else { const T1* const p = im + y * width + x; - const T2 cb = *p + T2 (threshold); - const T2 c_b = *p - T2 (threshold); + const T2 cb = *p + static_cast(threshold); + const T2 c_b = *p - static_cast(threshold); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset4] > cb) @@ -6625,8 +6625,8 @@ namespace pcl corners.reserve (n_expected_corners); } } - h.u = float (x); - h.v = float (y); + h.u = static_cast(x); + h.v = static_cast(y); corners.push_back (h); total++; } @@ -6642,9 +6642,9 @@ namespace pcl double score_threshold, const std::array &offset) { - T2 bmin = T2 (score_threshold); - T2 bmax = T2 (im_bmax); - int b_test = int ((bmax + bmin) / 2); + T2 bmin = static_cast(score_threshold); + T2 bmax = static_cast(im_bmax); + int b_test = static_cast ((bmax + bmin) / 2); std::int_fast16_t offset0 = offset[0]; std::int_fast16_t offset1 = offset[1]; @@ -6665,8 +6665,8 @@ namespace pcl while (true) { - const T2 cb = *p + T2 (b_test); - const T2 c_b = *p - T2 (b_test); + const T2 cb = *p + static_cast (b_test); + const T2 c_b = *p - static_cast (b_test); if (p[offset0] > cb) if (p[offset2] > cb) if (p[offset4] > cb) @@ -8698,18 +8698,18 @@ namespace pcl goto is_not_a_corner; is_a_corner: - bmin = T2 (b_test); + bmin = static_cast (b_test); goto end; is_not_a_corner: - bmax = T2 (b_test); + bmax = static_cast (b_test); goto end; end: if (bmin == bmax - 1 || bmin == bmax) - return (int (bmin)); - b_test = int ((bmin + bmax) / 2); + return (static_cast (bmin)); + b_test = static_cast ((bmin + bmax) / 2); } } } // namespace agast @@ -8744,14 +8744,14 @@ pcl::keypoints::agast::OastDetector9_16::initPattern () void pcl::keypoints::agast::OastDetector9_16::detect (const unsigned char* im, std::vector > & corners) const { - return (OastDetector9_16_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (OastDetector9_16_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// void pcl::keypoints::agast::OastDetector9_16::detect (const float* im, std::vector > & corners) const { - return (OastDetector9_16_detect (im, int (width_), int (height_), threshold_, offset_, corners)); + return (OastDetector9_16_detect (im, static_cast(width_), static_cast(height_), threshold_, offset_, corners)); } ///////////////////////////////////////////////////////////////////////////////////////// diff --git a/keypoints/src/brisk_2d.cpp b/keypoints/src/brisk_2d.cpp index 79c0085a339..b1da7714112 100644 --- a/keypoints/src/brisk_2d.cpp +++ b/keypoints/src/brisk_2d.cpp @@ -60,7 +60,7 @@ pcl::keypoints::brisk::ScaleSpace::ScaleSpace (int octaves) if (octaves == 0) layers_ = 1; else - layers_ = std::uint8_t (2 * octaves); + layers_ = static_cast(2 * octaves); } ///////////////////////////////////////////////////////////////////////////////////////// @@ -100,8 +100,8 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( keypoints.reserve (2000); // assign thresholds - threshold_ = std::uint8_t (threshold); - safe_threshold_ = std::uint8_t (threshold_ * safety_factor_); + threshold_ = static_cast(threshold); + safe_threshold_ = static_cast(threshold_ * safety_factor_); std::vector > > agast_points; agast_points.resize (layers_); @@ -116,12 +116,12 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( if (layers_ == 1) { // just do a simple 2d subpixel refinement... - const int num = int (agast_points[0].size ()); + const int num = static_cast(agast_points[0].size ()); for (int n = 0; n < num; n++) { const pcl::PointUV& point = agast_points.at (0)[n]; // first check if it is a maximum: - if (!isMax2D (0, int (point.u), int (point.v))) + if (!isMax2D (0, static_cast(point.u), static_cast(point.v))) continue; // let's do the subpixel and float scale refinement: @@ -151,7 +151,7 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( for (std::uint8_t i = 0; i < layers_; i++) { pcl::keypoints::brisk::Layer& l = pyramid_[i]; - const int num = int (agast_points[i].size ()); + const int num = static_cast(agast_points[i].size ()); if (i == layers_ - 1) { @@ -160,12 +160,12 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( const pcl::PointUV& point = agast_points.at (i)[n]; // consider only 2D maxima... - if (!isMax2D (i, int (point.u), int (point.v))) + if (!isMax2D (i, static_cast(point.u), static_cast(point.v))) continue; bool ismax; float dx, dy; - getScoreMaxBelow (i, int (point.u), int (point.v), + getScoreMaxBelow (i, static_cast(point.u), static_cast(point.v), l.getAgastScore (point.u, point.v, safe_threshold_), ismax, dx, dy); if (!ismax) @@ -205,20 +205,20 @@ pcl::keypoints::brisk::ScaleSpace::getKeypoints ( const pcl::PointUV& point = agast_points.at (i)[n]; // first check if it is a maximum: - if (!isMax2D (i, int (point.u), int (point.v))) + if (!isMax2D (i, static_cast(point.u), static_cast(point.v))) { continue; } // let's do the subpixel and float scale refinement: bool ismax; - score = refine3D (i, int (point.u), int (point.v), x, y, scale, ismax); + score = refine3D (i, static_cast(point.u), static_cast(point.v), x, y, scale, ismax); if (!ismax) continue; // finally store the detected keypoint: - if (score > float (threshold_)) + if (score > static_cast(threshold_)) { keypoints.emplace_back(x, y, 0.0f, basic_size_ * scale, -1, score, i); } @@ -290,28 +290,28 @@ pcl::keypoints::brisk::ScaleSpace::getScoreBelow ( if (layer % 2 == 0) { // octave int sixth_x = 8 * x_layer + 1; - xf = float (sixth_x) / 6.0f; + xf = static_cast(sixth_x) / 6.0f; int sixth_y = 8 * y_layer + 1; - yf = float (sixth_y) / 6.0f; + yf = static_cast(sixth_y) / 6.0f; // scaling: offs = 2.0f / 3.0f; area = 4.0f * offs * offs; scaling = static_cast (4194304.0f / area); - scaling2 = static_cast (float (scaling) * area); + scaling2 = static_cast (static_cast(scaling) * area); } else { int quarter_x = 6 * x_layer + 1; - xf = float (quarter_x) / 4.0f; + xf = static_cast(quarter_x) / 4.0f; int quarter_y = 6 * y_layer + 1; - yf = float (quarter_y) / 4.0f; + yf = static_cast(quarter_y) / 4.0f; // scaling: offs = 3.0f / 4.0f; area = 4.0f * offs * offs; scaling = static_cast (4194304.0f / area); - scaling2 = static_cast (float (scaling) * area); + scaling2 = static_cast (static_cast(scaling) * area); } // calculate borders @@ -320,49 +320,49 @@ pcl::keypoints::brisk::ScaleSpace::getScoreBelow ( const float y_1 = yf - offs; const float y1 = yf + offs; - const int x_left = int (x_1 + 0.5); - const int y_top = int (y_1 + 0.5); - const int x_right = int (x1 + 0.5); - const int y_bottom = int (y1 + 0.5); + const int x_left = static_cast(x_1 + 0.5); + const int y_top = static_cast(y_1 + 0.5); + const int x_right = static_cast(x1 + 0.5); + const int y_bottom = static_cast(y1 + 0.5); // overlap area - multiplication factors: - const float r_x_1 = float (x_left) - x_1 + 0.5f; - const float r_y_1 = float (y_top) - y_1 + 0.5f; - const float r_x1 = x1 - float (x_right) + 0.5f; - const float r_y1 = y1 - float (y_bottom) + 0.5f; + const float r_x_1 = static_cast(x_left) - x_1 + 0.5f; + const float r_y_1 = static_cast(y_top) - y_1 + 0.5f; + const float r_x1 = x1 - static_cast(x_right) + 0.5f; + const float r_y1 = y1 - static_cast(y_bottom) + 0.5f; const int dx = x_right - x_left - 1; const int dy = y_bottom - y_top - 1; - const int A = static_cast ((r_x_1 * r_y_1) * float (scaling)); - const int B = static_cast ((r_x1 * r_y_1) * float (scaling)); - const int C = static_cast ((r_x1 * r_y1) * float (scaling)); - const int D = static_cast ((r_x_1 * r_y1) * float (scaling)); - const int r_x_1_i = static_cast (r_x_1 * float (scaling)); - const int r_y_1_i = static_cast (r_y_1 * float (scaling)); - const int r_x1_i = static_cast (r_x1 * float (scaling)); - const int r_y1_i = static_cast (r_y1 * float (scaling)); + const int A = static_cast ((r_x_1 * r_y_1) * static_cast(scaling)); + const int B = static_cast ((r_x1 * r_y_1) * static_cast(scaling)); + const int C = static_cast ((r_x1 * r_y1) * static_cast(scaling)); + const int D = static_cast ((r_x_1 * r_y1) * static_cast(scaling)); + const int r_x_1_i = static_cast (r_x_1 * static_cast(scaling)); + const int r_y_1_i = static_cast (r_y_1 * static_cast(scaling)); + const int r_x1_i = static_cast (r_x1 * static_cast(scaling)); + const int r_y1_i = static_cast (r_y1 * static_cast(scaling)); // first row: - int ret_val = A * int (l.getAgastScore (x_left, y_top, 1)); + int ret_val = A * static_cast(l.getAgastScore (x_left, y_top, 1)); for (int X = 1; X <= dx; X++) - ret_val += r_y_1_i * int (l.getAgastScore (x_left + X, y_top, 1)); + ret_val += r_y_1_i * static_cast(l.getAgastScore (x_left + X, y_top, 1)); - ret_val += B * int (l.getAgastScore (x_left + dx + 1, y_top, 1)); + ret_val += B * static_cast(l.getAgastScore (x_left + dx + 1, y_top, 1)); // middle ones: for (int Y = 1; Y <= dy; Y++) { - ret_val += r_x_1_i * int (l.getAgastScore (x_left, y_top + Y, 1)); + ret_val += r_x_1_i * static_cast(l.getAgastScore (x_left, y_top + Y, 1)); for (int X = 1; X <= dx; X++) - ret_val += int (l.getAgastScore (x_left + X, y_top + Y, 1)) * scaling; + ret_val += static_cast(l.getAgastScore (x_left + X, y_top + Y, 1)) * scaling; - ret_val += r_x1_i * int (l.getAgastScore (x_left + dx + 1, y_top + Y, 1)); + ret_val += r_x1_i * static_cast(l.getAgastScore (x_left + dx + 1, y_top + Y, 1)); } // last row: - ret_val += D * int (l.getAgastScore (x_left, y_top + dy + 1, 1)); + ret_val += D * static_cast(l.getAgastScore (x_left, y_top + dy + 1, 1)); for (int X = 1; X <= dx; X++) - ret_val += r_y1_i * int (l.getAgastScore (x_left + X, y_top + dy + 1, 1)); + ret_val += r_y1_i * static_cast(l.getAgastScore (x_left + X, y_top + dy + 1, 1)); - ret_val += C * int (l.getAgastScore (x_left + dx + 1, y_top + dy + 1, 1)); + ret_val += C * static_cast(l.getAgastScore (x_left + dx + 1, y_top + dy + 1, 1)); return ((ret_val + scaling2 / 2) / scaling2); } @@ -563,18 +563,18 @@ pcl::keypoints::brisk::ScaleSpace::refine3D ( // calculate the relative scale (1D maximum): if (layer == 0) - scale = refine1D_2 (max_below_float, std::max (float (center), max_layer), max_above,max); + scale = refine1D_2 (max_below_float, std::max (static_cast(center), max_layer), max_above,max); else - scale = refine1D (max_below_float, std::max (float (center), max_layer), max_above,max); + scale = refine1D (max_below_float, std::max (static_cast(center), max_layer), max_above,max); if (scale > 1.0) { // interpolate the position: const float r0 = (1.5f - scale) / .5f; const float r1 = 1.0f - r0; - x = (r0 * delta_x_layer + r1 * delta_x_above + float (x_layer)) + x = (r0 * delta_x_layer + r1 * delta_x_above + static_cast(x_layer)) * this_layer.getScale () + this_layer.getOffset (); - y = (r0 * delta_y_layer + r1 * delta_y_above + float (y_layer)) + y = (r0 * delta_y_layer + r1 * delta_y_above + static_cast(y_layer)) * this_layer.getScale () + this_layer.getOffset (); } else @@ -584,17 +584,17 @@ pcl::keypoints::brisk::ScaleSpace::refine3D ( // interpolate the position: const float r0 = (scale - 0.5f) / 0.5f; const float r_1 = 1.0f - r0; - x = r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer); - y = r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer); + x = r0 * delta_x_layer + r_1 * delta_x_below + static_cast(x_layer); + y = r0 * delta_y_layer + r_1 * delta_y_below + static_cast(y_layer); } else { // interpolate the position: const float r0 = (scale - 0.75f) / 0.25f; const float r_1 = 1.0f -r0; - x = (r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer)) + x = (r0 * delta_x_layer + r_1 * delta_x_below + static_cast(x_layer)) * this_layer.getScale () +this_layer.getOffset (); - y = (r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer)) + y = (r0 * delta_y_layer + r_1 * delta_y_below + static_cast(y_layer)) * this_layer.getScale () + this_layer.getOffset (); } } @@ -626,15 +626,15 @@ pcl::keypoints::brisk::ScaleSpace::refine3D ( delta_x_layer, delta_y_layer); // calculate the relative scale (1D maximum): - scale = refine1D_1 (max_below, std::max (float (center),max_layer), max_above,max); + scale = refine1D_1 (max_below, std::max (static_cast(center),max_layer), max_above,max); if (scale > 1.0) { // interpolate the position: const float r0 = 4.0f - scale * 3.0f; const float r1 = 1.0f - r0; - x = (r0 * delta_x_layer + r1 * delta_x_above + float (x_layer)) + x = (r0 * delta_x_layer + r1 * delta_x_above + static_cast(x_layer)) * this_layer.getScale () + this_layer.getOffset (); - y = (r0 * delta_y_layer + r1 * delta_y_above + float (y_layer)) + y = (r0 * delta_y_layer + r1 * delta_y_above + static_cast(y_layer)) * this_layer.getScale () + this_layer.getOffset (); } else @@ -642,9 +642,9 @@ pcl::keypoints::brisk::ScaleSpace::refine3D ( // interpolate the position: const float r0 = scale * 3.0f - 2.0f; const float r_1 = 1.0f - r0; - x = (r0 * delta_x_layer + r_1 * delta_x_below + float (x_layer)) + x = (r0 * delta_x_layer + r_1 * delta_x_below + static_cast(x_layer)) * this_layer.getScale () + this_layer.getOffset (); - y = (r0 * delta_y_layer + r_1 * delta_y_below + float (y_layer)) + y = (r0 * delta_y_layer + r_1 * delta_y_below + static_cast(y_layer)) * this_layer.getScale () + this_layer.getOffset (); } } @@ -677,33 +677,33 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( if (layer % 2 == 0) { // octave - x_1 = float (4 * (x_layer) - 1 - 2) / 6.0f; - x1 = float (4 * (x_layer) - 1 + 2) / 6.0f; - y_1 = float (4 * (y_layer) - 1 - 2) / 6.0f; - y1 = float (4 * (y_layer) - 1 + 2) / 6.0f; + x_1 = static_cast(4 * (x_layer) - 1 - 2) / 6.0f; + x1 = static_cast(4 * (x_layer) - 1 + 2) / 6.0f; + y_1 = static_cast(4 * (y_layer) - 1 - 2) / 6.0f; + y1 = static_cast(4 * (y_layer) - 1 + 2) / 6.0f; } else { // intra - x_1 = float (6 * (x_layer) - 1 - 3) / 8.0f; - x1 = float (6 * (x_layer) - 1 + 3) / 8.0f; - y_1 = float (6 * (y_layer) - 1 - 3) / 8.0f; - y1 = float (6 * (y_layer) - 1 + 3) / 8.0f; + x_1 = static_cast(6 * (x_layer) - 1 - 3) / 8.0f; + x1 = static_cast(6 * (x_layer) - 1 + 3) / 8.0f; + y_1 = static_cast(6 * (y_layer) - 1 - 3) / 8.0f; + y1 = static_cast(6 * (y_layer) - 1 + 3) / 8.0f; } // check the first row //int max_x = int (x_1) + 1; //int max_y = int (y_1) + 1; - int max_x = int (x_1 + 1.0f); - int max_y = int (y_1 + 1.0f); + int max_x = static_cast(x_1 + 1.0f); + int max_y = static_cast(y_1 + 1.0f); float tmp_max = 0; float max = layer_above.getAgastScore (x_1, y_1, 1,1.0f); if (max > threshold) return (0); //for (int x = int (x_1) + 1; x <= int (x1); x++) - for (int x = int (x_1 + 1.0f); x <= int (x1); x++) + for (int x = static_cast(x_1 + 1.0f); x <= static_cast(x1); x++) { - tmp_max = layer_above.getAgastScore (float (x), y_1, 1,1.0f); + tmp_max = layer_above.getAgastScore (static_cast(x), y_1, 1,1.0f); if (tmp_max > threshold) return (0); if (tmp_max > max) @@ -718,22 +718,22 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( if (tmp_max > max) { max = tmp_max; - max_x = int (x1); + max_x = static_cast(x1); } // middle rows - for (int y = int (y_1) + 1; y <= int (y1); y++) + for (int y = static_cast(y_1) + 1; y <= static_cast(y1); y++) { - tmp_max = layer_above.getAgastScore (x_1, float (y), 1); + tmp_max = layer_above.getAgastScore (x_1, static_cast(y), 1); if (tmp_max > threshold) return (0); if (tmp_max > max) { max = tmp_max; - max_x = int (x_1 + 1); + max_x = static_cast(x_1 + 1); max_y = y; } - for (int x = int (x_1) + 1; x <= int (x1); x++) + for (int x = static_cast(x_1) + 1; x <= static_cast(x1); x++) { tmp_max = layer_above.getAgastScore (x, y, 1); @@ -745,13 +745,13 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( max_y = y; } } - tmp_max = layer_above.getAgastScore(x1,float(y),1); + tmp_max = layer_above.getAgastScore(x1,static_cast(y),1); if (tmp_max > threshold) return 0; if (tmp_max > max) { max = tmp_max; - max_x = int (x1); + max_x = static_cast(x1); max_y = y; } } @@ -762,18 +762,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( if (tmp_max > max) { max = tmp_max; - max_x = int (x_1 + 1); - max_y = int (y1); + max_x = static_cast(x_1 + 1); + max_y = static_cast(y1); } - for (int x = int (x_1) + 1; x <= int (x1); x++) + for (int x = static_cast(x_1) + 1; x <= static_cast(x1); x++) { - tmp_max = layer_above.getAgastScore (float (x), y1, 1); + tmp_max = layer_above.getAgastScore (static_cast(x), y1, 1); if (tmp_max > max) { max = tmp_max; max_x = x; - max_y = int (y1); + max_y = static_cast(y1); } } tmp_max = layer_above.getAgastScore (x1, y1, 1); @@ -781,8 +781,8 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( if (tmp_max > max) { max = tmp_max; - max_x = int (x1); - max_y = int (y1); + max_x = static_cast(x1); + max_y = static_cast(y1); } //find dx/dy: @@ -802,18 +802,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxAbove ( dx_1, dy_1); // calculate dx/dy in above coordinates - float real_x = float (max_x) + dx_1; - float real_y = float (max_y) + dy_1; + float real_x = static_cast(max_x) + dx_1; + float real_y = static_cast(max_y) + dy_1; bool returnrefined = true; if (layer % 2 == 0) { - dx = (real_x * 6.0f + 1.0f) / 4.0f - float (x_layer); - dy = (real_y * 6.0f + 1.0f) / 4.0f - float (y_layer); + dx = (real_x * 6.0f + 1.0f) / 4.0f - static_cast(x_layer); + dy = (real_y * 6.0f + 1.0f) / 4.0f - static_cast(y_layer); } else { - dx = (real_x * 8.0f + 1.0f) / 6.0f - float (x_layer); - dy = (real_y * 8.0f + 1.0f) / 6.0f - float (y_layer); + dx = (real_x * 8.0f + 1.0f) / 6.0f - static_cast(x_layer); + dy = (real_y * 8.0f + 1.0f) / 6.0f - static_cast(y_layer); } // saturate @@ -846,17 +846,17 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( if (layer % 2 == 0) { // octave - x_1 = float (8 * (x_layer) + 1 - 4) / 6.0f; - x1 = float (8 * (x_layer) + 1 + 4) / 6.0f; - y_1 = float (8 * (y_layer) + 1 - 4) / 6.0f; - y1 = float (8 * (y_layer) + 1 + 4) / 6.0f; + x_1 = static_cast(8 * (x_layer) + 1 - 4) / 6.0f; + x1 = static_cast(8 * (x_layer) + 1 + 4) / 6.0f; + y_1 = static_cast(8 * (y_layer) + 1 - 4) / 6.0f; + y1 = static_cast(8 * (y_layer) + 1 + 4) / 6.0f; } else { - x_1 = float (6 * (x_layer) + 1 - 3) / 4.0f; - x1 = float (6 * (x_layer) + 1 + 3) / 4.0f; - y_1 = float (6 * (y_layer) + 1 - 3) / 4.0f; - y1 = float (6 * (y_layer) + 1 + 3) / 4.0f; + x_1 = static_cast(6 * (x_layer) + 1 - 3) / 4.0f; + x1 = static_cast(6 * (x_layer) + 1 + 3) / 4.0f; + y_1 = static_cast(6 * (y_layer) + 1 - 3) / 4.0f; + y1 = static_cast(6 * (y_layer) + 1 + 3) / 4.0f; } // the layer below @@ -864,14 +864,14 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( pcl::keypoints::brisk::Layer& layer_below = pyramid_[layer-1]; // check the first row - int max_x = int (x_1) + 1; - int max_y = int (y_1) + 1; + int max_x = static_cast(x_1) + 1; + int max_y = static_cast(y_1) + 1; float tmp_max; float max = layer_below.getAgastScore (x_1, y_1, 1); if (max > threshold) return (0); - for (int x = int (x_1) + 1; x <= int (x1); x++) + for (int x = static_cast(x_1) + 1; x <= static_cast(x1); x++) { - tmp_max = layer_below.getAgastScore (float (x), y_1, 1); + tmp_max = layer_below.getAgastScore (static_cast(x), y_1, 1); if (tmp_max > threshold) return (0); if (tmp_max > max) { @@ -884,21 +884,21 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( if (tmp_max > max) { max = tmp_max; - max_x = int (x1); + max_x = static_cast(x1); } // middle rows - for (int y = int (y_1) + 1; y <= int (y1); y++) + for (int y = static_cast(y_1) + 1; y <= static_cast(y1); y++) { - tmp_max = layer_below.getAgastScore (x_1, float (y), 1); + tmp_max = layer_below.getAgastScore (x_1, static_cast(y), 1); if (tmp_max > threshold) return (0); if (tmp_max > max) { max = tmp_max; - max_x = int (x_1 + 1); + max_x = static_cast(x_1 + 1); max_y = y; } - for (int x = int (x_1) + 1; x <= int (x1); x++) + for (int x = static_cast(x_1) + 1; x <= static_cast(x1); x++) { tmp_max = layer_below.getAgastScore (x, y, 1); if (tmp_max > threshold) return (0); @@ -935,12 +935,12 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( max_y = y; } } - tmp_max = layer_below.getAgastScore (x1, float (y), 1); + tmp_max = layer_below.getAgastScore (x1, static_cast(y), 1); if (tmp_max > threshold) return (0); if (tmp_max > max) { max = tmp_max; - max_x = int (x1); + max_x = static_cast(x1); max_y = y; } } @@ -950,25 +950,25 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( if (tmp_max > max) { max = tmp_max; - max_x = int (x_1 + 1); - max_y = int (y1); + max_x = static_cast(x_1 + 1); + max_y = static_cast(y1); } - for (int x = int (x_1) + 1; x <= int (x1); x++) + for (int x = static_cast(x_1) + 1; x <= static_cast(x1); x++) { - tmp_max = layer_below.getAgastScore (float (x), y1, 1); + tmp_max = layer_below.getAgastScore (static_cast(x), y1, 1); if (tmp_max>max) { max = tmp_max; max_x = x; - max_y = int (y1); + max_y = static_cast(y1); } } tmp_max = layer_below.getAgastScore (x1, y1, 1); if (tmp_max > max) { max = tmp_max; - max_x = int (x1); - max_y = int (y1); + max_x = static_cast(x1); + max_y = static_cast(y1); } //find dx/dy: @@ -988,18 +988,18 @@ pcl::keypoints::brisk::ScaleSpace::getScoreMaxBelow ( dx_1, dy_1); // calculate dx/dy in above coordinates - float real_x = float (max_x) + dx_1; - float real_y = float (max_y) + dy_1; + float real_x = static_cast(max_x) + dx_1; + float real_y = static_cast(max_y) + dy_1; bool returnrefined = true; if (layer % 2 == 0) { - dx = (real_x * 6.0f + 1.0f) / 8.0f - float (x_layer); - dy = (real_y * 6.0f + 1.0f) / 8.0f - float (y_layer); + dx = (real_x * 6.0f + 1.0f) / 8.0f - static_cast(x_layer); + dy = (real_y * 6.0f + 1.0f) / 8.0f - static_cast(y_layer); } else { - dx = (real_x * 4.0f - 1.0f) / 6.0f - float (x_layer); - dy = (real_y * 4.0f - 1.0f) / 6.0f - float (y_layer); + dx = (real_x * 4.0f - 1.0f) / 6.0f - static_cast(x_layer); + dy = (real_y * 4.0f - 1.0f) / 6.0f - static_cast(y_layer); } // saturate @@ -1021,9 +1021,9 @@ float pcl::keypoints::brisk::ScaleSpace::refine1D ( const float s_05, const float s0, const float s05, float& max) { - int i_05 = int (1024.0 * s_05 + 0.5); - int i0 = int (1024.0 * s0 + 0.5); - int i05 = int (1024.0 * s05 + 0.5); + int i_05 = static_cast(1024.0 * s_05 + 0.5); + int i0 = static_cast(1024.0 * s0 + 0.5); + int i05 = static_cast(1024.0 * s05 + 0.5); // 16.0000 -24.0000 8.0000 // -40.0000 54.0000 -14.0000 @@ -1052,7 +1052,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D ( int three_b = -40 * i_05 + 54 * i0 - 14 * i05; // calculate max location: - float ret_val = -float (three_b) / float (2 * three_a); + float ret_val = -static_cast(three_b) / static_cast(2 * three_a); // saturate and return if (ret_val < 0.75f) ret_val= 0.75f; @@ -1060,7 +1060,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D ( if (ret_val > 1.5f) ret_val= 1.5f; // allow to be slightly off bounds ...? int three_c = +24 * i_05 -27 * i0 +6 * i05; - max = float (three_c) + float (three_a) * ret_val * ret_val + float (three_b) * ret_val; + max = static_cast(three_c) + static_cast(three_a) * ret_val * ret_val + static_cast(three_b) * ret_val; max /= 3072.0f; return (ret_val); } @@ -1070,9 +1070,9 @@ float pcl::keypoints::brisk::ScaleSpace::refine1D_1 ( const float s_05, const float s0, const float s05, float& max) { - int i_05 = int (1024.0 *s_05 + 0.5); - int i0 = int (1024.0 *s0 + 0.5); - int i05 = int (1024.0 *s05 + 0.5); + int i_05 = static_cast(1024.0 *s_05 + 0.5); + int i0 = static_cast(1024.0 *s0 + 0.5); + int i05 = static_cast(1024.0 *s05 + 0.5); // 4.5000 -9.0000 4.5000 //-10.5000 18.0000 -7.5000 @@ -1101,7 +1101,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_1 ( int two_b = -21 * i_05 + 36 * i0 - 15 * i05; // calculate max location: - float ret_val = -float (two_b) / float (2 * two_a); + float ret_val = -static_cast(two_b) / static_cast(2 * two_a); // saturate and return if (ret_val < 0.6666666666666666666666666667f) ret_val = 0.666666666666666666666666667f; @@ -1109,7 +1109,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_1 ( if (ret_val > 1.33333333333333333333333333f) ret_val = 1.333333333333333333333333333f; int two_c = +12 * i_05 -16 * i0 +6 * i05; - max = float (two_c) + float (two_a) * ret_val * ret_val + float (two_b) * ret_val; + max = static_cast(two_c) + static_cast(two_a) * ret_val * ret_val + static_cast(two_b) * ret_val; max /= 2048.0f; return (ret_val); } @@ -1119,9 +1119,9 @@ float pcl::keypoints::brisk::ScaleSpace::refine1D_2 ( const float s_05, const float s0, const float s05, float& max) { - int i_05 = int (1024.0 * s_05 + 0.5); - int i0 = int (1024.0 * s0 + 0.5); - int i05 = int (1024.0 * s05 + 0.5); + int i_05 = static_cast(1024.0 * s_05 + 0.5); + int i0 = static_cast(1024.0 * s0 + 0.5); + int i05 = static_cast(1024.0 * s05 + 0.5); // 18.0000 -30.0000 12.0000 // -45.0000 65.0000 -20.0000 @@ -1150,7 +1150,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_2 ( int b = -5 * i_05 + 8 * i0 - 3 * i05; // calculate max location: - float ret_val = -float (b) / float (2 * a); + float ret_val = -static_cast(b) / static_cast(2 * a); // saturate and return if (ret_val < 0.7f) ret_val = 0.7f; @@ -1158,7 +1158,7 @@ pcl::keypoints::brisk::ScaleSpace::refine1D_2 ( if (ret_val > 1.5f) ret_val = 1.5f; // allow to be slightly off bounds ...? int c = +3 * i_05 -3 * i0 +1 * i05; - max = float (c) + float(a) * ret_val * ret_val + float (b) * ret_val; + max = static_cast(c) + static_cast(a) * ret_val * ret_val + static_cast(b) * ret_val; max /= 1024.0f; return (ret_val); } @@ -1191,7 +1191,7 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D ( { delta_x = 0.0f; delta_y = 0.0f; - return (float (coeff6) / 18.0f); + return (static_cast(coeff6) / 18.0f); } if (!(H_det > 0 && coeff1 < 0)) @@ -1218,12 +1218,12 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D ( tmp_max = tmp; delta_x = -1.0f; delta_y = -1.0f; } - return (float (tmp_max + coeff1 + coeff2 + coeff6) / 18.0f); + return (static_cast(tmp_max + coeff1 + coeff2 + coeff6) / 18.0f); } // this is hopefully the normal outcome of the Hessian test - delta_x = float (2 * coeff2 * coeff3 - coeff4 * coeff5) / float (-H_det); - delta_y = float (2 * coeff1 * coeff4 - coeff3 * coeff5) / float (-H_det); + delta_x = static_cast(2 * coeff2 * coeff3 - coeff4 * coeff5) / static_cast(-H_det); + delta_y = static_cast(2 * coeff1 * coeff4 - coeff3 * coeff5) / static_cast(-H_det); // TODO: this is not correct, but easy, so perform a real boundary maximum search: bool tx = false; bool tx_ = false; bool ty = false; bool ty_ = false; if (delta_x > 1.0f) tx = true; @@ -1238,36 +1238,36 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D ( if (tx) { delta_x1 = 1.0f; - delta_y1 = -float (coeff4 + coeff5) / float (2.0 * coeff2); + delta_y1 = -static_cast(coeff4 + coeff5) / static_cast(2.0 * coeff2); if (delta_y1 > 1.0f) delta_y1 = 1.0f; else if (delta_y1 < -1.0f) delta_y1 = -1.0f; } else if (tx_) { delta_x1 = -1.0f; - delta_y1 = -float (coeff4 - coeff5) / float (2.0 * coeff2); + delta_y1 = -static_cast(coeff4 - coeff5) / static_cast(2.0 * coeff2); if (delta_y1 > 1.0f) delta_y1 = 1.0f; else if (delta_y1 < -1.0f) delta_y1 = -1.0f; } if (ty) { delta_y2 = 1.0f; - delta_x2 = -float (coeff3 + coeff5) / float (2.0 * coeff1); + delta_x2 = -static_cast(coeff3 + coeff5) / static_cast(2.0 * coeff1); if (delta_x2 > 1.0f) delta_x2 = 1.0f; else if (delta_x2 < -1.0f) delta_x2 = -1.0f; } else if (ty_) { delta_y2 = -1.0f; - delta_x2 = -float (coeff3 - coeff5) / float (2.0 * coeff1); + delta_x2 = -static_cast(coeff3 - coeff5) / static_cast(2.0 * coeff1); if (delta_x2 > 1.0f) delta_x2 = 1.0f; else if (delta_x2 < -1.0f) delta_x2 = -1.0f; } // insert both options for evaluation which to pick - float max1 = (float (coeff1) * delta_x1 * delta_x1 + float (coeff2) * delta_y1 * delta_y1 - +float (coeff3) * delta_x1 + float (coeff4) * delta_y1 - +float (coeff5) * delta_x1 * delta_y1 - +float (coeff6)) / 18.0f; - float max2 = (float (coeff1) * delta_x2 * delta_x2 + float (coeff2) * delta_y2 * delta_y2 - +float (coeff3) * delta_x2 + float (coeff4) * delta_y2 - +float (coeff5) * delta_x2 * delta_y2 - +float (coeff6)) / 18.0f; + float max1 = (static_cast(coeff1) * delta_x1 * delta_x1 + static_cast(coeff2) * delta_y1 * delta_y1 + +static_cast(coeff3) * delta_x1 + static_cast(coeff4) * delta_y1 + +static_cast(coeff5) * delta_x1 * delta_y1 + +static_cast(coeff6)) / 18.0f; + float max2 = (static_cast(coeff1) * delta_x2 * delta_x2 + static_cast(coeff2) * delta_y2 * delta_y2 + +static_cast(coeff3) * delta_x2 + static_cast(coeff4) * delta_y2 + +static_cast(coeff5) * delta_x2 * delta_y2 + +static_cast(coeff6)) / 18.0f; if (max1 > max2) { delta_x = delta_x1; @@ -1280,10 +1280,10 @@ pcl::keypoints::brisk::ScaleSpace::subpixel2D ( } // this is the case of the maximum inside the boundaries: - return ((float (coeff1) * delta_x * delta_x + float (coeff2) * delta_y * delta_y - +float (coeff3) * delta_x + float (coeff4) * delta_y - +float (coeff5) * delta_x * delta_y - +float (coeff6)) / 18.0f); + return ((static_cast(coeff1) * delta_x * delta_x + static_cast(coeff2) * delta_y * delta_y + +static_cast(coeff3) * delta_x + static_cast(coeff4) * delta_y + +static_cast(coeff5) * delta_x * delta_y + +static_cast(coeff6)) / 18.0f); } ///////////////////////////////////////////////////////////////////////////////////////// @@ -1350,12 +1350,12 @@ pcl::keypoints::brisk::Layer::getAgastPoints ( oast_detector_->detect (&img_[0], keypoints); // also write scores - const int num = int (keypoints.size ()); + const int num = static_cast(keypoints.size ()); const int imcols = img_width_; for (int i = 0; i < num; i++) { - const int offs = int (keypoints[i].u + keypoints[i].v * float (imcols)); + const int offs = static_cast(keypoints[i].u + keypoints[i].v * static_cast(imcols)); *(&scores_[0] + offs) = static_cast (oast_detector_->computeCornerScore (&img_[0] + offs)); } } @@ -1378,7 +1378,7 @@ pcl::keypoints::brisk::Layer::getAgastScore (int x, int y, std::uint8_t threshol return (score); } oast_detector_->setThreshold (threshold - 1); - score = std::uint8_t (oast_detector_->computeCornerScore (&img_[0] + x + y * img_width_)); + score = static_cast(oast_detector_->computeCornerScore (&img_[0] + x + y * img_width_)); if (score < threshold) score = 0; return (score); } @@ -1398,7 +1398,7 @@ pcl::keypoints::brisk::Layer::getAgastScore_5_8 (int x, int y, std::uint8_t thre } agast_detector_5_8_->setThreshold (threshold - 1); - auto score = std::uint8_t (agast_detector_5_8_->computeCornerScore (&img_[0] + x + y * img_width_)); + auto score = static_cast(agast_detector_5_8_->computeCornerScore (&img_[0] + x + y * img_width_)); if (score < threshold) score = 0; return (score); } @@ -1410,11 +1410,11 @@ pcl::keypoints::brisk::Layer::getAgastScore (float xf, float yf, std::uint8_t th if (scale <= 1.0f) { // just do an interpolation inside the layer - const int x = int (xf); - const float rx1 = xf - float (x); + const int x = static_cast(xf); + const float rx1 = xf - static_cast(x); const float rx = 1.0f - rx1; - const int y = int (yf); - const float ry1 = yf -float (y); + const int y = static_cast(yf); + const float ry1 = yf -static_cast(y); const float ry = 1.0f -ry1; const float value = rx * ry * getAgastScore (x, y, threshold)+ @@ -1429,8 +1429,8 @@ pcl::keypoints::brisk::Layer::getAgastScore (float xf, float yf, std::uint8_t th // this means we overlap area smoothing const float halfscale = scale / 2.0f; // get the scores first: - for (int x = int (xf - halfscale); x <= int (xf + halfscale + 1.0f); x++) - for (int y = int (yf - halfscale); y <= int (yf + halfscale + 1.0f); y++) + for (int x = static_cast(xf - halfscale); x <= static_cast(xf + halfscale + 1.0f); x++) + for (int y = static_cast(yf - halfscale); y <= static_cast(yf + halfscale + 1.0f); y++) getAgastScore (x, y, threshold); // get the smoothed value return (getValue (scores_, img_width_, img_height_, xf, yf, scale)); @@ -1447,8 +1447,8 @@ pcl::keypoints::brisk::Layer::getValue ( pcl::utils::ignore(height); assert (!mat.empty ()); // get the position - const int x = int (std::floor (xf)); - const int y = int (std::floor (yf)); + const int x = static_cast(std::floor (xf)); + const int y = static_cast(std::floor (yf)); const std::vector& image = mat; const int& imagecols = width; @@ -1461,20 +1461,20 @@ pcl::keypoints::brisk::Layer::getValue ( if (sigma_half < 0.5) { // interpolation multipliers: - const int r_x = static_cast ((xf - float (x)) * 1024); - const int r_y = static_cast ((yf - float (y)) * 1024); + const int r_x = static_cast ((xf - static_cast(x)) * 1024); + const int r_y = static_cast ((yf - static_cast(y)) * 1024); const int r_x_1 = (1024 - r_x); const int r_y_1 = (1024 - r_y); const unsigned char* ptr = &image[0] + x + y * imagecols; // just interpolate: - ret_val = (r_x_1 * r_y_1 * int (*ptr)); + ret_val = (r_x_1 * r_y_1 * static_cast(*ptr)); ptr++; - ret_val += (r_x * r_y_1 * int (*ptr)); + ret_val += (r_x * r_y_1 * static_cast(*ptr)); ptr += imagecols; - ret_val += (r_x * r_y * int (*ptr)); + ret_val += (r_x * r_y * static_cast(*ptr)); ptr--; - ret_val += (r_x_1 * r_y * int (*ptr)); + ret_val += (r_x_1 * r_y * static_cast(*ptr)); return (static_cast (0xFF & ((ret_val + 512) / 1024 / 1024))); } @@ -1482,7 +1482,7 @@ pcl::keypoints::brisk::Layer::getValue ( // scaling: const int scaling = static_cast (4194304.0f / area); - const int scaling2 = static_cast (float (scaling) * area / 1024.0f); + const int scaling2 = static_cast (static_cast(scaling) * area / 1024.0f); // calculate borders const float x_1 = xf - sigma_half; @@ -1490,37 +1490,37 @@ pcl::keypoints::brisk::Layer::getValue ( const float y_1 = yf - sigma_half; const float y1 = yf + sigma_half; - const int x_left = int (x_1 + 0.5f); - const int y_top = int (y_1 + 0.5f); - const int x_right = int (x1 + 0.5f); - const int y_bottom = int (y1 + 0.5f); + const int x_left = static_cast(x_1 + 0.5f); + const int y_top = static_cast(y_1 + 0.5f); + const int x_right = static_cast(x1 + 0.5f); + const int y_bottom = static_cast(y1 + 0.5f); // overlap area - multiplication factors: - const float r_x_1 = float (x_left) - x_1 + 0.5f; - const float r_y_1 = float (y_top) - y_1 + 0.5f; - const float r_x1 = x1 - float (x_right) + 0.5f; - const float r_y1 = y1 - float (y_bottom) + 0.5f; + const float r_x_1 = static_cast(x_left) - x_1 + 0.5f; + const float r_y_1 = static_cast(y_top) - y_1 + 0.5f; + const float r_x1 = x1 - static_cast(x_right) + 0.5f; + const float r_y1 = y1 - static_cast(y_bottom) + 0.5f; const int dx = x_right - x_left - 1; const int dy = y_bottom - y_top - 1; - const int A = static_cast ((r_x_1 * r_y_1) * float (scaling)); - const int B = static_cast ((r_x1 * r_y_1) * float (scaling)); - const int C = static_cast ((r_x1 * r_y1) * float (scaling)); - const int D = static_cast ((r_x_1 * r_y1) * float (scaling)); - const int r_x_1_i = static_cast (r_x_1 * float (scaling)); - const int r_y_1_i = static_cast (r_y_1 * float (scaling)); - const int r_x1_i = static_cast (r_x1 * float (scaling)); - const int r_y1_i = static_cast (r_y1 * float (scaling)); + const int A = static_cast ((r_x_1 * r_y_1) * static_cast(scaling)); + const int B = static_cast ((r_x1 * r_y_1) * static_cast(scaling)); + const int C = static_cast ((r_x1 * r_y1) * static_cast(scaling)); + const int D = static_cast ((r_x_1 * r_y1) * static_cast(scaling)); + const int r_x_1_i = static_cast (r_x_1 * static_cast(scaling)); + const int r_y_1_i = static_cast (r_y_1 * static_cast(scaling)); + const int r_x1_i = static_cast (r_x1 * static_cast(scaling)); + const int r_y1_i = static_cast (r_y1 * static_cast(scaling)); // now the calculation: const unsigned char* ptr = &image[0] + x_left + imagecols * y_top; // first row: - ret_val = A * int (*ptr); + ret_val = A * static_cast(*ptr); ptr++; const unsigned char* end1 = ptr + dx; for (; ptr < end1; ptr++) - ret_val += r_y_1_i * int (*ptr); + ret_val += r_y_1_i * static_cast(*ptr); - ret_val += B * int (*ptr); + ret_val += B * static_cast(*ptr); // middle ones: ptr += imagecols - dx - 1; @@ -1528,23 +1528,23 @@ pcl::keypoints::brisk::Layer::getValue ( for (; ptr < end_j; ptr += imagecols - dx - 1) { - ret_val += r_x_1_i * int (*ptr); + ret_val += r_x_1_i * static_cast(*ptr); ptr++; const unsigned char* end2 = ptr + dx; for (; ptr < end2; ptr++) - ret_val += int (*ptr) * scaling; + ret_val += static_cast(*ptr) * scaling; - ret_val += r_x1_i * int (*ptr); + ret_val += r_x1_i * static_cast(*ptr); } // last row: - ret_val += D * int (*ptr); + ret_val += D * static_cast(*ptr); ptr++; const unsigned char* end3 = ptr + dx; for (; ptr < end3; ptr++) - ret_val += r_y1_i * int (*ptr); + ret_val += r_y1_i * static_cast(*ptr); - ret_val += C * int (*ptr); + ret_val += C * static_cast(*ptr); return (static_cast (0xFF & ((ret_val + scaling2 / 2) / scaling2 / 1024))); } @@ -1720,10 +1720,10 @@ pcl::keypoints::brisk::Layer::twothirdsample ( assert (std::floor (double (srcheight) / 3.0 * 2.0) == dstheight); // masks: - __m128i mask1 = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),12,char(0x80),10,char(0x80),7,char(0x80),4,char(0x80),1); - __m128i mask2 = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),12,char(0x80),10,char(0x80),7,char(0x80),4,char(0x80),1,char(0x80)); - __m128i mask = _mm_set_epi8 (char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),14,12,11,9,8,6,5,3,2,0); - __m128i store_mask = _mm_set_epi8 (0x0,0x0,0x0,0x0,0x0,0x0,char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80),char(0x80)); + __m128i mask1 = _mm_set_epi8 (static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),12,static_cast(0x80),10,static_cast(0x80),7,static_cast(0x80),4,static_cast(0x80),1); + __m128i mask2 = _mm_set_epi8 (static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),12,static_cast(0x80),10,static_cast(0x80),7,static_cast(0x80),4,static_cast(0x80),1,static_cast(0x80)); + __m128i mask = _mm_set_epi8 (static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),14,12,11,9,8,6,5,3,2,0); + __m128i store_mask = _mm_set_epi8 (0x0,0x0,0x0,0x0,0x0,0x0,static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80)); // data pointers: const unsigned char* p1 = &srcimg[0]; diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index 35daf09357d..1c51db55c30 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -240,8 +240,8 @@ NarfKeypoint::calculateCompleteInterestImage () std::vector start_usage_ranges; start_usage_ranges.resize (range_image_scale_space_.size ()); - start_usage_ranges[int (range_image_scale_space_.size ())-1] = 0.0f; - for (int scale_idx = int (range_image_scale_space_.size ())-2; scale_idx >= 0; --scale_idx) + start_usage_ranges[static_cast(range_image_scale_space_.size ())-1] = 0.0f; + for (int scale_idx = static_cast(range_image_scale_space_.size ())-2; scale_idx >= 0; --scale_idx) { start_usage_ranges[scale_idx] = parameters_.support_size / tanf (static_cast (parameters_.optimal_range_image_patch_size) * range_image_scale_space_[scale_idx+1]->getAngularResolution ()); @@ -251,7 +251,7 @@ NarfKeypoint::calculateCompleteInterestImage () //double interest_value_calculation_start_time = getTime (); interest_image_scale_space_.clear (); interest_image_scale_space_.resize (range_image_scale_space_.size (), nullptr); - for (int scale_idx = int (range_image_scale_space_.size ())-1; scale_idx >= 0; --scale_idx) + for (int scale_idx = static_cast(range_image_scale_space_.size ())-1; scale_idx >= 0; --scale_idx) { const RangeImage& range_image = *range_image_scale_space_[scale_idx]; RangeImageBorderExtractor& border_extractor = *border_extractor_scale_space_[scale_idx]; @@ -305,8 +305,8 @@ NarfKeypoint::calculateCompleteInterestImage () { const RangeImage& half_range_image = *range_image_scale_space_[scale_idx+1]; float* half_interest_image = interest_image_scale_space_[scale_idx+1]; - int half_x = std::min (x/2, int (half_range_image.width)-1), - half_y = std::min (y/2, int (half_range_image.height)-1); + int half_x = std::min (x/2, static_cast(half_range_image.width)-1), + half_y = std::min (y/2, static_cast(half_range_image.height)-1); interest_value = half_interest_image[half_y*half_range_image.width + half_x]; continue; } @@ -343,9 +343,9 @@ NarfKeypoint::calculateCompleteInterestImage () continue; } - for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,int (range_image.height)-1); ++y3) + for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,static_cast(range_image.height)-1); ++y3) { - for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,int (range_image.width)-1); ++x3) + for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,static_cast(range_image.width)-1); ++x3) { int index3 = y3*range_image.width + x3; if (!was_touched[index3]) @@ -390,7 +390,7 @@ NarfKeypoint::calculateCompleteInterestImage () if (angle_histogram[histogram_cell2]==0.0f) continue; // TODO: lookup table for the following: - float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size); + float normalized_angle_diff = 2.0f*static_cast(histogram_cell2-histogram_cell1)/static_cast(angle_histogram_size); normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff); angle_change_value = std::max (angle_histogram[histogram_cell1] * angle_histogram[histogram_cell2] * @@ -534,9 +534,9 @@ NarfKeypoint::calculateSparseInterestImage () continue; } - for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,int (range_image.height)-1); ++y3) + for (int y3=std::max (0,y2-1); y3<=std::min (y2+1,static_cast(range_image.height)-1); ++y3) { - for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,int (range_image.width)-1); ++x3) + for (int x3=std::max (0,x2-1); x3<=std::min (x2+1,static_cast(range_image.width)-1); ++x3) { int index3 = y3*range_image.width + x3; if (!was_touched[index3]) @@ -574,7 +574,7 @@ NarfKeypoint::calculateSparseInterestImage () if (angle_histogram[histogram_cell2]==0.0f) continue; // TODO: lookup table for the following: - float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size); + float normalized_angle_diff = 2.0f*static_cast(histogram_cell2-histogram_cell1)/static_cast(angle_histogram_size); normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff); angle_change_value = std::max (angle_histogram[histogram_cell1] * angle_histogram[histogram_cell2] * @@ -608,12 +608,12 @@ NarfKeypoint::calculateSparseInterestImage () std::sort(relevent_point_indices.begin(), relevent_point_indices.end(), secondPairElementIsGreater); relevant_point_still_valid.clear(); relevant_point_still_valid.resize(relevent_point_indices.size(), true); - for (int rpi_idx1=0; rpi_idx1(relevent_point_indices.size ())-1; ++rpi_idx1) { if (!relevant_point_still_valid[rpi_idx1]) continue; const PointWithRange& relevant_point1 = range_image.getPoint (relevent_point_indices[rpi_idx1].first); - for (int rpi_idx2=rpi_idx1+1; rpi_idx2(relevent_point_indices.size ()); ++rpi_idx2) { if (!relevant_point_still_valid[rpi_idx2]) continue; @@ -625,7 +625,7 @@ NarfKeypoint::calculateSparseInterestImage () } } int newPointIdx=0; - for (int oldPointIdx=0; oldPointIdx(relevant_point_still_valid.size()); ++oldPointIdx) { if (relevant_point_still_valid[oldPointIdx]) relevent_point_indices[newPointIdx++] = relevent_point_indices[oldPointIdx]; } @@ -677,7 +677,7 @@ NarfKeypoint::calculateSparseInterestImage () if (angle_histogram[histogram_cell2]==0.0f) continue; // TODO: lookup table for the following: - float normalized_angle_diff = 2.0f*float (histogram_cell2-histogram_cell1)/float (angle_histogram_size); + float normalized_angle_diff = 2.0f*static_cast(histogram_cell2-histogram_cell1)/static_cast(angle_histogram_size); normalized_angle_diff = (normalized_angle_diff <= 1.0f ? normalized_angle_diff : 2.0f-normalized_angle_diff); angle_change_value = std::max (angle_change_value, angle_histogram[histogram_cell1] * angle_histogram[histogram_cell2] * @@ -842,7 +842,7 @@ NarfKeypoint::calculateInterestPoints () float min_distance_squared = powf (parameters_.min_distance_between_interest_points*parameters_.support_size, 2); for (const auto &interest_point : tmp_interest_points) { - if (parameters_.max_no_of_interest_points > 0 && int (interest_points_->size ()) >= parameters_.max_no_of_interest_points) + if (parameters_.max_no_of_interest_points > 0 && static_cast(interest_points_->size ()) >= parameters_.max_no_of_interest_points) break; bool better_point_too_close = false; for (const auto &interest_point2 : interest_points_->points) diff --git a/ml/src/permutohedral.cpp b/ml/src/permutohedral.cpp index f6609b1c6f9..3e450979f1c 100644 --- a/ml/src/permutohedral.cpp +++ b/ml/src/permutohedral.cpp @@ -530,7 +530,7 @@ pcl::Permutohedral::computeOLD(std::vector& out, } // Alpha is a magic scaling constant (write Andrew if you really wanna understand // this) - float alpha = 1.0f / (1.0f + powf(2.0f, -float(d_))); + float alpha = 1.0f / (1.0f + powf(2.0f, -static_cast(d_))); // Slicing for (int i = 0; i < out_size; i++) { diff --git a/ml/src/svm_wrapper.cpp b/ml/src/svm_wrapper.cpp index a9d886437cb..76552693a31 100644 --- a/ml/src/svm_wrapper.cpp +++ b/ml/src/svm_wrapper.cpp @@ -56,7 +56,7 @@ pcl::SVM::readline(FILE* input) while (strrchr(line_, '\n') == nullptr) { max_line_len_ *= 2; line_ = static_cast(realloc(line_, max_line_len_)); - int len = int(strlen(line_)); + int len = static_cast(strlen(line_)); // if the new read part of the string is unavailable, break the while if (fgets(line_ + len, max_line_len_ - len, input) == nullptr) @@ -166,7 +166,7 @@ pcl::SVM::adaptLibSVMToInput(std::vector& training_set, svm_problem pro if (std::isfinite(prob.x[i][j].value)) { seed.idx = prob.x[i][j].index; - seed.value = float(prob.x[i][j].value); + seed.value = static_cast(prob.x[i][j].value); parent.SV.push_back(seed); } @@ -190,7 +190,7 @@ pcl::SVM::adaptInputToLibSVM(std::vector training_set, svm_problem& pro return; } - prob.l = int(training_set.size()); // n of elements/points + prob.l = static_cast(training_set.size()); // n of elements/points prob.y = Malloc(double, prob.l); prob.x = Malloc(struct svm_node*, prob.l); @@ -371,7 +371,7 @@ pcl::SVM::loadProblem(const char* filename, svm_problem& prob) // std::cout << idx << ":" << val<< " "; errno = 0; - x_space_[j].index = int(strtol(idx, &endptr, 10)); + x_space_[j].index = static_cast(strtol(idx, &endptr, 10)); if (endptr == idx || errno != 0 || *endptr != '\0' || x_space_[j].index <= inst_max_index) @@ -408,7 +408,8 @@ pcl::SVM::loadProblem(const char* filename, svm_problem& prob) return false; } - if (int(prob.x[i][0].value) <= 0 || int(prob.x[i][0].value) > max_index) { + if (static_cast(prob.x[i][0].value) <= 0 || + static_cast(prob.x[i][0].value) > max_index) { PCL_ERROR("[pcl::%s] Wrong input format: sample_serial_number out of range.\n", getClassName().c_str()); return false; @@ -641,7 +642,7 @@ pcl::SVMClassify::classificationTest() else { pcl::console::print_info(" - Accuracy (classification) = "); pcl::console::print_value( - "%g%% (%d/%d)\n", double(correct) / total * 100, correct, total); + "%g%% (%d/%d)\n", static_cast(correct) / total * 100, correct, total); } if (predict_probability_) diff --git a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp index 1a28dd1988b..8d947d8f4b8 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp @@ -576,7 +576,7 @@ namespace pcl } // Derive percentage from specified sample_percent and tree depth - const double percent = pow(sample_percent_, double((this->root_node_->m_tree_->getDepth () - depth_))); + const double percent = pow(sample_percent_, static_cast((this->root_node_->m_tree_->getDepth () - depth_))); const auto samplesize = static_cast(percent * static_cast(sampleBuff.size())); const std::uint64_t inputsize = sampleBuff.size(); diff --git a/outofcore/include/pcl/outofcore/octree_disk_container.h b/outofcore/include/pcl/outofcore/octree_disk_container.h index a0d89a709b4..0f9c0acf310 100644 --- a/outofcore/include/pcl/outofcore/octree_disk_container.h +++ b/outofcore/include/pcl/outofcore/octree_disk_container.h @@ -210,7 +210,7 @@ namespace pcl writebuff_.clear (); //remove the binary data in the directory PCL_DEBUG ("[Octree Disk Container] Removing the point data from disk, in file %s\n", disk_storage_filename_.c_str ()); - boost::filesystem::remove (boost::filesystem::path (disk_storage_filename_.c_str ())); + boost::filesystem::remove (static_cast (disk_storage_filename_.c_str ())); //reset the size-of-file counter filelen_ = 0; } diff --git a/outofcore/src/visualization/grid.cpp b/outofcore/src/visualization/grid.cpp index 247479e38af..d4109a20fae 100644 --- a/outofcore/src/visualization/grid.cpp +++ b/outofcore/src/visualization/grid.cpp @@ -26,7 +26,7 @@ Grid::Grid (std::string name, int size/*=10*/, double spacing/*=1.0*/) : // Fill arrays for (int i = -size / 2; i <= size / 2; i++) - xz_array->InsertNextValue ((double)i * spacing); + xz_array->InsertNextValue (static_cast(i) * spacing); y_array->InsertNextValue (0.0); grid_->SetXCoordinates (xz_array); diff --git a/people/apps/main_ground_based_people_detection.cpp b/people/apps/main_ground_based_people_detection.cpp index 8ae58151cb7..ce0c79033a6 100644 --- a/people/apps/main_ground_based_people_detection.cpp +++ b/people/apps/main_ground_based_people_detection.cpp @@ -167,7 +167,7 @@ int main (int argc, char** argv) PointCloudT::Ptr clicked_points_3d (new PointCloudT); cb_args.clicked_points_3d = clicked_points_3d; cb_args.viewerPtr = pcl::visualization::PCLVisualizer::Ptr(&viewer); - viewer.registerPointPickingCallback (pp_callback, (void*)&cb_args); + viewer.registerPointPickingCallback (pp_callback, reinterpret_cast(&cb_args)); std::cout << "Shift+click on three floor points, then press 'Q'..." << std::endl; // Spin until 'Q' is pressed: @@ -244,7 +244,7 @@ int main (int argc, char** argv) if (++count == 30) { double now = pcl::getTime (); - std::cout << "Average framerate: " << double(count)/double(now - last) << " Hz" << std::endl; + std::cout << "Average framerate: " << static_cast(count)/(now - last) << " Hz" << std::endl; count = 0; last = now; } diff --git a/people/include/pcl/people/impl/ground_based_people_detection_app.hpp b/people/include/pcl/people/impl/ground_based_people_detection_app.hpp index 3710c87cb4e..920c843045c 100644 --- a/people/include/pcl/people/impl/ground_based_people_detection_app.hpp +++ b/people/include/pcl/people/impl/ground_based_people_detection_app.hpp @@ -148,8 +148,8 @@ pcl::people::GroundBasedPeopleDetectionApp::setSensorPortraitOrientation template void pcl::people::GroundBasedPeopleDetectionApp::updateMinMaxPoints () { - min_points_ = (int) (min_height_ * min_width_ / voxel_size_ / voxel_size_); - max_points_ = (int) (max_height_ * max_width_ / voxel_size_ / voxel_size_); + min_points_ = static_cast (min_height_ * min_width_ / voxel_size_ / voxel_size_); + max_points_ = static_cast (max_height_ * max_width_ / voxel_size_ / voxel_size_); } template void diff --git a/people/include/pcl/people/impl/head_based_subcluster.hpp b/people/include/pcl/people/impl/head_based_subcluster.hpp index f8586e73970..43d333832eb 100644 --- a/people/include/pcl/people/impl/head_based_subcluster.hpp +++ b/people/include/pcl/people/impl/head_based_subcluster.hpp @@ -291,7 +291,7 @@ pcl::people::HeadBasedSubclustering::subcluster (std::vector > subclusters; - int cluster_min_points_sub = int(float(min_points_) * 1.5); + int cluster_min_points_sub = static_cast(static_cast(min_points_) * 1.5); // int cluster_max_points_sub = max_points_; // create HeightMap2D object: diff --git a/people/include/pcl/people/impl/height_map_2d.hpp b/people/include/pcl/people/impl/height_map_2d.hpp index 0591e27c782..e8640ebd768 100644 --- a/people/include/pcl/people/impl/height_map_2d.hpp +++ b/people/include/pcl/people/impl/height_map_2d.hpp @@ -80,9 +80,9 @@ pcl::people::HeightMap2D::compute (pcl::people::PersonCluster& c // Create a height map with the projection of cluster points onto the ground plane: if (!vertical_) // camera horizontal - buckets_.resize(std::size_t((cluster.getMax()(0) - cluster.getMin()(0)) / bin_size_) + 1, 0); + buckets_.resize(static_cast((cluster.getMax()(0) - cluster.getMin()(0)) / bin_size_) + 1, 0); else // camera vertical - buckets_.resize(std::size_t((cluster.getMax()(1) - cluster.getMin()(1)) / bin_size_) + 1, 0); + buckets_.resize(static_cast((cluster.getMax()(1) - cluster.getMin()(1)) / bin_size_) + 1, 0); buckets_cloud_indices_.resize(buckets_.size(), 0); for(const auto& cluster_idx : cluster.getIndices().indices) @@ -90,9 +90,9 @@ pcl::people::HeightMap2D::compute (pcl::people::PersonCluster& c PointT* p = &(*cloud_)[cluster_idx]; int index; if (!vertical_) // camera horizontal - index = int((p->x - cluster.getMin()(0)) / bin_size_); + index = static_cast((p->x - cluster.getMin()(0)) / bin_size_); else // camera vertical - index = int((p->y - cluster.getMin()(1)) / bin_size_); + index = static_cast((p->y - cluster.getMin()(1)) / bin_size_); if (index > (static_cast (buckets_.size ()) - 1)) std::cout << "Error: out of array - " << index << " of " << buckets_.size() << std::endl; else @@ -122,8 +122,8 @@ pcl::people::HeightMap2D::searchLocalMaxima () maxima_number_ = 0; int left = buckets_[0]; // current left element float offset = 0; // used to center the maximum to the right place - maxima_indices_.resize(std::size_t(buckets_.size()), 0); - maxima_cloud_indices_.resize(std::size_t(buckets_.size()), 0); + maxima_indices_.resize(static_cast(buckets_.size()), 0); + maxima_cloud_indices_.resize(static_cast(buckets_.size()), 0); // Handle first element: if (buckets_[0] > buckets_[1]) @@ -153,7 +153,7 @@ pcl::people::HeightMap2D::searchLocalMaxima () maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1]; } // Insert the new element: - maxima_indices_[t] = i - int(offset/2 + 0.5); + maxima_indices_[t] = i - static_cast(offset/2 + 0.5); maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]]; left = buckets_[i+1]; i +=2; @@ -191,7 +191,7 @@ pcl::people::HeightMap2D::searchLocalMaxima () maxima_cloud_indices_[m] = maxima_cloud_indices_[m-1]; } // Insert the new element: - maxima_indices_[t] = i - int(offset/2 + 0.5); + maxima_indices_[t] = i - static_cast(offset/2 + 0.5); maxima_cloud_indices_[t] = buckets_cloud_indices_[maxima_indices_[t]]; maxima_number_++; diff --git a/people/include/pcl/people/impl/person_classifier.hpp b/people/include/pcl/people/impl/person_classifier.hpp index 1bc86572aa7..1c23d26ba63 100644 --- a/people/include/pcl/people/impl/person_classifier.hpp +++ b/people/include/pcl/people/impl/person_classifier.hpp @@ -122,8 +122,8 @@ pcl::people::PersonClassifier::resize (PointCloudPtr& input_image, output_image->width = width; // Compute scale factor: - float scale1 = float(height) / float(input_image->height); - float scale2 = float(width) / float(input_image->width); + float scale1 = static_cast(height) / static_cast(input_image->height); + float scale2 = static_cast(width) / static_cast(input_image->width); Eigen::Matrix3f T_inv; T_inv << 1/scale1, 0, 0, @@ -163,9 +163,9 @@ pcl::people::PersonClassifier::resize (PointCloudPtr& input_image, w1 = (A(0) - f1); w2 = (A(1) - f2); - new_point.r = int((1 - w1) * ((1 - w2) * g1.r + w2 * g4.r) + w1 * ((1 - w2) * g3.r + w2 * g4.r)); - new_point.g = int((1 - w1) * ((1 - w2) * g1.g + w2 * g4.g) + w1 * ((1 - w2) * g3.g + w2 * g4.g)); - new_point.b = int((1 - w1) * ((1 - w2) * g1.b + w2 * g4.b) + w1 * ((1 - w2) * g3.b + w2 * g4.b)); + new_point.r = static_cast((1 - w1) * ((1 - w2) * g1.r + w2 * g4.r) + w1 * ((1 - w2) * g3.r + w2 * g4.r)); + new_point.g = static_cast((1 - w1) * ((1 - w2) * g1.g + w2 * g4.g) + w1 * ((1 - w2) * g3.g + w2 * g4.g)); + new_point.b = static_cast((1 - w1) * ((1 - w2) * g1.b + w2 * g4.b) + w1 * ((1 - w2) * g3.b + w2 * g4.b)); // Insert the point in the output image: (*output_image)(j,i) = new_point; @@ -190,9 +190,9 @@ pcl::people::PersonClassifier::copyMakeBorder (PointCloudPtr& input_imag output_image->height = height; int x_start_in = std::max(0, xmin); - int x_end_in = std::min(int(input_image->width-1), xmin+width-1); + int x_end_in = std::min(static_cast(input_image->width-1), xmin+width-1); int y_start_in = std::max(0, ymin); - int y_end_in = std::min(int(input_image->height-1), ymin+height-1); + int y_end_in = std::min(static_cast(input_image->height-1), ymin+height-1); int x_start_out = std::max(0, -xmin); //int x_end_out = x_start_out + (x_end_in - x_start_in); @@ -243,9 +243,9 @@ pcl::people::PersonClassifier::evaluate (float height_person, { for (std::uint32_t col = 0; col < sample->width; col++) { - sample_float[row + sample->height * col] = ((float) ((*sample)(col, row).r))/255; //ptr[col * 3 + 2]; - sample_float[row + sample->height * col + delta] = ((float) ((*sample)(col, row).g))/255; //ptr[col * 3 + 1]; - sample_float[row + sample->height * col + delta * 2] = (float) (((*sample)(col, row).b))/255; //ptr[col * 3]; + sample_float[row + sample->height * col] = (static_cast ((*sample)(col, row).r))/255; //ptr[col * 3 + 2]; + sample_float[row + sample->height * col + delta] = (static_cast ((*sample)(col, row).g))/255; //ptr[col * 3 + 1]; + sample_float[row + sample->height * col + delta * 2] = static_cast (((*sample)(col, row).b))/255; //ptr[col * 3]; } } diff --git a/people/src/hog.cpp b/people/src/hog.cpp index 2b3880b6146..f4700b6fe1c 100644 --- a/people/src/hog.cpp +++ b/people/src/hog.cpp @@ -105,7 +105,7 @@ pcl::people::HOG::gradMag( float *I, int h, int w, int d, float *M, float *O ) c std::copy(M2, M2 + h, M + x * h); // compute and store gradient orientation (O) via table lookup - if(O!=nullptr) for( y=0; y(Gx[y])]; } alFree(Gx); alFree(Gy); alFree(M2); #else @@ -170,7 +170,7 @@ void pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int n_orients, bool soft_bin, float *H ) const { const int hb=h/bin_size, wb=w/bin_size, h0=hb*bin_size, w0=wb*bin_size, nb=wb*hb; - const float s=(float)bin_size, sInv=1/s, sInv2=1/s/s; + const float s=static_cast(bin_size), sInv=1/s, sInv2=1/s/s; float *H0, *H1, *M0, *M1; int *O0, *O1; O0=reinterpret_cast(alMalloc(h*sizeof(int),16)); M0=reinterpret_cast(alMalloc(h*sizeof(float),16)); O1=reinterpret_cast(alMalloc(h*sizeof(int),16)); M1=reinterpret_cast(alMalloc(h*sizeof(float),16)); @@ -203,7 +203,7 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int float ms[4], xyd, yb, xd, yd; __m128 _m, _m0, _m1; bool hasLf, hasRt; int xb0, yb0; if( x==0 ) { init=(0+.5f)*sInv-0.5f; xb=init; } - hasLf = xb>=0; xb0 = hasLf?(int)xb:-1; hasRt = xb0 < wb-1; + hasLf = xb>=0; xb0 = hasLf?static_cast(xb):-1; hasRt = xb0 < wb-1; xd=xb-xb0; xb+=sInv; yb=init; int y=0; // lambda for code conciseness @@ -233,7 +233,7 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int } // main rows, has top and bottom bins, use SSE for minor speedup for( ; ; y++ ) { - yb0 = (int) yb; if(yb0>=hb-1) break; GHinit(); + yb0 = static_cast(yb); if(yb0>=hb-1) break; GHinit(); _m0=pcl::sse_set(M0[y]); _m1=pcl::sse_set(M1[y]); if(hasLf) { _m=pcl::sse_set(0,0,ms[1],ms[0]); GH(H0+O0[y],_m,_m0); GH(H0+O1[y],_m,_m1); } @@ -242,7 +242,7 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int } // final rows, no bottom bin_size for( ; y(yb); GHinit(); if(hasLf) { H0[O0[y]]+=ms[0]*M0[y]; H0[O1[y]]+=ms[0]*M1[y]; } if(hasRt) { H0[O0[y]+hb]+=ms[2]*M0[y]; H0[O1[y]+hb]+=ms[2]*M1[y]; } } @@ -315,7 +315,7 @@ pcl::people::HOG::normalization (float *H, int h, int w, int bin_size, int n_ori N = reinterpret_cast(calloc(nb,sizeof(float))); for( o=0; o0 || (std::size_t(I)&15) || (std::size_t(Gx)&15) ) + if( h<4 || h%4>0 || (reinterpret_cast(I)&15) || (reinterpret_cast(Gx)&15) ) { for( y = 0; y < h; y++ ) *Gx++ = (*In++ - *Ip++) * r; @@ -483,12 +483,12 @@ pcl::people::HOG::acosTable () const static float a[25000]; static bool init = false; if( init ) return a+n2; - float ni = 2.02f/(float) n; + float ni = 2.02f/static_cast(n); for(int i=0; i1 ? 1 : t); - t = (float) std::acos( t ); + t = std::acos( t ); a[i] = (t <= M_PI-1e-5f) ? t : 0; } init = true; @@ -499,7 +499,7 @@ void pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0, float *M1, int n_orients, int nb, int n, float norm) const { // define useful constants - const float oMult = (float)n_orients/M_PI; + const float oMult = static_cast(n_orients)/M_PI; const int oMax = n_orients * nb; int i = 0; @@ -508,7 +508,7 @@ pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0, __m128i _o0, _o1, *_O0, *_O1; __m128 _o, _o0f, _m, *_M0, *_M1; const __m128 _norm = pcl::sse_set(norm); const __m128 _oMult = pcl::sse_set(oMult); - const __m128 _nbf = pcl::sse_set((float)nb); + const __m128 _nbf = pcl::sse_set(static_cast(nb)); const __m128i _oMax = pcl::sse_set(oMax); const __m128i _nb = pcl::sse_set(nb); @@ -535,7 +535,7 @@ pcl::people::HOG::gradQuantize (float *O, float *M, int *O0, int *O1, float *M0, for( ; i < n; i++ ) { float o = O[i] * oMult; float m = M[i] * norm; - int o0 = (int) o; + int o0 = static_cast(o); float od = o - o0; o0 *= nb; int o1 = o0 + nb; diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 16891698ffb..359d6c4d308 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -294,7 +294,7 @@ pcl::ColorGradientModality:: computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::vector & kernel_values) { // code taken from OpenCV - const int n = int (kernel_size); + const int n = static_cast(kernel_size); constexpr int SMALL_GAUSSIAN_SIZE = 7; static const float small_gaussian_tab[][SMALL_GAUSSIAN_SIZE] = { @@ -320,16 +320,16 @@ computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::ve for( int i = 0; i < n; i++ ) { double x = i - (n-1)*0.5; - double t = fixed_kernel ? double (fixed_kernel[i]) : std::exp (scale2X*x*x); + double t = fixed_kernel ? static_cast(fixed_kernel[i]) : std::exp (scale2X*x*x); - cf[i] = float (t); + cf[i] = static_cast(t); sum += cf[i]; } sum = 1./sum; for ( int i = 0; i < n; i++ ) { - cf[i] = float (cf[i]*sum); + cf[i] = static_cast(cf[i]*sum); } } diff --git a/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp b/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp index 3efbae002ce..62a50891c34 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_papazov.hpp @@ -141,12 +141,12 @@ template typename boost::graph_traits::adjacency_iterator ai; typename boost::graph_traits::adjacency_iterator ai_end; - auto current = std::static_pointer_cast (graph_id_model_map_[int (v)]); + auto current = std::static_pointer_cast (graph_id_model_map_[static_cast(v)]); bool a_better_one = false; for (boost::tie (ai, ai_end) = boost::adjacent_vertices (v, conflict_graph_); (ai != ai_end) && !a_better_one; ++ai) { - auto neighbour = std::static_pointer_cast (graph_id_model_map_[int (*ai)]); + auto neighbour = std::static_pointer_cast (graph_id_model_map_[static_cast(*ai)]); if ((neighbour->explained_.size () >= current->explained_.size ()) && mask_[neighbour->id_]) { a_better_one = true; @@ -169,7 +169,7 @@ template for (std::size_t i = 0; i < (recognition_models_.size ()); i++) { const typename Graph::vertex_descriptor v = boost::add_vertex (recognition_models_[i], conflict_graph_); - graph_id_model_map_[int (v)] = std::static_pointer_cast (recognition_models_[i]); + graph_id_model_map_[static_cast(v)] = std::static_pointer_cast (recognition_models_[i]); } // iterate over the remaining models and check for each one if there is a conflict with another one diff --git a/recognition/include/pcl/recognition/impl/hv/occlusion_reasoning.hpp b/recognition/include/pcl/recognition/impl/hv/occlusion_reasoning.hpp index a0e8b490938..c20314a8a96 100644 --- a/recognition/include/pcl/recognition/impl/hv/occlusion_reasoning.hpp +++ b/recognition/include/pcl/recognition/impl/hv/occlusion_reasoning.hpp @@ -164,7 +164,7 @@ pcl::occlusion_reasoning::ZBuffering::computeDepthMap (typename { //Dilate and smooth the depth map int ws = wsize; - int ws2 = int (std::floor (static_cast (ws) / 2.f)); + int ws2 = static_cast(std::floor (static_cast (ws) / 2.f)); float * depth_smooth = new float[cx_ * cy_]; for (int i = 0; i < (cx_ * cy_); i++) depth_smooth[i] = std::numeric_limits::quiet_NaN (); diff --git a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp index 04e3d9e9a1e..a340e254439 100644 --- a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp +++ b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp @@ -904,8 +904,8 @@ LineRGBD::removeOverlappingDetections () average_center_z += p_center_z * weight; weight_sum += weight; - average_region_x += float (detections_[detection_id].region.x) * weight; - average_region_y += float (detections_[detection_id].region.y) * weight; + average_region_x += static_cast(detections_[detection_id].region.x) * weight; + average_region_y += static_cast(detections_[detection_id].region.y) * weight; } typename LineRGBD::Detection detection; @@ -926,8 +926,8 @@ LineRGBD::removeOverlappingDetections () detection.bounding_box.height = best_detection_bb_height; detection.bounding_box.depth = best_detection_bb_depth; - detection.region.x = int (average_region_x * inv_weight_sum); - detection.region.y = int (average_region_y * inv_weight_sum); + detection.region.x = static_cast(average_region_x * inv_weight_sum); + detection.region.y = static_cast(average_region_y * inv_weight_sum); detection.region.width = detections_[best_detection_id].region.width; detection.region.height = detections_[best_detection_id].region.height; diff --git a/recognition/src/dotmod.cpp b/recognition/src/dotmod.cpp index e11241537a6..49a18f46ea7 100644 --- a/recognition/src/dotmod.cpp +++ b/recognition/src/dotmod.cpp @@ -170,7 +170,7 @@ detectTemplates (const std::vector & modalities, } // find templates with response over threshold - const float scaling_factor = 1.0f / float (nr_template_horizontal_bins * nr_template_vertical_bins); + const float scaling_factor = 1.0f / static_cast(nr_template_horizontal_bins * nr_template_vertical_bins); for (std::size_t template_index = 0; template_index < nr_templates; ++template_index) { const float response = responses[template_index] * scaling_factor; diff --git a/recognition/src/linemod.cpp b/recognition/src/linemod.cpp index fe61d04c532..bbdf6be2122 100644 --- a/recognition/src/linemod.cpp +++ b/recognition/src/linemod.cpp @@ -323,7 +323,7 @@ pcl::LINEMOD::matchTemplates (const std::vector & modaliti } #endif - const float inv_max_score = 1.0f / float (max_score); + const float inv_max_score = 1.0f / static_cast(max_score); std::size_t max_value = 0; std::size_t max_index = 0; @@ -662,14 +662,14 @@ pcl::LINEMOD::detectTemplates (const std::vector & modalit } #endif - const float inv_max_score = 1.0f / float (max_score); + const float inv_max_score = 1.0f / static_cast(max_score); // we compute a new threshold based on the threshold supplied by the user; // this is due to the use of the cosine approx. in the response computation; #ifdef LINEMOD_USE_SEPARATE_ENERGY_MAPS const float raw_threshold = (4.0f * float (max_score) / 2.0f + template_threshold_ * (4.0f * float (max_score) / 2.0f)); #else - const float raw_threshold = (float (max_score) / 2.0f + template_threshold_ * (float (max_score) / 2.0f)); + const float raw_threshold = (static_cast(max_score) / 2.0f + template_threshold_ * (static_cast(max_score) / 2.0f)); #endif //int max_value = 0; @@ -1023,7 +1023,7 @@ pcl::LINEMOD::detectTemplatesSemiScaleInvariant ( max_score += 4; unsigned char *data = modality_linearized_maps[feature.modality_index][bin_index].getOffsetMap ( - std::size_t (float (feature.x) * scale), std::size_t (float (feature.y) * scale)); + static_cast(static_cast(feature.x) * scale), static_cast(static_cast(feature.y) * scale)); auto * data_m128i = reinterpret_cast<__m128i*> (data); for (std::size_t mem_index = 0; mem_index < mem_size_16; ++mem_index) @@ -1129,14 +1129,14 @@ pcl::LINEMOD::detectTemplatesSemiScaleInvariant ( } #endif - const float inv_max_score = 1.0f / float (max_score); + const float inv_max_score = 1.0f / static_cast(max_score); // we compute a new threshold based on the threshold supplied by the user; // this is due to the use of the cosine approx. in the response computation; #ifdef LINEMOD_USE_SEPARATE_ENERGY_MAPS const float raw_threshold = (4.0f * float (max_score) / 2.0f + template_threshold_ * (4.0f * float (max_score) / 2.0f)); #else - const float raw_threshold = (float (max_score) / 2.0f + template_threshold_ * (float (max_score) / 2.0f)); + const float raw_threshold = (static_cast(max_score) / 2.0f + template_threshold_ * (static_cast(max_score) / 2.0f)); #endif //int max_value = 0; diff --git a/registration/include/pcl/registration/correspondence_rejection.h b/registration/include/pcl/registration/correspondence_rejection.h index df388ac784a..1392d6f6e9b 100644 --- a/registration/include/pcl/registration/correspondence_rejection.h +++ b/registration/include/pcl/registration/correspondence_rejection.h @@ -385,8 +385,9 @@ class DataContainer : public DataContainerInterface { "Normals are not set for the input and target point clouds"); const NormalT& src = (*input_normals_)[corr.index_query]; const NormalT& tgt = (*target_normals_)[corr.index_match]; - return (double((src.normal[0] * tgt.normal[0]) + (src.normal[1] * tgt.normal[1]) + - (src.normal[2] * tgt.normal[2]))); + return (static_cast((src.normal[0] * tgt.normal[0]) + + (src.normal[1] * tgt.normal[1]) + + (src.normal[2] * tgt.normal[2]))); } private: diff --git a/registration/include/pcl/registration/default_convergence_criteria.h b/registration/include/pcl/registration/default_convergence_criteria.h index 7533cc6e27f..dd742438587 100644 --- a/registration/include/pcl/registration/default_convergence_criteria.h +++ b/registration/include/pcl/registration/default_convergence_criteria.h @@ -275,7 +275,7 @@ class DefaultConvergenceCriteria : public ConvergenceCriteria { double mse = 0; for (const auto& correspondence : correspondences) mse += correspondence.distance; - mse /= double(correspondences.size()); + mse /= static_cast(correspondences.size()); return (mse); } diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp index 4b4bd0b2cfe..f9e3d7e178d 100644 --- a/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp +++ b/registration/include/pcl/registration/impl/correspondence_rejection_poly.hpp @@ -167,7 +167,7 @@ CorrespondenceRejectorPoly::computeHistogram( // Accumulate for (const float& value : data) - ++result[std::min(last_idx, int(value * idx_per_val))]; + ++result[std::min(last_idx, static_cast(value * idx_per_val))]; return (result); } diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index a8e9d17e1c0..35bb8c1a9f9 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -53,7 +53,7 @@ GeneralizedIterativeClosestPoint::computeCovar const typename pcl::search::KdTree::Ptr kdtree, MatricesVector& cloud_covariances) { - if (k_correspondences_ > int(cloud->size())) { + if (k_correspondences_ > static_cast(cloud->size())) { PCL_ERROR("[pcl::GeneralizedIterativeClosestPoint::computeCovariances] Number or " "points in cloud (%lu) is less than k_correspondences_ (%lu)!\n", cloud->size(), @@ -284,7 +284,7 @@ GeneralizedIterativeClosestPoint:: Eigen::Vector3d Md(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * d); // increment= d'*Md/num_matches = d'*M*d/num_matches (we postpone // 1/num_matches after the loop closes) - f += double(d.transpose() * Md); + f += static_cast(d.transpose() * Md); } return f / m; } @@ -360,7 +360,7 @@ GeneralizedIterativeClosestPoint:: // Md = M*d Eigen::Vector3d Md(gicp_->mahalanobis((*gicp_->tmp_idx_src_)[i]) * d); // Increment total error - f += double(d.transpose() * Md); + f += static_cast(d.transpose() * Md); // Increment translation gradient // g.head<3> ()+= 2*M*d/num_matches (we postpone 2/num_matches after the loop // closes) @@ -370,8 +370,8 @@ GeneralizedIterativeClosestPoint:: // Increment rotation gradient dCost_dR_T += p_base_src * Md.transpose(); } - f /= double(m); - g.head<3>() *= double(2.0 / m); + f /= static_cast(m); + g.head<3>() *= (2.0 / m); dCost_dR_T *= 2.0 / m; gicp_->computeRDerivative(x, dCost_dR_T, g); } @@ -441,7 +441,8 @@ GeneralizedIterativeClosestPoint:: for (std::size_t i = 0; i < 4; i++) for (std::size_t j = 0; j < 4; j++) for (std::size_t k = 0; k < 4; k++) - transform_R(i, j) += double(transformation_(i, k)) * double(guess(k, j)); + transform_R(i, j) += static_cast(transformation_(i, k)) * + static_cast(guess(k, j)); Eigen::Matrix3d R = transform_R.topLeftCorner<3, 3>(); diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index 51bb956783a..9245f84cfe9 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -312,9 +312,9 @@ pcl::registration::FPCSInitialAlignment(approx_overlap_), + static_cast(min_iterations))); max_iterations_ = static_cast(first_est / (diameter_fraction * approx_overlap_ * 2.f)); } @@ -691,9 +691,9 @@ pcl::registration::FPCSInitialAlignment(std::floor((float)(id / 2.f)))].index_match; + pairs_a[static_cast(std::floor((id / 2.f)))].index_match; match_indices[1] = - pairs_a[static_cast(std::floor((float)(id / 2.f)))].index_query; + pairs_a[static_cast(std::floor((id / 2.f)))].index_query; match_indices[2] = pair.index_match; match_indices[3] = pair.index_query; diff --git a/registration/include/pcl/registration/impl/ia_kfpcs.hpp b/registration/include/pcl/registration/impl/ia_kfpcs.hpp index e0ce10fac57..7d0973b4265 100644 --- a/registration/include/pcl/registration/impl/ia_kfpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_kfpcs.hpp @@ -95,7 +95,7 @@ KFPCSInitialAlignment::initCompute() // generate a subset of indices of size ransac_iterations_ on which to evaluate // candidates on std::size_t nr_indices = indices_->size(); - if (nr_indices < std::size_t(ransac_iterations_)) + if (nr_indices < static_cast(ransac_iterations_)) indices_validation_ = indices_; else for (int i = 0; i < ransac_iterations_; i++) diff --git a/registration/include/pcl/registration/impl/ndt_2d.hpp b/registration/include/pcl/registration/impl/ndt_2d.hpp index 0285757d7c8..3f790cd6e2f 100644 --- a/registration/include/pcl/registration/impl/ndt_2d.hpp +++ b/registration/include/pcl/registration/impl/ndt_2d.hpp @@ -176,7 +176,7 @@ class NormalDist { const Eigen::Vector2d p_xy(transformed_pt.x, transformed_pt.y); const Eigen::Vector2d q = p_xy - mean_; const Eigen::RowVector2d qt_cvi(q.transpose() * covar_inv_); - const double exp_qt_cvi_q = std::exp(-0.5 * double(qt_cvi * q)); + const double exp_qt_cvi_q = std::exp(-0.5 * static_cast(qt_cvi * q)); r.value = -exp_qt_cvi_q; Eigen::Matrix jacobian; @@ -184,7 +184,7 @@ class NormalDist { x * cos_theta - y * sin_theta; for (std::size_t i = 0; i < 3; i++) - r.grad[i] = double(qt_cvi * jacobian.col(i)) * exp_qt_cvi_q; + r.grad[i] = static_cast(qt_cvi * jacobian.col(i)) * exp_qt_cvi_q; // second derivative only for i == j == 2: const Eigen::Vector2d d2q_didj(y * sin_theta - x * cos_theta, @@ -194,7 +194,8 @@ class NormalDist { for (std::size_t j = 0; j < 3; j++) r.hessian(i, j) = -exp_qt_cvi_q * - (double(-qt_cvi * jacobian.col(i)) * double(-qt_cvi * jacobian.col(j)) + + (static_cast(-qt_cvi * jacobian.col(i)) * + static_cast(-qt_cvi * jacobian.col(j)) + (-qt_cvi * ((i == 2 && j == 2) ? d2q_didj : Eigen::Vector2d::Zero())) + (-jacobian.col(j).transpose() * covar_inv_ * jacobian.col(i))); diff --git a/registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp b/registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp index ddfc4be6a87..a21327ba890 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_dual_quaternion.hpp @@ -194,14 +194,15 @@ TransformationEstimationDualQuaternion:: C2 *= 2.0; const Eigen::Matrix A = - (0.25 / double(npts)) * C2.transpose() * C2 - C1; + (0.25 / static_cast(npts)) * C2.transpose() * C2 - C1; const Eigen::EigenSolver> es(A); ptrdiff_t i; es.eigenvalues().real().maxCoeff(&i); const Eigen::Matrix qmat = es.eigenvectors().col(i).real(); - const Eigen::Matrix smat = -(0.5 / double(npts)) * C2 * qmat; + const Eigen::Matrix smat = + -(0.5 / static_cast(npts)) * C2 * qmat; const Eigen::Quaternion q(qmat(3), qmat(0), qmat(1), qmat(2)); const Eigen::Quaternion s(smat(3), smat(0), smat(1), smat(2)); diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index 478fa0b22aa..fbe2b16f5b5 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -228,9 +228,9 @@ class NormalDistributionsTransform convertTransform(const Eigen::Matrix& x, Affine3& trans) { trans = Eigen::Translation(x.head<3>().cast()) * - Eigen::AngleAxis(Scalar(x(3)), Vector3::UnitX()) * - Eigen::AngleAxis(Scalar(x(4)), Vector3::UnitY()) * - Eigen::AngleAxis(Scalar(x(5)), Vector3::UnitZ()); + Eigen::AngleAxis(static_cast(x(3)), Vector3::UnitX()) * + Eigen::AngleAxis(static_cast(x(4)), Vector3::UnitY()) * + Eigen::AngleAxis(static_cast(x(5)), Vector3::UnitZ()); } /** \brief Convert 6 element transformation vector to transformation matrix. diff --git a/registration/src/correspondence_rejection_trimmed.cpp b/registration/src/correspondence_rejection_trimmed.cpp index f305ee82e95..8fcb8abd8df 100644 --- a/registration/src/correspondence_rejection_trimmed.cpp +++ b/registration/src/correspondence_rejection_trimmed.cpp @@ -47,8 +47,8 @@ pcl::registration::CorrespondenceRejectorTrimmed::getRemainingCorrespondences( { // not really an efficient implementation remaining_correspondences = original_correspondences; - unsigned int number_valid_correspondences = (int(std::floor( - overlap_ratio_ * static_cast(remaining_correspondences.size())))); + auto number_valid_correspondences = static_cast(std::floor( + overlap_ratio_ * static_cast(remaining_correspondences.size()))); number_valid_correspondences = std::max(number_valid_correspondences, nr_min_correspondences_); diff --git a/registration/src/correspondence_rejection_var_trimmed.cpp b/registration/src/correspondence_rejection_var_trimmed.cpp index 79ee3955e39..ff6ff5a363b 100644 --- a/registration/src/correspondence_rejection_var_trimmed.cpp +++ b/registration/src/correspondence_rejection_var_trimmed.cpp @@ -57,9 +57,12 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::getRemainingCorrespondences } } factor_ = optimizeInlierRatio(dists); - nth_element( - dists.begin(), dists.begin() + int(double(dists.size()) * factor_), dists.end()); - trimmed_distance_ = dists[int(double(dists.size()) * factor_)]; + nth_element(dists.begin(), + dists.begin() + + static_cast(static_cast(dists.size()) * factor_), + dists.end()); + trimmed_distance_ = + dists[static_cast(static_cast(dists.size()) * factor_)]; unsigned int number_valid_correspondences = 0; remaining_correspondences.resize(original_correspondences.size()); @@ -82,8 +85,8 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio( auto points_nbr = static_cast(dists.size()); std::sort(dists.begin(), dists.end()); - const int min_el = int(std::floor(min_ratio_ * points_nbr)); - const int max_el = int(std::floor(max_ratio_ * points_nbr)); + const int min_el = static_cast(std::floor(min_ratio_ * points_nbr)); + const int max_el = static_cast(std::floor(max_ratio_ * points_nbr)); using LineArray = Eigen::Array; Eigen::Map sorted_dist(&dists[0], points_nbr); @@ -99,6 +102,7 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio( int min_index(0); FRMS.minCoeff(&min_index); - const float opt_ratio = float(min_index + min_el) / float(points_nbr); + const float opt_ratio = + static_cast(min_index + min_el) / static_cast(points_nbr); return (opt_ratio); } diff --git a/registration/src/gicp6d.cpp b/registration/src/gicp6d.cpp index 5c3fa82dc20..c06bc2c2664 100644 --- a/registration/src/gicp6d.cpp +++ b/registration/src/gicp6d.cpp @@ -141,7 +141,8 @@ GeneralizedIterativeClosestPoint6D::computeTransformation(PointCloudSource& outp for (std::size_t i = 0; i < 4; i++) for (std::size_t j = 0; j < 4; j++) for (std::size_t k = 0; k < 4; k++) - transform_R(i, j) += double(transformation_(i, k)) * double(guess(k, j)); + transform_R(i, j) += static_cast(transformation_(i, k)) * + static_cast(guess(k, j)); Eigen::Matrix3d R = transform_R.topLeftCorner<3, 3>(); diff --git a/search/include/pcl/search/impl/flann_search.hpp b/search/include/pcl/search/impl/flann_search.hpp index f54098ffb2a..db951a602b5 100644 --- a/search/include/pcl/search/impl/flann_search.hpp +++ b/search/include/pcl/search/impl/flann_search.hpp @@ -54,7 +54,7 @@ template typename pcl::search::FlannSearch::IndexPtr pcl::search::FlannSearch::KdTreeIndexCreator::createIndex (MatrixConstPtr data) { - return (IndexPtr (new flann::KDTreeSingleIndex (*data,flann::KDTreeSingleIndexParams (max_leaf_size_)))); + return (static_cast (new flann::KDTreeSingleIndex (*data,static_cast (max_leaf_size_)))); } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -62,7 +62,7 @@ template typename pcl::search::FlannSearch::IndexPtr pcl::search::FlannSearch::KMeansIndexCreator::createIndex (MatrixConstPtr data) { - return (IndexPtr (new flann::KMeansIndex (*data,flann::KMeansIndexParams ()))); + return (static_cast (new flann::KMeansIndex (*data,flann::KMeansIndexParams ()))); } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -70,7 +70,7 @@ template typename pcl::search::FlannSearch::IndexPtr pcl::search::FlannSearch::KdTreeMultiIndexCreator::createIndex (MatrixConstPtr data) { - return (IndexPtr (new flann::KDTreeIndex (*data, flann::KDTreeIndexParams (trees_)))); + return (static_cast (new flann::KDTreeIndex (*data, static_cast (trees_)))); } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -383,12 +383,12 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () if (input_->is_dense && point_representation_->isTrivial ()) { // const cast is evil, but flann won't change the data - input_flann_ = MatrixPtr (new flann::Matrix (const_cast(reinterpret_cast(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT))); + input_flann_ = static_cast (new flann::Matrix (const_cast(reinterpret_cast(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT))); input_copied_for_flann_ = false; } else { - input_flann_ = MatrixPtr (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); + input_flann_ = static_cast (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); float* cloud_ptr = input_flann_->ptr(); for (std::size_t i = 0; i < original_no_of_points; ++i) { @@ -410,7 +410,7 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () } else { - input_flann_ = MatrixPtr (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); + input_flann_ = static_cast (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); float* cloud_ptr = input_flann_->ptr(); for (std::size_t indices_index = 0; indices_index < original_no_of_points; ++indices_index) { diff --git a/search/include/pcl/search/impl/organized.hpp b/search/include/pcl/search/impl/organized.hpp index 45b493a376a..704ac1c6094 100644 --- a/search/include/pcl/search/impl/organized.hpp +++ b/search/include/pcl/search/impl/organized.hpp @@ -128,8 +128,8 @@ pcl::search::OrganizedNeighbor::nearestKSearch (const PointT &query, // project query point on the image plane //Eigen::Vector3f q = KR_ * query.getVector3fMap () + projection_matrix_.block <3, 1> (0, 3); Eigen::Vector3f q (KR_ * queryvec + projection_matrix_.block <3, 1> (0, 3)); - int xBegin = int(q [0] / q [2] + 0.5f); - int yBegin = int(q [1] / q [2] + 0.5f); + int xBegin = static_cast(q [0] / q [2] + 0.5f); + int yBegin = static_cast(q [1] / q [2] + 0.5f); int xEnd = xBegin + 1; // end is the pixel that is not used anymore, like in iterators int yEnd = yBegin + 1; @@ -340,8 +340,8 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () return; } - const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, unsigned (1)); - const unsigned xSkip = (std::max) (input_->width >> pyramid_level_, unsigned (1)); + const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, static_cast(1)); + const unsigned xSkip = (std::max) (input_->width >> pyramid_level_, static_cast(1)); Indices indices; indices.reserve (input_->size () >> (pyramid_level_ << 1)); @@ -359,7 +359,7 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () double residual_sqr = pcl::estimateProjectionMatrix (input_, projection_matrix_, indices); - if (std::abs (residual_sqr) > eps_ * float (indices.size ())) + if (std::abs (residual_sqr) > eps_ * static_cast(indices.size ())) { PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %f, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ()); return; diff --git a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp index 9e67b261f69..81729e64c21 100644 --- a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -126,7 +126,7 @@ pcl::ApproximateProgressiveMorphologicalFilter::extract (Indices& ground default(none) \ shared(A, global_min) \ num_threads(threads_) - for (int i = 0; i < (int)input_->size (); ++i) + for (int i = 0; i < static_cast(input_->size ()); ++i) { // ...then test for lower points within the cell PointT p = (*input_)[i]; diff --git a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp index cdba4b46ac5..d9792e0fa4e 100644 --- a/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/organized_connected_component_segmentation.hpp @@ -78,7 +78,7 @@ pcl::OrganizedConnectedComponentSegmentation::findLabeledRegion x = curr_x + directions [dIdx].d_x; y = curr_y + directions [dIdx].d_y; index = curr_idx + directions [dIdx].d_index; - if (x >= 0 && x < int(labels->width) && y >= 0 && y < int(labels->height) && (*labels)[index].label != label) + if (x >= 0 && x < static_cast(labels->width) && y >= 0 && y < static_cast(labels->height) && (*labels)[index].label != label) { direction = dIdx; break; @@ -100,7 +100,7 @@ pcl::OrganizedConnectedComponentSegmentation::findLabeledRegion x = curr_x + directions [nIdx].d_x; y = curr_y + directions [nIdx].d_y; index = curr_idx + directions [nIdx].d_index; - if (x >= 0 && x < int(labels->width) && y >= 0 && y < int(labels->height) && (*labels)[index].label == label) + if (x >= 0 && x < static_cast(labels->width) && y >= 0 && y < static_cast(labels->height) && (*labels)[index].label == label) break; } diff --git a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp index 1bce66b94b9..9ea6cd9cd32 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp @@ -511,9 +511,9 @@ template float pcl::RegionGrowingRGB::calculateColorimetricalDifference (std::vector& first_color, std::vector& second_color) const { float difference = 0.0f; - difference += float ((first_color[0] - second_color[0]) * (first_color[0] - second_color[0])); - difference += float ((first_color[1] - second_color[1]) * (first_color[1] - second_color[1])); - difference += float ((first_color[2] - second_color[2]) * (first_color[2] - second_color[2])); + difference += static_cast((first_color[0] - second_color[0]) * (first_color[0] - second_color[0])); + difference += static_cast((first_color[1] - second_color[1]) * (first_color[1] - second_color[1])); + difference += static_cast((first_color[2] - second_color[2]) * (first_color[2] - second_color[2])); return (difference); } diff --git a/segmentation/src/grabcut_segmentation.cpp b/segmentation/src/grabcut_segmentation.cpp index 6b9e5b99bd7..e6d309f63ca 100644 --- a/segmentation/src/grabcut_segmentation.cpp +++ b/segmentation/src/grabcut_segmentation.cpp @@ -83,7 +83,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::getTargetEdgeCapacity (int u) cons void pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths () { - for (int u = 0; u < (int)nodes_.size (); u++) + for (int u = 0; u < static_cast(nodes_.size ()); u++) { // augment s-u-t paths if ((source_edges_[u] > 0.0) && (target_edges_[u] > 0.0)) @@ -115,7 +115,7 @@ pcl::segmentation::grabcut::BoykovKolmogorov::preAugmentPaths () int pcl::segmentation::grabcut::BoykovKolmogorov::addNodes (std::size_t n) { - int node_id = (int)nodes_.size (); + int node_id = static_cast(nodes_.size ()); nodes_.resize (nodes_.size () + n); source_edges_.resize (nodes_.size (), 0.0); target_edges_.resize (nodes_.size (), 0.0); @@ -283,7 +283,7 @@ void pcl::segmentation::grabcut::BoykovKolmogorov::initializeTrees () { // initialize search tree - for (int u = 0; u < (int)nodes_.size (); u++) + for (int u = 0; u < static_cast(nodes_.size ()); u++) { if (source_edges_[u] > 0.0) { diff --git a/simulation/src/sum_reduce.cpp b/simulation/src/sum_reduce.cpp index e4b95bfe6c9..f6a4b0c7bf5 100644 --- a/simulation/src/sum_reduce.cpp +++ b/simulation/src/sum_reduce.cpp @@ -91,8 +91,8 @@ pcl::simulation::SumReduce::sum(GLuint input_array, float* output_array) glViewport(0, 0, width / 2, height / 2); - float step_x = 1.0f / float(width); - float step_y = 1.0f / float(height); + float step_x = 1.0f / static_cast(width); + float step_y = 1.0f / static_cast(height); sum_program_->setUniform("step_x", step_x); sum_program_->setUniform("step_y", step_y); // float step_x = 1.0f / static_cast (width); diff --git a/simulation/tools/sim_terminal_demo.cpp b/simulation/tools/sim_terminal_demo.cpp index 5b5de285bbe..0347761875f 100644 --- a/simulation/tools/sim_terminal_demo.cpp +++ b/simulation/tools/sim_terminal_demo.cpp @@ -100,7 +100,8 @@ generate_halo( int n_poses) { - for (double t = 0; t < (2 * M_PI); t = t + (2 * M_PI) / ((double)n_poses)) { + for (double t = 0; t < (2 * M_PI); + t = t + (2 * M_PI) / (static_cast(n_poses))) { double x = halo_r * std::cos(t); double y = halo_r * sin(t); double z = halo_dz; @@ -189,7 +190,7 @@ main(int argc, char** argv) pose2.rotate(rot2); int n_poses = 20; - for (double i = 0; i <= 1; i += 1 / ((double)n_poses - 1)) { + for (double i = 0; i <= 1; i += 1 / (static_cast(n_poses) - 1)) { Eigen::Quaterniond rot3; Eigen::Quaterniond r1(pose1.rotation()); Eigen::Quaterniond r2(pose2.rotation()); diff --git a/simulation/tools/sim_test_simple.cpp b/simulation/tools/sim_test_simple.cpp index a0547df862a..10e2b832e16 100644 --- a/simulation/tools/sim_test_simple.cpp +++ b/simulation/tools/sim_test_simple.cpp @@ -516,8 +516,8 @@ on_passive_motion(int x, int y) return; // in window coordinates positive y-axis is down - double pitch = -(0.5 - (double)y / window_height_) * M_PI * 4; - double yaw = (0.5 - (double)x / window_width_) * M_PI * 2 * 4; + double pitch = -(0.5 - static_cast(y) / window_height_) * M_PI * 4; + double yaw = (0.5 - static_cast(x) / window_width_) * M_PI * 2 * 4; camera_->setPitch(pitch); camera_->setYaw(yaw); diff --git a/simulation/tools/sim_viewer.cpp b/simulation/tools/sim_viewer.cpp index f80f0dd5bd2..02bf5745b13 100644 --- a/simulation/tools/sim_viewer.cpp +++ b/simulation/tools/sim_viewer.cpp @@ -638,7 +638,7 @@ main(int argc, char** argv) // Create the PCLVisualizer object here on the first encountered XYZ file if (!p) { p.reset(new pcl::visualization::PCLVisualizer(argc, argv, "PCD viewer")); - p->registerPointPickingCallback(&pp_callback, (void*)&cloud); + p->registerPointPickingCallback(&pp_callback, reinterpret_cast(&cloud)); Eigen::Matrix3f rotation; rotation = orientation; p->setCameraPosition(origin[0], @@ -670,7 +670,7 @@ main(int argc, char** argv) print_info("[done, "); print_value("%g", tt.toc()); print_info(" ms : "); - print_value("%d", (int)cloud->width * cloud->height); + print_value("%d", static_cast(cloud->width * cloud->height)); print_info(" points]\n"); print_info("Available dimensions: "); print_value("%s\n", pcl::getFieldsList(*cloud).c_str()); @@ -827,7 +827,7 @@ main(int argc, char** argv) //////////////////////////////////////////////////////////////// // Key binding for saving simulated point cloud: if (p) - p->registerKeyboardCallback(simulate_callback, (void*)&p); + p->registerKeyboardCallback(simulate_callback, reinterpret_cast(&p)); int width = 640; int height = 480; diff --git a/stereo/src/stereo_adaptive_cost_so.cpp b/stereo/src/stereo_adaptive_cost_so.cpp index 353195bf384..335bebb7d04 100644 --- a/stereo/src/stereo_adaptive_cost_so.cpp +++ b/stereo/src/stereo_adaptive_cost_so.cpp @@ -79,7 +79,7 @@ pcl::AdaptiveCostSOStereoMatching::compute_impl(unsigned char* ref_img, // LUT for color distance weight computation float lut[256]; for (int j = 0; j < 256; j++) - lut[j] = float(std::exp(-j / gamma_c_)); + lut[j] = static_cast(std::exp(-j / gamma_c_)); // left weight array alloc float* wl = new float[2 * radius_ + 1]; diff --git a/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp b/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp index c0f590bbaa9..1fcab8091f8 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp +++ b/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp @@ -126,13 +126,13 @@ namespace pcl baseBSplines = new BSplineComponents[functionCount]; baseFunction = PPolynomial< Degree >::BSpline(); - for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( double(-(Degree+1)/2) + i - 0.5 ); + for( int i=0 ; i<=Degree ; i++ ) baseBSpline[i] = Polynomial< Degree >::BSplineComponent( i ).shift( static_cast(-(Degree+1)/2) + i - 0.5 ); dBaseFunction = baseFunction.derivative(); StartingPolynomial< Degree > sPolys[Degree+3]; for( int i=0 ; i(-(Degree+1)/2) + i - 1.5; sPolys[i].p *= 0; if( i<=Degree ) sPolys[i].p += baseBSpline[i ].shift( -1 ); if( i>=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1]; @@ -141,7 +141,7 @@ namespace pcl leftBaseFunction.set( sPolys , Degree+3 ); for( int i=0 ; i(-(Degree+1)/2) + i - 0.5; sPolys[i].p *= 0; if( i<=Degree ) sPolys[i].p += baseBSpline[i ]; if( i>=1 && i<=Degree+1 ) sPolys[i].p += baseBSpline[i-1].shift( 1 ); @@ -179,18 +179,15 @@ namespace pcl int fullSize = functionCount*functionCount; if( flags & VV_DOT_FLAG ) { - vvDotTable = new Real[size]; - memset( vvDotTable , 0 , sizeof(Real)*size ); + vvDotTable = new Real[size]{}; } if( flags & DV_DOT_FLAG ) { - dvDotTable = new Real[fullSize]; - memset( dvDotTable , 0 , sizeof(Real)*fullSize ); + dvDotTable = new Real[fullSize]{}; } if( flags & DD_DOT_FLAG ) { - ddDotTable = new Real[size]; - memset( ddDotTable , 0 , sizeof(Real)*size ); + ddDotTable = new Real[size]{}; } double vvIntegrals[Degree+1][Degree+1]; double vdIntegrals[Degree+1][Degree ]; @@ -309,12 +306,12 @@ namespace pcl // (start)/(sampleCount-1) >_start && (start-1)/(sampleCount-1)<=_start // => start > _start * (sampleCount-1 ) && start <= _start*(sampleCount-1) + 1 // => _start * (sampleCount-1) + 1 >= start > _start * (sampleCount-1) - start = int( floor( _start * (sampleCount-1) + 1 ) ); + start = static_cast( floor( _start * (sampleCount-1) + 1 ) ); if( start<0 ) start = 0; // (end)/(sampleCount-1)<_end && (end+1)/(sampleCount-1)>=_end // => end < _end * (sampleCount-1 ) && end >= _end*(sampleCount-1) - 1 // => _end * (sampleCount-1) > end >= _end * (sampleCount-1) - 1 - end = int( ceil( _end * (sampleCount-1) - 1 ) ); + end = static_cast( ceil( _end * (sampleCount-1) - 1 ) ); if( end>=sampleCount ) end = sampleCount-1; } template @@ -339,7 +336,7 @@ namespace pcl } for( int j=0 ; j(j)/(sampleCount-1); if(flags & VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));} if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));} } @@ -359,7 +356,7 @@ namespace pcl else {dFunction=baseFunctions[i].derivative();} for(int j=0;j(j)/(sampleCount-1); if(flags & VALUE_FLAG){ valueTables[j*functionCount+i]=Real( function(x));} if(flags & D_VALUE_FLAG){dValueTables[j*functionCount+i]=Real(dFunction(x));} } diff --git a/surface/include/pcl/surface/impl/concave_hull.hpp b/surface/include/pcl/surface/impl/concave_hull.hpp index bb807abf65b..346daad24b6 100644 --- a/surface/include/pcl/surface/impl/concave_hull.hpp +++ b/surface/include/pcl/surface/impl/concave_hull.hpp @@ -249,7 +249,7 @@ pcl::ConcaveHull::performReconstruction (PointCloud &alpha_shape, std: int max_vertex_id = 0; FORALLvertices { - if (vertex->id + 1 > unsigned (max_vertex_id)) + if (vertex->id + 1 > static_cast(max_vertex_id)) max_vertex_id = vertex->id + 1; } diff --git a/surface/include/pcl/surface/impl/marching_cubes.hpp b/surface/include/pcl/surface/impl/marching_cubes.hpp index 84f9304cc4e..a70f16c5c20 100644 --- a/surface/include/pcl/surface/impl/marching_cubes.hpp +++ b/surface/include/pcl/surface/impl/marching_cubes.hpp @@ -243,9 +243,9 @@ pcl::MarchingCubes::performReconstruction (pcl::PointCloud &po voxelizeData (); // preallocate memory assuming a hull. suppose 6 point per voxel - double size_reserve = std::min((double) intermediate_cloud.points.max_size (), - 2.0 * 6.0 * (double) (res_y_*res_z_ + res_x_*res_z_ + res_x_*res_y_)); - intermediate_cloud.reserve ((std::size_t) size_reserve); + double size_reserve = std::min(static_cast(intermediate_cloud.points.max_size ()), + 2.0 * 6.0 * static_cast(res_y_*res_z_ + res_x_*res_z_ + res_x_*res_y_)); + intermediate_cloud.reserve (static_cast(size_reserve)); for (int x = 1; x < res_x_-1; ++x) for (int y = 1; y < res_y_-1; ++y) diff --git a/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp b/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp index 89692b521a3..3c8529c978c 100644 --- a/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp +++ b/surface/include/pcl/surface/impl/marching_cubes_rbf.hpp @@ -99,7 +99,7 @@ pcl::MarchingCubesRBF::voxelizeData () c_it != centers.end (); ++c_it, ++w_it) f += *w_it * kernel (*c_it, point); - grid_[x * res_y_*res_z_ + y * res_z_ + z] = float (f); + grid_[x * res_y_*res_z_ + y * res_z_ + z] = static_cast(f); } } diff --git a/surface/include/pcl/surface/impl/poisson.hpp b/surface/include/pcl/surface/impl/poisson.hpp index 46652733359..c020020e636 100644 --- a/surface/include/pcl/surface/impl/poisson.hpp +++ b/surface/include/pcl/surface/impl/poisson.hpp @@ -132,7 +132,7 @@ pcl::Poisson::execute (poisson::CoredVectorMeshData &mesh, kernel_depth_ = depth_ - 2; - tree.setBSplineData (depth_, pcl::poisson::Real (1.0 / (1 << depth_)), true); + tree.setBSplineData (depth_, static_cast(1.0 / (1 << depth_)), true); tree.maxMemoryUsage = 0; @@ -202,16 +202,16 @@ pcl::Poisson::performReconstruction (PolygonMesh &output) // Write output PolygonMesh pcl::PointCloud cloud; - cloud.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); + cloud.resize (static_cast(mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); poisson::Point3D p; - for (int i = 0; i < int (mesh.inCorePoints.size ()); i++) + for (int i = 0; i < static_cast(mesh.inCorePoints.size ()); i++) { p = mesh.inCorePoints[i]; cloud[i].x = p.coords[0]*scale+center.coords[0]; cloud[i].y = p.coords[1]*scale+center.coords[1]; cloud[i].z = p.coords[2]*scale+center.coords[2]; } - for (int i = int (mesh.inCorePoints.size ()); i < int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ()); i++) + for (int i = static_cast(mesh.inCorePoints.size ()); i < static_cast(mesh.outOfCorePointCount () + mesh.inCorePoints.size ()); i++) { mesh.nextOutOfCorePoint (p); cloud[i].x = p.coords[0]*scale+center.coords[0]; @@ -233,7 +233,7 @@ pcl::Poisson::performReconstruction (PolygonMesh &output) if (polygon[i].inCore ) v.vertices[i] = polygon[i].idx; else - v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ()); + v.vertices[i] = polygon[i].idx + static_cast(mesh.inCorePoints.size ()); output.polygons[p_i] = v; } @@ -283,16 +283,16 @@ pcl::Poisson::performReconstruction (pcl::PointCloud &points, // Write output PolygonMesh // Write vertices - points.resize (int (mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); + points.resize (static_cast(mesh.outOfCorePointCount () + mesh.inCorePoints.size ())); poisson::Point3D p; - for (int i = 0; i < int(mesh.inCorePoints.size ()); i++) + for (int i = 0; i < static_cast(mesh.inCorePoints.size ()); i++) { p = mesh.inCorePoints[i]; points[i].x = p.coords[0]*scale+center.coords[0]; points[i].y = p.coords[1]*scale+center.coords[1]; points[i].z = p.coords[2]*scale+center.coords[2]; } - for (int i = int(mesh.inCorePoints.size()); i < int (mesh.outOfCorePointCount() + mesh.inCorePoints.size ()); i++) + for (int i = static_cast(mesh.inCorePoints.size()); i < static_cast(mesh.outOfCorePointCount() + mesh.inCorePoints.size ()); i++) { mesh.nextOutOfCorePoint (p); points[i].x = p.coords[0]*scale+center.coords[0]; @@ -314,7 +314,7 @@ pcl::Poisson::performReconstruction (pcl::PointCloud &points, if (polygon[i].inCore ) v.vertices[i] = polygon[i].idx; else - v.vertices[i] = polygon[i].idx + int (mesh.inCorePoints.size ()); + v.vertices[i] = polygon[i].idx + static_cast(mesh.inCorePoints.size ()); polygons[p_i] = v; } diff --git a/surface/src/3rdparty/poisson4/bspline_data.cpp b/surface/src/3rdparty/poisson4/bspline_data.cpp index 7c19a76c7e8..922d5a39638 100644 --- a/surface/src/3rdparty/poisson4/bspline_data.cpp +++ b/surface/src/3rdparty/poisson4/bspline_data.cpp @@ -44,7 +44,7 @@ BSplineElements<1>::upSample(BSplineElements<1>& high) const { high.resize(size() * 2); high.assign(high.size(), BSplineElementCoefficients<1>()); - for (int i = 0; i < int(size()); i++) { + for (int i = 0; i < static_cast(size()); i++) { high[2 * i + 0][0] += 1 * (*this)[i][0]; high[2 * i + 0][1] += 0 * (*this)[i][0]; high[2 * i + 1][0] += 2 * (*this)[i][0]; @@ -71,7 +71,7 @@ BSplineElements<2>::upSample(BSplineElements<2>& high) const high.resize(size() * 2); high.assign(high.size(), BSplineElementCoefficients<2>()); - for (int i = 0; i < int(size()); i++) { + for (int i = 0; i < static_cast(size()); i++) { high[2 * i + 0][0] += 1 * (*this)[i][0]; high[2 * i + 0][1] += 0 * (*this)[i][0]; high[2 * i + 0][2] += 0 * (*this)[i][0]; diff --git a/surface/src/3rdparty/poisson4/geometry.cpp b/surface/src/3rdparty/poisson4/geometry.cpp index 75c97caf233..dda5573fc78 100644 --- a/surface/src/3rdparty/poisson4/geometry.cpp +++ b/surface/src/3rdparty/poisson4/geometry.cpp @@ -45,19 +45,19 @@ namespace pcl void CoredVectorMeshData::resetIterator ( ) { oocPointIndex = polygonIndex = 0; } int CoredVectorMeshData::addOutOfCorePoint(const Point3D& p){ oocPoints.push_back(p); - return int(oocPoints.size())-1; + return static_cast(oocPoints.size())-1; } int CoredVectorMeshData::addPolygon( const std::vector< CoredVertexIndex >& vertices ) { std::vector< int > polygon( vertices.size() ); - for( int i=0 ; i(vertices.size()) ; i++ ) if( vertices[i].inCore ) polygon[i] = vertices[i].idx; else polygon[i] = -vertices[i].idx-1; polygons.push_back( polygon ); - return int( polygons.size() )-1; + return static_cast( polygons.size() )-1; } int CoredVectorMeshData::nextOutOfCorePoint(Point3D& p){ - if(oocPointIndex(oocPoints.size())){ p=oocPoints[oocPointIndex++]; return 1; } @@ -65,19 +65,19 @@ namespace pcl } int CoredVectorMeshData::nextPolygon( std::vector< CoredVertexIndex >& vertices ) { - if( polygonIndex( polygons.size() ) ) { std::vector< int >& polygon = polygons[ polygonIndex++ ]; vertices.resize( polygon.size() ); - for( int i=0 ; i(polygon.size()) ; i++ ) if( polygon[i]<0 ) vertices[i].idx = -polygon[i]-1 , vertices[i].inCore = false; else vertices[i].idx = polygon[i] , vertices[i].inCore = true; return 1; } else return 0; } - int CoredVectorMeshData::outOfCorePointCount(){return int(oocPoints.size());} - int CoredVectorMeshData::polygonCount( ) { return int( polygons.size() ); } + int CoredVectorMeshData::outOfCorePointCount(){return static_cast(oocPoints.size());} + int CoredVectorMeshData::polygonCount( ) { return static_cast( polygons.size() ); } ///////////////////////// // CoredVectorMeshData // @@ -87,20 +87,20 @@ namespace pcl int CoredVectorMeshData2::addOutOfCorePoint( const CoredMeshData2::Vertex& v ) { oocPoints.push_back( v ); - return int(oocPoints.size())-1; + return static_cast(oocPoints.size())-1; } int CoredVectorMeshData2::addPolygon( const std::vector< CoredVertexIndex >& vertices ) { std::vector< int > polygon( vertices.size() ); - for( int i=0 ; i(vertices.size()) ; i++ ) if( vertices[i].inCore ) polygon[i] = vertices[i].idx; else polygon[i] = -vertices[i].idx-1; polygons.push_back( polygon ); - return int( polygons.size() )-1; + return static_cast( polygons.size() )-1; } int CoredVectorMeshData2::nextOutOfCorePoint( CoredMeshData2::Vertex& v ) { - if(oocPointIndex(oocPoints.size())) { v = oocPoints[oocPointIndex++]; return 1; @@ -109,19 +109,19 @@ namespace pcl } int CoredVectorMeshData2::nextPolygon( std::vector< CoredVertexIndex >& vertices ) { - if( polygonIndex( polygons.size() ) ) { std::vector< int >& polygon = polygons[ polygonIndex++ ]; vertices.resize( polygon.size() ); - for( int i=0 ; i(polygon.size()) ; i++ ) if( polygon[i]<0 ) vertices[i].idx = -polygon[i]-1 , vertices[i].inCore = false; else vertices[i].idx = polygon[i] , vertices[i].inCore = true; return 1; } else return 0; } - int CoredVectorMeshData2::outOfCorePointCount(){return int(oocPoints.size());} - int CoredVectorMeshData2::polygonCount( ) { return int( polygons.size() ); } + int CoredVectorMeshData2::outOfCorePointCount(){return static_cast(oocPoints.size());} + int CoredVectorMeshData2::polygonCount( ) { return static_cast( polygons.size() ); } } } diff --git a/test/common/test_eigen.cpp b/test/common/test_eigen.cpp index fb53febb1ee..6bcc4ae1ae8 100644 --- a/test/common/test_eigen.cpp +++ b/test/common/test_eigen.cpp @@ -72,7 +72,7 @@ TEST (PCL, InverseGeneral3x3f) for (unsigned idx = 0; idx < iterations; ++idx) { for (unsigned elIdx = 0; elIdx < 9; ++elIdx) - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); c_matrix = r_matrix; @@ -132,7 +132,7 @@ TEST (PCL, InverseGeneral3x3d) { for (unsigned elIdx = 0; elIdx < 9; ++elIdx) { - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); } c_matrix = r_matrix; // test row-major -> row-major @@ -190,7 +190,7 @@ TEST (PCL, InverseSymmetric3x3f) for (unsigned idx = 0; idx < iterations; ++idx) { for (unsigned elIdx = 0; elIdx < 9; ++elIdx) - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); r_matrix.coeffRef (3) = r_matrix.coeffRef (1); r_matrix.coeffRef (6) = r_matrix.coeffRef (2); @@ -255,7 +255,7 @@ TEST (PCL, InverseSymmetric3x3d) for (unsigned idx = 0; idx < iterations; ++idx) { for (unsigned elIdx = 0; elIdx < 9; ++elIdx) - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); r_matrix.coeffRef (3) = r_matrix.coeffRef (1); r_matrix.coeffRef (6) = r_matrix.coeffRef (2); @@ -321,7 +321,7 @@ TEST (PCL, Inverse2x2f) for (unsigned idx = 0; idx < iterations; ++idx) { for (unsigned elIdx = 0; elIdx < 4; ++elIdx) - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); c_matrix = r_matrix; // test row-major -> row-major @@ -379,7 +379,7 @@ TEST (PCL, Inverse2x2d) for (unsigned idx = 0; idx < iterations; ++idx) { for (unsigned elIdx = 0; elIdx < 4; ++elIdx) - r_matrix.coeffRef (elIdx) = Scalar(rand_double (rng)); + r_matrix.coeffRef (elIdx) = static_cast(rand_double (rng)); c_matrix = r_matrix; // test row-major -> row-major @@ -425,8 +425,8 @@ inline void generateSymPosMatrix2x2 (Matrix& matrix) unsigned test_case = rand_uint (rng) % 10; - Scalar val1 = Scalar (rand_double (rng)); - Scalar val2 = Scalar (rand_double (rng)); + Scalar val1 = static_cast (rand_double (rng)); + Scalar val2 = static_cast (rand_double (rng)); // 10% of test cases include equal eigenvalues if (test_case == 0) @@ -446,8 +446,8 @@ inline void generateSymPosMatrix2x2 (Matrix& matrix) { do { - eigenvectors.col (0)[0] = Scalar (rand_double (rng)); - eigenvectors.col (0)[1] = Scalar (rand_double (rng)); + eigenvectors.col (0)[0] = static_cast (rand_double (rng)); + eigenvectors.col (0)[1] = static_cast (rand_double (rng)); sqrNorm = eigenvectors.col (0).squaredNorm (); } while (sqrNorm == 0); eigenvectors.col (0) /= sqrt (sqrNorm); @@ -592,9 +592,9 @@ inline void generateSymPosMatrix3x3 (Matrix& matrix) unsigned test_case = rand_uint (rng); - Scalar val1 = Scalar (rand_double (rng)); - Scalar val2 = Scalar (rand_double (rng)); - Scalar val3 = Scalar (rand_double (rng)); + Scalar val1 = static_cast (rand_double (rng)); + Scalar val2 = static_cast (rand_double (rng)); + Scalar val3 = static_cast (rand_double (rng)); // 1%: all three values are equal and non-zero if (test_case == 0) @@ -635,12 +635,12 @@ inline void generateSymPosMatrix3x3 (Matrix& matrix) do { - eigenvectors.col (0)[0] = Scalar (rand_double (rng)); - eigenvectors.col (0)[1] = Scalar (rand_double (rng)); - eigenvectors.col (0)[2] = Scalar (rand_double (rng)); - eigenvectors.col (1)[0] = Scalar (rand_double (rng)); - eigenvectors.col (1)[1] = Scalar (rand_double (rng)); - eigenvectors.col (1)[2] = Scalar (rand_double (rng)); + eigenvectors.col (0)[0] = static_cast (rand_double (rng)); + eigenvectors.col (0)[1] = static_cast (rand_double (rng)); + eigenvectors.col (0)[2] = static_cast (rand_double (rng)); + eigenvectors.col (1)[0] = static_cast (rand_double (rng)); + eigenvectors.col (1)[1] = static_cast (rand_double (rng)); + eigenvectors.col (1)[2] = static_cast (rand_double (rng)); eigenvectors.col (2) = eigenvectors.col (0).cross (eigenvectors.col (1)); sqrNorm = eigenvectors.col (2).squaredNorm (); @@ -828,8 +828,8 @@ TEST (PCL, transformLine) // Simple rotation transformation = Eigen::Affine3f::Identity (); transformationd = Eigen::Affine3d::Identity (); - transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ()); - transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ()); + transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ())); + transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ())); line << 1, 2, 3, 0, 1, 0; lined << 1, 2, 3, 0, 1, 0; @@ -849,9 +849,9 @@ TEST (PCL, transformLine) transformationd = Eigen::Affine3d::Identity (); transformation.translation() << 25.97, -2.45, 0.48941; transformationd.translation() << 25.97, -2.45, 0.48941; - transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/5, Eigen::Vector3f::UnitX()) + transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/5, Eigen::Vector3f::UnitX())) * Eigen::AngleAxisf(M_PI/3, Eigen::Vector3f::UnitY()); - transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/5, Eigen::Vector3d::UnitX()) + transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/5, Eigen::Vector3d::UnitX())) * Eigen::AngleAxisd(M_PI/3, Eigen::Vector3d::UnitY()); line << -1, 9, 3, 1.5, 2.0, 0.2; @@ -901,8 +901,8 @@ TEST (PCL, transformPlane) // Simple rotation transformation.translation() << 0, 0, 0; transformationd.translation() << 0, 0, 0; - transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ()); - transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ()); + transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/2, Eigen::Vector3f::UnitZ())); + transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/2, Eigen::Vector3d::UnitZ())); test << 0, 1, 0, -2; tolerance = 1e-6; @@ -925,9 +925,9 @@ TEST (PCL, transformPlane) // Random transformation transformation.translation() << 12.5, -5.4, 0.1; transformationd.translation() << 12.5, -5.4, 0.1; - transformation.linear() = (Eigen::Matrix3f) Eigen::AngleAxisf(M_PI/7, Eigen::Vector3f::UnitY()) + transformation.linear() = Eigen::Matrix3f(Eigen::AngleAxisf(M_PI/7, Eigen::Vector3f::UnitY())) * Eigen::AngleAxisf(M_PI/4, Eigen::Vector3f::UnitZ()); - transformationd.linear() = (Eigen::Matrix3d) Eigen::AngleAxisd(M_PI/7, Eigen::Vector3d::UnitY()) + transformationd.linear() = Eigen::Matrix3d(Eigen::AngleAxisd(M_PI/7, Eigen::Vector3d::UnitY())) * Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitZ()); test << 5.35315, 2.89914, 0.196848, -49.2788; test /= test.head<3> ().norm (); diff --git a/test/common/test_io.cpp b/test/common/test_io.cpp index efdc8245b7b..0cb75d1884b 100644 --- a/test/common/test_io.cpp +++ b/test/common/test_io.cpp @@ -153,12 +153,12 @@ TEST (PCL, concatenatePointCloud2) 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) + for (int i = 0; i < static_cast(cloud_xyz_rgba.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]); } - for (int i = 0; i < int (cloud_xyz_rgba2.size ()); ++i) + for (int i = 0; i < static_cast(cloud_xyz_rgba2.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]); EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgba2[i]); @@ -175,12 +175,12 @@ TEST (PCL, concatenatePointCloud2) 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) + for (int i = 0; i < static_cast(cloud_xyz_rgba.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]); } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) + for (int i = 0; i < static_cast(cloud_xyz_rgb.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); @@ -209,13 +209,13 @@ TEST (PCL, concatenatePointCloud2) pcl::fromPCLPointCloud2 (cloud_out3, cloud_all); EXPECT_EQ (cloud_all.size (), cloud_xyz_rgba.size () + cloud_xyz_rgb.size ()); - for (int i = 0; i < int (cloud_xyz_rgba.size ()); ++i) + for (int i = 0; i < static_cast(cloud_xyz_rgba.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[i], cloud_xyz_rgba[i]); // Data doesn't get modified EXPECT_RGBA_EQ (cloud_all[i], cloud_xyz_rgba[i]); } - for (int i = 0; i < int (cloud_xyz_rgb.size ()); ++i) + for (int i = 0; i < static_cast(cloud_xyz_rgb.size ()); ++i) { EXPECT_XYZ_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); EXPECT_RGBA_EQ (cloud_all[cloud_xyz_rgba.size () + i], cloud_xyz_rgb[i]); diff --git a/test/features/test_boundary_estimation.cpp b/test/features/test_boundary_estimation.cpp index ea23214a76a..d0717a2c6e6 100644 --- a/test/features/test_boundary_estimation.cpp +++ b/test/features/test_boundary_estimation.cpp @@ -86,23 +86,23 @@ TEST (PCL, BoundaryEstimation) // isBoundaryPoint (indices) bool pt = false; - pt = b.isBoundaryPoint (cloud, 0, indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, 0, indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) / 3, indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) / 3, indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) / 2, indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) / 2, indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) - 1, indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, static_cast (indices.size ()) - 1, indices, u, v, static_cast(M_PI) / 2.0); EXPECT_TRUE (pt); // isBoundaryPoint (points) - pt = b.isBoundaryPoint (cloud, cloud[0], indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, cloud[0], indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 3], indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 3], indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 2], indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, cloud[indices.size () / 2], indices, u, v, static_cast(M_PI) / 2.0); EXPECT_FALSE (pt); - pt = b.isBoundaryPoint (cloud, cloud[indices.size () - 1], indices, u, v, float (M_PI) / 2.0); + pt = b.isBoundaryPoint (cloud, cloud[indices.size () - 1], indices, u, v, static_cast(M_PI) / 2.0); EXPECT_TRUE (pt); // Object diff --git a/test/features/test_brisk.cpp b/test/features/test_brisk.cpp index 93bb31ea55d..c4405f17257 100644 --- a/test/features/test_brisk.cpp +++ b/test/features/test_brisk.cpp @@ -70,8 +70,8 @@ TEST (PCL, BRISK_2D) //io::savePCDFileBinary ("brisk_keypoints.pcd", *cloud_keypoints); - const int num_of_keypoints = int (cloud_keypoints->size ()); - const int num_of_keypoints_gt = int (cloud_keypoints_gt->size ()); + const int num_of_keypoints = static_cast(cloud_keypoints->size ()); + const int num_of_keypoints_gt = static_cast(cloud_keypoints_gt->size ()); EXPECT_EQ (num_of_keypoints_gt, num_of_keypoints); @@ -96,8 +96,8 @@ TEST (PCL, BRISK_2D) cloud_descriptors.reset (new PointCloud); brisk_descriptor_estimation.compute (*cloud_descriptors); - const int num_of_descriptors = int (cloud_descriptors->size ()); - const int num_of_descriptors_gt = int (cloud_descriptors_gt->size ()); + const int num_of_descriptors = static_cast(cloud_descriptors->size ()); + const int num_of_descriptors_gt = static_cast(cloud_descriptors_gt->size ()); EXPECT_EQ (num_of_descriptors_gt, num_of_descriptors); @@ -111,7 +111,7 @@ TEST (PCL, BRISK_2D) float sqr_dist = 0.0f; for (std::size_t index = 0; index < 33; ++index) { - const float dist = float (descriptor.descriptor[index] - descriptor_gt.descriptor[index]); + const float dist = static_cast(descriptor.descriptor[index] - descriptor_gt.descriptor[index]); sqr_dist += dist * dist; } diff --git a/test/features/test_flare_estimation.cpp b/test/features/test_flare_estimation.cpp index 320cbf4c76c..5a60c2d7a94 100644 --- a/test/features/test_flare_estimation.cpp +++ b/test/features/test_flare_estimation.cpp @@ -165,7 +165,7 @@ main (int argc, char** argv) sampled_cloud.reset (new pcl::PointCloud ()); pcl::Indices sampled_indices; - for (float sa = 0.0f; sa < (float)cloud->size (); sa += sampling_incr) + for (float sa = 0.0f; sa < static_cast(cloud->size ()); sa += sampling_incr) sampled_indices.push_back (static_cast (sa)); copyPointCloud (*cloud, sampled_indices, *sampled_cloud); diff --git a/test/features/test_gasd_estimation.cpp b/test/features/test_gasd_estimation.cpp index 0b000cbcabe..13c1cb77c53 100644 --- a/test/features/test_gasd_estimation.cpp +++ b/test/features/test_gasd_estimation.cpp @@ -114,7 +114,7 @@ TEST (PCL, GASDShapeEstimationNoInterp) 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; EXPECT_EQ (descriptor.size (), 1); - for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i) + for (std::size_t i = 0; i < static_cast(descriptor[0].descriptorSize ()); ++i) { EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5); } @@ -158,7 +158,7 @@ TEST(PCL, GASDShapeEstimationTrilinearInterp) 0, 0, 0, 0, 0, 0, 0, 0}; EXPECT_EQ (descriptor.size (), 1); - for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i) + for (std::size_t i = 0; i < static_cast(descriptor[0].descriptorSize ()); ++i) { EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5); } @@ -217,7 +217,7 @@ TEST (PCL, GASDShapeAndColorEstimationNoInterp) 0, 0, 0, 0, 0, 0, 0, 0}; EXPECT_EQ (descriptor.size (), 1); - for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i) + for (std::size_t i = 0; i < static_cast(descriptor[0].descriptorSize ()); ++i) { EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5); } @@ -304,7 +304,7 @@ TEST(PCL, GASDShapeAndColorEstimationQuadrilinearInterp) 0, 0, 0, 0, 0, 0, 0, 0}; EXPECT_EQ (descriptor.size (), 1); - for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i) + for (std::size_t i = 0; i < static_cast( descriptor[0].descriptorSize ()); ++i) { EXPECT_NEAR (descriptor[0].histogram[i], ref_values[i], 1e-5); } diff --git a/test/features/test_normal_estimation.cpp b/test/features/test_normal_estimation.cpp index 58a5e77f763..d1eb8d5e0aa 100644 --- a/test/features/test_normal_estimation.cpp +++ b/test/features/test_normal_estimation.cpp @@ -430,7 +430,7 @@ TEST (PCL, IntegralImageNormalEstimationIndexingIssue) double y = ypos; double x = xpos; - (*cloudptr)[idx++] = PointXYZ(float(x), float(y), float(z)); + (*cloudptr)[idx++] = PointXYZ(static_cast(x), static_cast(y), static_cast(z)); } } diff --git a/test/features/test_pfh_estimation.cpp b/test/features/test_pfh_estimation.cpp index f63450ab2cb..563f0ddd732 100644 --- a/test/features/test_pfh_estimation.cpp +++ b/test/features/test_pfh_estimation.cpp @@ -507,7 +507,7 @@ TEST (PCL, GFPFH) const float ref_values[] = { 1877, 6375, 5361, 14393, 6674, 2471, 2248, 2753, 3117, 4585, 14388, 32407, 15122, 3061, 3202, 794 }; EXPECT_EQ (descriptor.size (), 1); - for (std::size_t i = 0; i < std::size_t (descriptor[0].descriptorSize ()); ++i) + for (std::size_t i = 0; i < static_cast(descriptor[0].descriptorSize ()); ++i) { EXPECT_EQ (descriptor[0].histogram[i], ref_values[i]); } diff --git a/test/filters/test_clipper.cpp b/test/filters/test_clipper.cpp index 46f82e48e90..58d388f498c 100644 --- a/test/filters/test_clipper.cpp +++ b/test/filters/test_clipper.cpp @@ -95,13 +95,13 @@ TEST (BoxClipper3D, Filters) EXPECT_EQ (int (indices.size ()), 5); // ... then rotate points +45 in Y-Axis - t.rotate (AngleAxisf (45.0f * float (M_PI) / 180.0f, Vector3f::UnitY ())); + t.rotate (AngleAxisf (45.0f * static_cast(M_PI) / 180.0f, Vector3f::UnitY ())); boxClipper3D.setTransformation (t); boxClipper3D.clipPointCloud3D (*input, indices); EXPECT_EQ (int (indices.size ()), 1); // ... then rotate points -45 in Z-axis - t.rotate (AngleAxisf (-45.0f * float (M_PI) / 180.0f, Vector3f::UnitZ ())); + t.rotate (AngleAxisf (-45.0f * static_cast(M_PI) / 180.0f, Vector3f::UnitZ ())); boxClipper3D.setTransformation (t); boxClipper3D.clipPointCloud3D (*input, indices); EXPECT_EQ (int (indices.size ()), 3); @@ -210,7 +210,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Rotate crop box up by 45 - cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f)); + cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast(M_PI) / 180.0f, 0.0f)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -234,7 +234,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Rotate point cloud by -45 - cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f)); + cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast(M_PI) / 180.0f)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -258,7 +258,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Translate point cloud down by -1 - cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0)); + cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast(M_PI) / 180.0)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -366,7 +366,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Rotate crop box up by 45 - cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f)); + cropBoxFilter.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast(M_PI) / 180.0f, 0.0f)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -391,7 +391,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Rotate point cloud by -45 - cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f)); + cropBoxFilter.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast(M_PI) / 180.0f)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -418,7 +418,7 @@ TEST (CropBox, Filters) cropBoxFilter.filter (cloud_out); // Translate point cloud down by -1 - cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0)); + cropBoxFilter.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast(M_PI) / 180.0)); cropBoxFilter.filter (indices); cropBoxFilter.filter (cloud_out); @@ -533,7 +533,7 @@ TEST (CropBox, Filters) cropBoxFilter2.filter (cloud_out2); // Rotate crop box up by 45 - cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f)); + cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast(M_PI) / 180.0f, 0.0f)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); @@ -541,7 +541,7 @@ TEST (CropBox, Filters) EXPECT_EQ (int (indices2.size ()), int (cloud_out2.width * cloud_out2.height)); // Rotate point cloud by -45 - cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f)); + cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast(M_PI) / 180.0f)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); @@ -563,7 +563,7 @@ TEST (CropBox, Filters) cropBoxFilter2.filter (cloud_out2); // Translate point cloud down by -1 - cropBoxFilter2.setTransform (getTransformation (0.0f, -1.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f)); + cropBoxFilter2.setTransform (getTransformation (0.0f, -1.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast(M_PI) / 180.0f)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); @@ -669,7 +669,7 @@ TEST (CropBox, Filters) cropBoxFilter2.filter (cloud_out2); // Rotate crop box up by 45 - cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * float (M_PI) / 180.0f, 0.0f)); + cropBoxFilter2.setRotation (Eigen::Vector3f (0.0f, 45.0f * static_cast(M_PI) / 180.0f, 0.0f)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); @@ -694,7 +694,7 @@ TEST (CropBox, Filters) cropBoxFilter2.filter (cloud_out2); // Rotate point cloud by -45 - cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * float (M_PI) / 180.0f)); + cropBoxFilter2.setTransform (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, -45.0f * static_cast(M_PI) / 180.0f)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); @@ -720,7 +720,7 @@ TEST (CropBox, Filters) cropBoxFilter2.filter (cloud_out2); // Translate point cloud down by -1 - cropBoxFilter2.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * float (M_PI) / 180.0)); + cropBoxFilter2.setTransform (getTransformation(0, -1, 0, 0, 0, -45.0 * static_cast(M_PI) / 180.0)); cropBoxFilter2.filter (indices2); cropBoxFilter2.filter (cloud_out2); diff --git a/test/filters/test_convolution.cpp b/test/filters/test_convolution.cpp index 2bae7ae0bd4..cd9a1d7f798 100644 --- a/test/filters/test_convolution.cpp +++ b/test/filters/test_convolution.cpp @@ -193,10 +193,10 @@ TEST (Convolution, convolveRowsRGB) for (std::uint32_t r = 0; r < input->height; r++) for (std::uint32_t c = 0; c < input->width; c++) { - float x1 = -2.0f + (4.0f / (float)input->width) * (float)c; - float y1 = -2.0f + (4.0f / (float)input->height) * (float)r; - float x2 = -M_PI + (2.0f * M_PI / (float)input->width) * (float)c; - float y2 = -2.0f + (4.0f / (float)input->height) * (float)r; + float x1 = -2.0f + (4.0f / static_cast(input->width)) * static_cast(c); + float y1 = -2.0f + (4.0f / static_cast(input->height)) * static_cast(r); + float x2 = -M_PI + (2.0f * M_PI / static_cast(input->width)) * static_cast(c); + float y2 = -2.0f + (4.0f / static_cast(input->height)) * static_cast(r); float z = x1 * std::exp(-(x1 * x1 + y1 * y1)) * 2.5f + std::sin(x2) * std::sin(y2); (*input) (c, r) = interpolate_color(-1.6f, 1.6f, z); } @@ -302,18 +302,18 @@ TEST (Convolution, convolveRowsXYZRGB) for (std::uint32_t r = 0; r < input->height; r++) for (std::uint32_t c = 0; c < input->width; c++) { - float x1 = -2.0f + (4.0f / (float)input->width) * (float)c; - float y1 = -2.0f + (4.0f / (float)input->height) * (float)r; - float x2 = -M_PI + (2.0f * M_PI / (float)input->width) * (float)c; - float y2 = -2.0f + (4.0f / (float)input->height) * (float)r; + float x1 = -2.0f + (4.0f / static_cast(input->width)) * static_cast(c); + float y1 = -2.0f + (4.0f / static_cast(input->height)) * static_cast(r); + float x2 = -M_PI + (2.0f * M_PI / static_cast(input->width)) * static_cast(c); + float y2 = -2.0f + (4.0f / static_cast(input->height)) * static_cast(r); float z = x1 * std::exp(-(x1 * x1 + y1 * y1)) * 2.5f + std::sin(x2) * std::sin(y2); RGB color = interpolate_color(-1.6f, 1.6f, z); (*input) (c, r).x = x1; (*input) (c, r).y = y1; (*input) (c, r).z = z; - (*input) (c, r).r = (uint8_t)(255.0f * color.r); - (*input) (c, r).g = (uint8_t)(255.0f * color.g); - (*input) (c, r).b = (uint8_t)(255.0f * color.b); + (*input) (c, r).r = static_cast(255.0f * color.r); + (*input) (c, r).g = static_cast(255.0f * color.g); + (*input) (c, r).b = static_cast(255.0f * color.b); } // filter diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index 15fdea56ddb..2cc5b88361e 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -1972,9 +1972,9 @@ TEST (FrustumCulling, Filters) for (int k = 0; k < 5; k++) { pcl::PointXYZ pt; - pt.x = float (i); - pt.y = float (j); - pt.z = float (k); + pt.x = static_cast(i); + pt.y = static_cast(j); + pt.z = static_cast(k); input->push_back (pt); } } @@ -2126,7 +2126,7 @@ TEST (ConditionalRemovalTfQuadraticXYZComparison, Filters) EXPECT_EQ ((*input)[9].z, output[9].z); // rotate cylinder comparison along z-axis by PI/2 - cyl_comp->transformComparison (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, float (M_PI) / 2.0f).inverse ()); + cyl_comp->transformComparison (getTransformation (0.0f, 0.0f, 0.0f, 0.0f, 0.0f, static_cast(M_PI) / 2.0f).inverse ()); condrem.filter (output); diff --git a/test/geometry/test_iterator.cpp b/test/geometry/test_iterator.cpp index 4e8eda16ed8..df91318689e 100644 --- a/test/geometry/test_iterator.cpp +++ b/test/geometry/test_iterator.cpp @@ -51,8 +51,8 @@ void checkSimpleLine8 (unsigned x_start, unsigned y_start, unsigned x_end, unsig for (unsigned xIdx = 0; xIdx < cloud.width; ++xIdx) { PointT& point = cloud.points [yIdx * cloud.width + xIdx]; - point.x = float(xIdx); - point.y = float(yIdx); + point.x = static_cast(xIdx); + point.y = static_cast(yIdx); point.z = 0.0f; } } @@ -132,8 +132,8 @@ void checkGeneralLine (unsigned x_start, unsigned y_start, unsigned x_end, unsig for (unsigned xIdx = 0; xIdx < cloud.width; ++xIdx) { PointT& point = cloud.points [yIdx * cloud.width + xIdx]; - point.x = float(xIdx); - point.y = float(yIdx); + point.x = static_cast(xIdx); + point.y = static_cast(yIdx); point.z = 0.0f; } } @@ -168,27 +168,27 @@ void checkGeneralLine (unsigned x_start, unsigned y_start, unsigned x_end, unsig else EXPECT_EQ (std::abs(dx) + std::abs(dy), idx); - float length = std::sqrt (float (dx * dx + dy * dy)); - float dir_x = float (dx) / length; - float dir_y = float (dy) / length; + float length = std::sqrt (static_cast(dx * dx + dy * dy)); + float dir_x = static_cast(dx) / length; + float dir_y = static_cast(dy) / length; // now all z-values should be 0 again! - for (int yIdx = 0; yIdx < int(cloud.height); ++yIdx) + for (int yIdx = 0; yIdx < static_cast(cloud.height); ++yIdx) { - for (int xIdx = 0; xIdx < int(cloud.width); ++xIdx) + for (int xIdx = 0; xIdx < static_cast(cloud.width); ++xIdx) { PointT& point = cloud.points [yIdx * cloud.width + xIdx]; if (point.z != 0) { // point need to be close to line - float distance = dir_x * float(yIdx - int(y_start)) - dir_y * float(xIdx - int(x_start)); + float distance = dir_x * static_cast(yIdx - static_cast(y_start)) - dir_y * static_cast(xIdx - static_cast(x_start)); if (neighorhood) EXPECT_LE (std::fabs(distance), 0.5f); else EXPECT_LE (std::fabs(distance), 0.70711f); // and within the endpoints - float lambda = dir_y * float(yIdx - int(y_start)) + dir_x * float(xIdx - int(x_start)); + float lambda = dir_y * static_cast(yIdx - static_cast(y_start)) + dir_x * static_cast(xIdx - static_cast(x_start)); EXPECT_LE (lambda, length); EXPECT_GE (lambda, 0.0f); } @@ -246,11 +246,11 @@ TEST (PCL, LineIterator8NeighborsGeneral) unsigned length = 45; constexpr unsigned angular_resolution = 180; - constexpr float d_alpha = float(M_PI / angular_resolution); + constexpr float d_alpha = static_cast(M_PI / angular_resolution); for (unsigned idx = 0; idx < angular_resolution; ++idx) { - auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5); - auto y_end = unsigned (length * std::sin (float(idx) * d_alpha) + center_y + 0.5); + auto x_end = static_cast(length * std::cos (static_cast(idx) * d_alpha) + center_x + 0.5); + auto y_end = static_cast(length * std::sin (static_cast(idx) * d_alpha) + center_y + 0.5); // right checkGeneralLine (center_x, center_y, x_end, y_end, cloud, true); @@ -270,11 +270,11 @@ TEST (PCL, LineIterator4NeighborsGeneral) unsigned length = 45; constexpr unsigned angular_resolution = 360; - constexpr float d_alpha = float(2.0 * M_PI / angular_resolution); + constexpr float d_alpha = static_cast(2.0 * M_PI / angular_resolution); for (unsigned idx = 0; idx < angular_resolution; ++idx) { - auto x_end = unsigned (length * std::cos (float(idx) * d_alpha) + center_x + 0.5); - auto y_end = unsigned (length * std::sin (float(idx) * d_alpha) + center_y + 0.5); + auto x_end = static_cast(length * std::cos (static_cast(idx) * d_alpha) + center_x + 0.5); + auto y_end = static_cast(length * std::sin (static_cast(idx) * d_alpha) + center_y + 0.5); // right checkGeneralLine (center_x, center_y, x_end, y_end, cloud, false); diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 1809f2c1835..a73f4583a7a 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -94,7 +94,7 @@ TYPED_TEST (OctreeDeCompressionTest, RandomClouds) 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_encoder(static_cast(compression_profile), false); pcl::io::OctreePointCloudCompression pointcloud_decoder; typename pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); // iterate over runs @@ -130,7 +130,7 @@ TEST (PCL, OctreeDeCompressionRandomPointXYZRGBASameCloud) 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_encoder(static_cast(compression_profile), false); pcl::io::OctreePointCloudCompression pointcloud_decoder; auto cloud = generateRandomCloud(MAX_XYZ); @@ -173,7 +173,7 @@ TEST(PCL, OctreeDeCompressionFile) 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((pcl::io::compression_Profiles_e) compression_profile, false); + pcl::io::OctreePointCloudCompression PointCloudEncoder(static_cast(compression_profile), false); pcl::io::OctreePointCloudCompression PointCloudDecoder; // iterate over various voxel sizes diff --git a/test/io/test_ply_io.cpp b/test/io/test_ply_io.cpp index 40bb4f2a0ab..89065bf9b2a 100644 --- a/test/io/test_ply_io.cpp +++ b/test/io/test_ply_io.cpp @@ -160,25 +160,25 @@ struct PLYColorTest : public PLYTest "property list uchar int vertex_indices\n" "end_header\n" "4.23607 0 1.61803 " - << unsigned (clr_1_.r) << ' ' - << unsigned (clr_1_.g) << ' ' - << unsigned (clr_1_.b) << ' ' - << unsigned (clr_1_.a) << "\n" + << static_cast(clr_1_.r) << ' ' + << static_cast(clr_1_.g) << ' ' + << static_cast(clr_1_.b) << ' ' + << static_cast(clr_1_.a) << "\n" "2.61803 2.61803 2.61803 " - << unsigned (clr_2_.r) << ' ' - << unsigned (clr_2_.g) << ' ' - << unsigned (clr_2_.b) << ' ' - << unsigned (clr_2_.a) << "\n" + << static_cast(clr_2_.r) << ' ' + << static_cast(clr_2_.g) << ' ' + << static_cast(clr_2_.b) << ' ' + << static_cast(clr_2_.a) << "\n" "0 1.61803 4.23607 " - << unsigned (clr_3_.r) << ' ' - << unsigned (clr_3_.g) << ' ' - << unsigned (clr_3_.b) << ' ' - << unsigned (clr_3_.a) << "\n" + << static_cast(clr_3_.r) << ' ' + << static_cast(clr_3_.g) << ' ' + << static_cast(clr_3_.b) << ' ' + << static_cast(clr_3_.a) << "\n" "0 -1.61803 4.23607 " - << unsigned (clr_4_.r) << ' ' - << unsigned (clr_4_.g) << ' ' - << unsigned (clr_4_.b) << ' ' - << unsigned (clr_4_.a) << "\n" + << static_cast(clr_4_.r) << ' ' + << static_cast(clr_4_.g) << ' ' + << static_cast(clr_4_.b) << ' ' + << static_cast(clr_4_.a) << "\n" "3 0 1 2\n" "3 1 2 3\n"; fs.close (); diff --git a/test/kdtree/test_kdtree.cpp b/test/kdtree/test_kdtree.cpp index 8f6831b5246..a13ac9d7bcf 100644 --- a/test/kdtree/test_kdtree.cpp +++ b/test/kdtree/test_kdtree.cpp @@ -310,7 +310,7 @@ TEST (PCL, KdTreeFLANN_32_vs_64_bit) for (std::size_t vec_i = 0; vec_i < nn_indices_vector.size (); ++vec_i) { char str[512]; - sprintf (str, "point_%d", int (vec_i)); + sprintf (str, "point_%d", static_cast(vec_i)); boost::optional tree = xml_property_tree.get_child_optional (str); if (!tree) FAIL (); @@ -320,7 +320,7 @@ TEST (PCL, KdTreeFLANN_32_vs_64_bit) for (std::size_t n_i = 0; n_i < nn_indices_vector[vec_i].size (); ++n_i) { - sprintf (str, "nn_%d", int (n_i)); + sprintf (str, "nn_%d", static_cast(n_i)); int neighbor_index = tree.get ().get (str); EXPECT_EQ (neighbor_index, nn_indices_vector[vec_i][n_i]); } diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index c44e042dff3..07332be6ab1 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -1259,12 +1259,12 @@ struct OctreePointCloudAdjacencyBeginEndIteratorsTest // Generate Point Cloud typename PointCloudT::Ptr cloud (new PointCloudT (100, 1)); - constexpr float max_inv = 1.f / float (RAND_MAX); + constexpr float max_inv = 1.f / static_cast(RAND_MAX); for (std::size_t i = 0; i < 100; ++i) { - const PointT pt (10.f * (float (std::rand ()) * max_inv - .5f), - 10.f * (float (std::rand ()) * max_inv - .5f), - 10.f * (float (std::rand ()) * max_inv - .5f)); + const PointT pt (10.f * (static_cast(std::rand ()) * max_inv - .5f), + 10.f * (static_cast(std::rand ()) * max_inv - .5f), + 10.f * (static_cast(std::rand ()) * max_inv - .5f)); (*cloud)[i] = pt; } @@ -1503,9 +1503,9 @@ struct OctreePointCloudSierpinskiTest for (unsigned int i = 0; i < nb_pt_in_voxel; ++i) { - float x = x_min + (rand () / ((float)(RAND_MAX) + 1)) * (x_max - x_min); - float y = y_min + (rand () / ((float)(RAND_MAX) + 1)) * (y_max - y_min); - float z = z_min + (rand () / ((float)(RAND_MAX) + 1)) * (z_max - z_min); + float x = x_min + (rand () / (static_cast(RAND_MAX) + 1)) * (x_max - x_min); + float y = y_min + (rand () / (static_cast(RAND_MAX) + 1)) * (y_max - y_min); + float z = z_min + (rand () / (static_cast(RAND_MAX) + 1)) * (z_max - z_min); cloud->points.emplace_back(x, y, z); } diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index 8a890212bc0..fe70dfa7e8c 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -920,7 +920,7 @@ TEST_F (OutofcoreTest, PointCloud2_Query) pcl::PCLPointCloud2::Ptr query_result_a (new pcl::PCLPointCloud2 ()); pcl::PCLPointCloud2::Ptr query_result_b (new pcl::PCLPointCloud2 ()); - octreeA.queryBBIncludes (min, max, int (octreeA.getDepth ()), query_result_a); + octreeA.queryBBIncludes (min, max, static_cast(octreeA.getDepth ()), query_result_a); EXPECT_EQ (test_cloud->width*test_cloud->height, query_result_a->width*query_result_a->height) << "PCLPointCloud2 Query number of points returned failed\n"; diff --git a/test/recognition/test_recognition_cg.cpp b/test/recognition/test_recognition_cg.cpp index 7fa655c8b97..c6208b14403 100644 --- a/test/recognition/test_recognition_cg.cpp +++ b/test/recognition/test_recognition_cg.cpp @@ -93,7 +93,7 @@ computeRmsE (const PointCloud::ConstPtr &model, const PointCloud 0) - return sqrt (sqr_norm_sum / double (transformed_model.size ())); + return sqrt (sqr_norm_sum / static_cast(transformed_model.size ())); return std::numeric_limits::max (); } diff --git a/test/registration/test_correspondence_estimation.cpp b/test/registration/test_correspondence_estimation.cpp index 2192f3d78c0..7df7ca6b830 100644 --- a/test/registration/test_correspondence_estimation.cpp +++ b/test/registration/test_correspondence_estimation.cpp @@ -90,8 +90,8 @@ TEST (CorrespondenceEstimation, CorrespondenceEstimationSetSearchMethod) pcl::PointCloud::Ptr cloud2 (new pcl::PointCloud ()); for ( std::size_t i = 0; i < 50; i++ ) { - cloud1->points.emplace_back(float (rand()), float (rand()), float (rand())); - cloud2->points.emplace_back(float (rand()), float (rand()), float (rand())); + cloud1->points.emplace_back(static_cast(rand()), static_cast(rand()), static_cast(rand())); + cloud2->points.emplace_back(static_cast(rand()), static_cast(rand()), static_cast(rand())); } // Build a KdTree for each pcl::search::KdTree::Ptr tree1 (new pcl::search::KdTree ()); diff --git a/test/registration/test_correspondence_rejectors.cpp b/test/registration/test_correspondence_rejectors.cpp index 4a6bc105ee2..0e06cfb869e 100644 --- a/test/registration/test_correspondence_rejectors.cpp +++ b/test/registration/test_correspondence_rejectors.cpp @@ -92,7 +92,7 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly) // Transform the target pcl::PointCloud::Ptr target(new pcl::PointCloud); Eigen::Vector3f t(0.1f, 0.2f, 0.3f); - Eigen::Quaternionf q (float (std::cos (0.5*M_PI_4)), 0.0f, 0.0f, float (std::sin (0.5*M_PI_4))); + Eigen::Quaternionf q (static_cast(std::cos (0.5*M_PI_4)), 0.0f, 0.0f, static_cast(std::sin (0.5*M_PI_4))); pcl::transformPointCloud (*cloud, *target, t, q); // Noisify the target with a known seed and N(0, 0.005) using deterministic sampling @@ -121,8 +121,8 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly) reject.getRemainingCorrespondences (corr, result); // Ground truth fraction of inliers and estimated fraction of inliers - const float ground_truth_frac = float (size-last) / float (size); - const float accepted_frac = float (result.size()) / float (size); + const float ground_truth_frac = static_cast(size-last) / static_cast(size); + const float accepted_frac = static_cast(result.size()) / static_cast(size); /* * Test criterion 1: verify that the method accepts at least 25 % of the input correspondences, @@ -143,8 +143,8 @@ TEST (CorrespondenceRejectors, CorrespondenceRejectionPoly) ++true_positives; const std::size_t false_positives = result.size() - true_positives; - const double precision = double(true_positives) / double(true_positives+false_positives); - const double recall = double(true_positives) / double(size-last); + const double precision = static_cast(true_positives) / static_cast(true_positives+false_positives); + const double recall = static_cast(true_positives) / static_cast(size-last); EXPECT_NEAR(precision, 1.0, 0.4); EXPECT_NEAR(recall, 1.0, 0.2); } diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index cdebf4bc35e..6fa4ad6eb94 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -249,10 +249,10 @@ sampleRandomTransform (Eigen::Affine3f &trans, float max_angle, float max_trans) { srand(0); // Sample random transform - Eigen::Vector3f axis((float)rand() / RAND_MAX, (float)rand() / RAND_MAX, (float)rand() / RAND_MAX); + Eigen::Vector3f axis(static_cast(rand()) / RAND_MAX, static_cast(rand()) / RAND_MAX, static_cast(rand()) / RAND_MAX); axis.normalize(); - float angle = (float)rand() / RAND_MAX * max_angle; - Eigen::Vector3f translation((float)rand() / RAND_MAX, (float)rand() / RAND_MAX, (float)rand() / RAND_MAX); + float angle = static_cast(rand()) / RAND_MAX * max_angle; + Eigen::Vector3f translation(static_cast(rand()) / RAND_MAX, static_cast(rand()) / RAND_MAX, static_cast(rand()) / RAND_MAX); translation *= max_trans; Eigen::Affine3f rotation(Eigen::AngleAxis(angle, axis)); trans = Eigen::Translation3f(translation) * rotation; diff --git a/test/registration/test_registration_api.cpp b/test/registration/test_registration_api.cpp index 5667a8ccdda..1aeebb78918 100644 --- a/test/registration/test_registration_api.cpp +++ b/test/registration/test_registration_api.cpp @@ -88,7 +88,7 @@ TEST (PCL, CorrespondenceEstimation) // check for correct order and number of matches EXPECT_EQ (int (correspondences->size ()), nr_original_correspondences); - if (int (correspondences->size ()) == nr_original_correspondences) + if (static_cast(correspondences->size ()) == nr_original_correspondences) { for (int i = 0; i < nr_original_correspondences; ++i) { @@ -112,7 +112,7 @@ TEST (PCL, CorrespondenceEstimationReciprocal) // check for correct matches and number of matches EXPECT_EQ (int (correspondences->size ()), nr_reciprocal_correspondences); - if (int (correspondences->size ()) == nr_reciprocal_correspondences) + if (static_cast(correspondences->size ()) == nr_reciprocal_correspondences) { for (int i = 0; i < nr_reciprocal_correspondences; ++i) { @@ -143,7 +143,7 @@ TEST (PCL, CorrespondenceRejectorDistance) // check for correct matches and number of matches EXPECT_EQ (int (correspondences_result_rej_dist->size ()), nr_correspondences_result_rej_dist); - if (int (correspondences_result_rej_dist->size ()) == nr_correspondences_result_rej_dist) + if (static_cast(correspondences_result_rej_dist->size ()) == nr_correspondences_result_rej_dist) { for (int i = 0; i < nr_correspondences_result_rej_dist; ++i) { @@ -176,7 +176,7 @@ TEST (PCL, CorrespondenceRejectorMedianDistance) // check for correct matches EXPECT_NEAR (corr_rej_median_dist.getMedianDistance (), rej_median_distance, 1e-4); EXPECT_EQ (int (correspondences_result_rej_median_dist->size ()), nr_correspondences_result_rej_median_dist); - if (int (correspondences_result_rej_median_dist->size ()) == nr_correspondences_result_rej_median_dist) + if (static_cast(correspondences_result_rej_median_dist->size ()) == nr_correspondences_result_rej_median_dist) { for (int i = 0; i < nr_correspondences_result_rej_median_dist; ++i) { @@ -206,7 +206,7 @@ TEST (PCL, CorrespondenceRejectorOneToOne) // check for correct matches and number of matches EXPECT_EQ (int (correspondences_result_rej_one_to_one->size ()), nr_correspondences_result_rej_one_to_one); - if (int (correspondences_result_rej_one_to_one->size ()) == nr_correspondences_result_rej_one_to_one) + if (static_cast(correspondences_result_rej_one_to_one->size ()) == nr_correspondences_result_rej_one_to_one) { for (int i = 0; i < nr_correspondences_result_rej_one_to_one; ++i) { @@ -242,7 +242,7 @@ TEST (PCL, CorrespondenceRejectorSampleConsensus) // check for correct matches and number of matches EXPECT_EQ (int (correspondences_result_rej_sac->size ()), nr_correspondences_result_rej_sac); - if (int (correspondences_result_rej_sac->size ()) == nr_correspondences_result_rej_sac) + if (static_cast(correspondences_result_rej_sac->size ()) == nr_correspondences_result_rej_sac) { for (int i = 0; i < nr_correspondences_result_rej_sac; ++i) { @@ -302,7 +302,7 @@ TEST (PCL, CorrespondenceRejectorSurfaceNormal) corr_rej_surf_norm.getCorrespondences (*correspondences_result_rej_surf_norm); // check for correct matches - if (int (correspondences_result_rej_surf_norm->size ()) == nr_correspondences_result_rej_dist) + if (static_cast(correspondences_result_rej_surf_norm->size ()) == nr_correspondences_result_rej_dist) { for (int i = 0; i < nr_correspondences_result_rej_dist; ++i) { @@ -332,7 +332,7 @@ TEST (PCL, CorrespondenceRejectorTrimmed) // check for correct matches, number of matches, and for sorting (correspondences should be sorted w.r.t. distance) EXPECT_EQ (int (correspondences_result_rej_trimmed->size ()), nr_correspondences_result_rej_trimmed); - if (int (correspondences_result_rej_trimmed->size ()) == nr_correspondences_result_rej_trimmed) + if (static_cast(correspondences_result_rej_trimmed->size ()) == nr_correspondences_result_rej_trimmed) { for (int i = 0; i < nr_correspondences_result_rej_trimmed; ++i) { @@ -364,7 +364,7 @@ TEST (PCL, CorrespondenceRejectorVarTrimmed) corr_rej_var_trimmed_dist.getCorrespondences(*correspondences_result_rej_var_trimmed_dist); // check for correct matches - if (int (correspondences_result_rej_var_trimmed_dist->size ()) == nr_correspondences_result_rej_dist) + if (static_cast(correspondences_result_rej_var_trimmed_dist->size ()) == nr_correspondences_result_rej_dist) { for (int i = 0; i < nr_correspondences_result_rej_dist; ++i) { diff --git a/test/sample_consensus/test_sample_consensus_plane_models.cpp b/test/sample_consensus/test_sample_consensus_plane_models.cpp index 750797b1c22..a9f4b32328e 100644 --- a/test/sample_consensus/test_sample_consensus_plane_models.cpp +++ b/test/sample_consensus/test_sample_consensus_plane_models.cpp @@ -583,7 +583,7 @@ main (int argc, char** argv) fromPCLPointCloud2 (cloud_blob, *normals_); indices_.resize (cloud_->size ()); - for (std::size_t i = 0; i < indices_.size (); ++i) { indices_[i] = int (i); } + for (std::size_t i = 0; i < indices_.size (); ++i) { indices_[i] = static_cast(i); } testing::InitGoogleTest (&argc, argv); return (RUN_ALL_TESTS ()); diff --git a/test/search/test_flann_search.cpp b/test/search/test_flann_search.cpp index 6fe198dea0f..bb8a46ef469 100644 --- a/test/search/test_flann_search.cpp +++ b/test/search/test_flann_search.cpp @@ -61,7 +61,7 @@ init () cloud.width = cloud.size (); cloud.height = 1; - srand (int (time (nullptr))); + srand (static_cast(time (nullptr))); // Randomly create a new point cloud, use points.emplace_back cloud_big.width = 640; cloud_big.height = 480; @@ -83,7 +83,7 @@ TEST (PCL, FlannSearch_nearestKSearch) for (std::size_t i = 0; i < cloud.size (); ++i) { float distance = euclideanDistance (cloud[i], test_point); - sorted_brute_force_result.insert (std::make_pair (distance, int (i))); + sorted_brute_force_result.insert (std::make_pair (distance, static_cast(i))); } float max_dist = 0.0f; unsigned int counter = 0; @@ -221,7 +221,7 @@ TEST (PCL, FlannSearch_knnByIndex) pcl::Indices query_indices; for (std::size_t i = 0; i(i)); } flann_search.nearestKSearch (cloud_big, query_indices,no_of_neighbors,indices,dists); @@ -334,7 +334,7 @@ TEST (PCL, FlannSearch_compareToKdTreeFlann) pcl::Indices query_indices; for (std::size_t i = 0; i(i)); { ScopeTime scopeTime ("FLANN multi nearestKSearch with indices"); diff --git a/test/search/test_organized.cpp b/test/search/test_organized.cpp index e89daadb649..5673126f78b 100644 --- a/test/search/test_organized.cpp +++ b/test/search/test_organized.cpp @@ -115,11 +115,11 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) for (int ypos = -centerY; ypos < centerY; ypos++) for (int xpos = -centerX; xpos < centerX; xpos++) { - double z = 15.0 * (double (rand ()) / double (RAND_MAX+1.0))+20; + double z = 15.0 * (static_cast(rand ()) / (RAND_MAX+1.0))+20; double y = ypos * oneOverFocalLength * z; double x = xpos * oneOverFocalLength * z; - cloudIn->points.emplace_back(float (x), float (y), float (z)); + cloudIn->points.emplace_back(static_cast(x), static_cast(y), static_cast(z)); } unsigned int searchIdx = rand()%(cloudIn->width * cloudIn->height); @@ -130,7 +130,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) // organized nearest neighbor search organizedNeighborSearch.setInputCloud (cloudIn); - organizedNeighborSearch.nearestKSearch (searchPoint, int (K), k_indices, k_sqr_distances); + organizedNeighborSearch.nearestKSearch (searchPoint, static_cast(K), k_indices, k_sqr_distances); k_indices_bruteforce.clear(); k_sqr_distances_bruteforce.clear(); @@ -143,7 +143,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) { double pointDist = pcl_tests::squared_point_distance((*cloudIn)[i], searchPoint); - prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, int (i)); + prioPointQueueEntry pointEntry ((*cloudIn)[i], pointDist, static_cast(i)); pointCandidates.push (pointEntry); } @@ -156,7 +156,7 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Nearest_K_Neighbour_Search) while (!pointCandidates.empty ()) { k_indices_bruteforce.push_back (pointCandidates.top ().pointIdx_); - k_sqr_distances_bruteforce.push_back (float (pointCandidates.top ().pointDistance_)); + k_sqr_distances_bruteforce.push_back (static_cast(pointCandidates.top ().pointDistance_)); pointCandidates.pop (); } @@ -208,18 +208,18 @@ TEST (PCL, Organized_Neighbor_Pointcloud_Neighbours_Within_Radius_Search) for (int ypos = -centerY; ypos < centerY; ypos++) for (int xpos = -centerX; xpos < centerX; xpos++) { - double z = 5.0 * ( (double (rand ()) / double (RAND_MAX)))+5; + double z = 5.0 * ( (static_cast(rand ()) / static_cast(RAND_MAX)))+5; double y = ypos*oneOverFocalLength*z; double x = xpos*oneOverFocalLength*z; - (*cloudIn)[idx++]= PointXYZ (float (x), float (y), float (z)); + (*cloudIn)[idx++]= PointXYZ (static_cast(x), static_cast(y), static_cast(z)); } unsigned int randomIdx = rand()%(cloudIn->width * cloudIn->height); const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; - double searchRadius = 1.0 * (double (rand ()) / double (RAND_MAX)); + double searchRadius = 1.0 * (static_cast(rand ()) / static_cast(RAND_MAX)); // bruteforce radius search std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index f06a4f42382..f4ba1e4c390 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -114,9 +114,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search) for (int ypos = -centerY; ypos < centerY; ypos++) for (int xpos = -centerX; xpos < centerX; xpos++) { - double z = 15.0 * ((double)rand () / (double)(RAND_MAX+1.0))+20; - double y = (double)ypos*oneOverFocalLength*(double)z; - double x = (double)xpos*oneOverFocalLength*(double)z; + double z = 15.0 * (static_cast(rand ()) / (RAND_MAX+1.0))+20; + double y = static_cast(ypos)*oneOverFocalLength*z; + double x = static_cast(xpos)*oneOverFocalLength*z; cloudIn->points.emplace_back(x, y, z); } @@ -220,7 +220,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Nearest_K_Neighbour_Search_Kinec // organized nearest neighbor search organizedNeighborSearch.setInputCloud (cloudIn); - organizedNeighborSearch.nearestKSearch (searchPoint, (int)K, k_indices, k_sqr_distances); + organizedNeighborSearch.nearestKSearch (searchPoint, static_cast(K), k_indices, k_sqr_distances); k_indices_bruteforce.clear(); k_sqr_distances_bruteforce.clear(); @@ -287,7 +287,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) for (int ypos = -centerY; ypos < centerY; ypos++) for (int xpos = -centerX; xpos < centerX; xpos++) { - double z = 5.0 * ( ((double)rand () / (double)RAND_MAX))+5; + double z = 5.0 * ( (static_cast(rand ()) / static_cast(RAND_MAX)))+5; double y = ypos*oneOverFocalLength*z; double x = xpos*oneOverFocalLength*z; (*cloudIn)[idx++]= PointXYZ (x, y, z); @@ -297,7 +297,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; - const double searchRadius = 1.0 * ((double)rand () / (double)RAND_MAX); + const double searchRadius = 1.0 * (static_cast(rand ()) / static_cast(RAND_MAX)); // double searchRadius = 1/10; // bruteforce radius search @@ -376,7 +376,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ for (int ypos = -centerY; ypos < centerY; ypos++) for (int xpos = -centerX; xpos < centerX; xpos++) { - double z = 5.0 * ( ((double)rand () / (double)RAND_MAX))+5; + double z = 5.0 * ( (static_cast(rand ()) / static_cast(RAND_MAX)))+5; double y = ypos*oneOverFocalLength*z; double x = xpos*oneOverFocalLength*z; @@ -387,7 +387,7 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; - const double searchRadius = 1.0 * ((double)rand () / (double)RAND_MAX); + const double searchRadius = 1.0 * (static_cast(rand ()) / static_cast(RAND_MAX)); // bruteforce radius search std::vector cloudSearchBruteforce; diff --git a/test/search/test_search.cpp b/test/search/test_search.cpp index 208caea499c..20bf9734d04 100644 --- a/test/search/test_search.cpp +++ b/test/search/test_search.cpp @@ -302,7 +302,7 @@ testKNNSearch (typename PointCloud::ConstPtr point_cloud, std::vectorsize ()); ++pIdx) + for (int pIdx = 0; pIdx < static_cast(point_cloud->size ()); ++pIdx) { if (!isFinite (point_cloud->points [pIdx])) nan_mask [pIdx] = false; @@ -315,7 +315,7 @@ testKNNSearch (typename PointCloud::ConstPtr point_cloud, std::vector(search_methods.size ()); ++sIdx) search_methods [sIdx]->setInputCloud (point_cloud, input_indices_); // test knn values from 1, 8, 64, 512 @@ -327,7 +327,7 @@ testKNNSearch (typename PointCloud::ConstPtr point_cloud, std::vector(search_methods.size ()); ++sIdx) { search_methods [sIdx]->nearestKSearch ((*point_cloud)[query_index], knn, indices [sIdx], distances [sIdx]); passed [sIdx] = passed [sIdx] && testUniqueness (indices [sIdx], search_methods [sIdx]->getName ()); @@ -339,7 +339,7 @@ testKNNSearch (typename PointCloud::ConstPtr point_cloud, std::vector(search_methods.size ()); ++sIdx) { passed [sIdx] = passed [sIdx] && compareResults (indices [0], distances [0], search_methods [0]->getName (), indices [sIdx], distances [sIdx], search_methods [sIdx]->getName (), 1e-6f); @@ -380,7 +380,7 @@ testRadiusSearch (typename PointCloud::ConstPtr point_cloud, std::vector #pragma omp parallel for \ default(none) \ shared(nan_mask, point_cloud) - for (int pIdx = 0; pIdx < int (point_cloud->size ()); ++pIdx) + for (int pIdx = 0; pIdx < static_cast(point_cloud->size ()); ++pIdx) { if (!isFinite (point_cloud->points [pIdx])) nan_mask [pIdx] = false; @@ -393,7 +393,7 @@ testRadiusSearch (typename PointCloud::ConstPtr point_cloud, std::vector #pragma omp parallel for \ default(none) \ shared(input_indices_, point_cloud, search_methods) - for (int sIdx = 0; sIdx < int (search_methods.size ()); ++sIdx) + for (int sIdx = 0; sIdx < static_cast(search_methods.size ()); ++sIdx) search_methods [sIdx]->setInputCloud (point_cloud, input_indices_); // test radii 0.01, 0.02, 0.04, 0.08 diff --git a/test/surface/test_concave_hull.cpp b/test/surface/test_concave_hull.cpp index 3f22c606a50..3f863d71625 100644 --- a/test/surface/test_concave_hull.cpp +++ b/test/surface/test_concave_hull.cpp @@ -213,8 +213,8 @@ TEST (PCL, ConcaveHull_LTable) { for (std::size_t j = 0; j <= 2; j++) { - cloud_out_ltable[npoints].x = float (i) * 0.5f; - cloud_out_ltable[npoints].y = -float (j) * 0.5f; + cloud_out_ltable[npoints].x = static_cast(i) * 0.5f; + cloud_out_ltable[npoints].y = -static_cast(j) * 0.5f; cloud_out_ltable[npoints].z = 0.f; npoints++; } @@ -224,8 +224,8 @@ TEST (PCL, ConcaveHull_LTable) { for(std::size_t j = 3; j < 8; j++) { - cloud_out_ltable[npoints].x = float (i) * 0.5f; - cloud_out_ltable[npoints].y = -float (j) * 0.5f; + cloud_out_ltable[npoints].x = static_cast(i) * 0.5f; + cloud_out_ltable[npoints].y = -static_cast(j) * 0.5f; cloud_out_ltable[npoints].z = 0.f; npoints++; } diff --git a/test/surface/test_convex_hull.cpp b/test/surface/test_convex_hull.cpp index 7dc05a02dc1..0ad3b8e9644 100644 --- a/test/surface/test_convex_hull.cpp +++ b/test/surface/test_convex_hull.cpp @@ -195,8 +195,8 @@ TEST (PCL, ConvexHull_LTable) { for (std::size_t j = 0; j <= 2; j++) { - cloud_out_ltable[npoints].x = float (i) * 0.5f; - cloud_out_ltable[npoints].y = -float (j) * 0.5f; + cloud_out_ltable[npoints].x = static_cast(i) * 0.5f; + cloud_out_ltable[npoints].y = -static_cast(j) * 0.5f; cloud_out_ltable[npoints].z = 0.f; npoints++; } @@ -206,8 +206,8 @@ TEST (PCL, ConvexHull_LTable) { for (std::size_t j = 3; j < 8; j++) { - cloud_out_ltable[npoints].x = float (i) * 0.5f; - cloud_out_ltable[npoints].y = -float (j) * 0.5f; + cloud_out_ltable[npoints].x = static_cast(i) * 0.5f; + cloud_out_ltable[npoints].y = -static_cast(j) * 0.5f; cloud_out_ltable[npoints].z = 0.f; npoints++; } diff --git a/tools/elch.cpp b/tools/elch.cpp index 1d170ec9b1f..e8e721955ee 100644 --- a/tools/elch.cpp +++ b/tools/elch.cpp @@ -91,7 +91,7 @@ loopDetection (int end, const CloudVector &clouds, double dist, int &first, int } } //std::cout << "min_dist: " << min_dist << " state: " << state << " first: " << first << " end: " << end << std::endl; - if (min_dist > 0 && (state < 2 || end == int (clouds.size ()) - 1)) //TODO + if (min_dist > 0 && (state < 2 || end == static_cast(clouds.size ()) - 1)) //TODO { min_dist = -1; return true; @@ -136,7 +136,7 @@ main (int argc, char **argv) for (std::size_t i = 0; i < clouds.size (); i++) { - if (loopDetection (int (i), clouds, 3.0, first, last)) + if (loopDetection (static_cast(i), clouds, 3.0, first, last)) { std::cout << "Loop between " << first << " (" << clouds[first].first << ") and " << last << " (" << clouds[last].first << ")" << std::endl; elch.setLoopStart (first); diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index 4bf9835cf0f..1832d83e2bf 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -116,7 +116,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir #pragma omp parallel for \ default(none) \ shared(output_dir, pcd_files, sigma_r, sigma_s) - for (int i = 0; i < int (pcd_files.size ()); ++i) + for (int i = 0; i < static_cast(pcd_files.size ()); ++i) { // Load the first file Eigen::Vector4f translation; diff --git a/tools/image_grabber_saver.cpp b/tools/image_grabber_saver.cpp index 764e672d8f9..1dab5d9230d 100644 --- a/tools/image_grabber_saver.cpp +++ b/tools/image_grabber_saver.cpp @@ -126,7 +126,7 @@ main (int argc, char** argv) printHelp (argc, argv); return (-1); } - grabber->setDepthImageUnits (float (1E-3)); + grabber->setDepthImageUnits (static_cast(1E-3)); //grabber->setFocalLength(focal_length); // FIXME EventHelper h; diff --git a/tools/image_grabber_viewer.cpp b/tools/image_grabber_viewer.cpp index 2669f04e970..4cf45843fe1 100644 --- a/tools/image_grabber_viewer.cpp +++ b/tools/image_grabber_viewer.cpp @@ -129,7 +129,7 @@ mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie) int main (int argc, char** argv) { - srand (unsigned (time (nullptr))); + srand (static_cast(time (nullptr))); if (argc > 1) { @@ -207,7 +207,7 @@ main (int argc, char** argv) printHelp (argc, argv); return (-1); } - grabber->setDepthImageUnits (float (1E-3)); + grabber->setDepthImageUnits (static_cast(1E-3)); // Before manually setting double fx, fy, cx, cy; diff --git a/tools/mesh_sampling.cpp b/tools/mesh_sampling.cpp index 00c07bc1ac4..79f916ce6fc 100644 --- a/tools/mesh_sampling.cpp +++ b/tools/mesh_sampling.cpp @@ -82,7 +82,7 @@ randPSurface (vtkPolyData * polydata, std::vector * cumulativeAreas, dou float r = static_cast (uniform_deviate (rand ()) * totalArea); auto low = std::lower_bound (cumulativeAreas->begin (), cumulativeAreas->end (), r); - vtkIdType el = vtkIdType (low - cumulativeAreas->begin ()); + vtkIdType el = static_cast(low - cumulativeAreas->begin ()); double A[3], B[3], C[3]; vtkIdType npts = 0; @@ -102,9 +102,9 @@ randPSurface (vtkPolyData * polydata, std::vector * cumulativeAreas, dou } float r1 = static_cast (uniform_deviate (rand ())); float r2 = static_cast (uniform_deviate (rand ())); - randomPointTriangle (float (A[0]), float (A[1]), float (A[2]), - float (B[0]), float (B[1]), float (B[2]), - float (C[0]), float (C[1]), float (C[2]), r1, r2, p); + randomPointTriangle (static_cast(A[0]), static_cast(A[1]), static_cast(A[2]), + static_cast(B[0]), static_cast(B[1]), static_cast(B[2]), + static_cast(C[0]), static_cast(C[1]), static_cast(C[2]), r1, r2, p); if (calcColor) { @@ -116,9 +116,9 @@ randPSurface (vtkPolyData * polydata, std::vector * cumulativeAreas, dou colors->GetTuple (ptIds[1], cB); colors->GetTuple (ptIds[2], cC); - randomPointTriangle (float (cA[0]), float (cA[1]), float (cA[2]), - float (cB[0]), float (cB[1]), float (cB[2]), - float (cC[0]), float (cC[1]), float (cC[2]), r1, r2, c); + randomPointTriangle (static_cast(cA[0]), static_cast(cA[1]), static_cast(cA[2]), + static_cast(cB[0]), static_cast(cB[1]), static_cast(cB[2]), + static_cast(cC[0]), static_cast(cC[1]), static_cast(cC[2]), r1, r2, c); } else { diff --git a/tools/mls_smoothing.cpp b/tools/mls_smoothing.cpp index 4caf1476260..1a95bdd178e 100644 --- a/tools/mls_smoothing.cpp +++ b/tools/mls_smoothing.cpp @@ -117,7 +117,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, // mls.setUpsamplingMethod (MovingLeastSquares::RANDOM_UNIFORM_DENSITY); // mls.setUpsamplingMethod (MovingLeastSquares::VOXEL_GRID_DILATION); mls.setUpsamplingMethod (MovingLeastSquares::NONE); - mls.setPointDensity (60000 * int (search_radius)); // 300 points in a 5 cm radius + mls.setPointDensity (60000 * static_cast(search_radius)); // 300 points in a 5 cm radius mls.setUpsamplingRadius (0.025); mls.setUpsamplingStepSize (0.015); mls.setDilationIterations (2); diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index 34401a8bcb2..f340ddb8816 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -99,7 +99,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output IntegralImageNormalEstimation ne; ne.setInputCloud (xyz); ne.setNormalEstimationMethod (IntegralImageNormalEstimation::COVARIANCE_MATRIX); - ne.setNormalSmoothingSize (float (radius)); + ne.setNormalSmoothingSize (static_cast(radius)); ne.setDepthDependentSmoothing (true); ne.compute (normals); } @@ -135,7 +135,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir #pragma omp parallel for \ default(none) \ shared(k, output_dir, pcd_files, radius) - for (int i = 0; i < int (pcd_files.size ()); ++i) + for (int i = 0; i < static_cast(pcd_files.size ()); ++i) { // Load the first file Eigen::Vector4f translation; diff --git a/tools/octree_viewer.cpp b/tools/octree_viewer.cpp index 23d1cee4d51..7e09b0cb4e3 100644 --- a/tools/octree_viewer.cpp +++ b/tools/octree_viewer.cpp @@ -390,7 +390,7 @@ class OctreeViewer cloudVoxel->points.push_back (pt_voxel_center); // If the asked depth is the depth of the octree, retrieve the centroid at this LeafNode - if (octree.getTreeDepth () == (unsigned int) depth) + if (octree.getTreeDepth () == static_cast(depth)) { auto* container = dynamic_cast::LeafNode*> (tree_it.getCurrentOctreeNode ()); diff --git a/tools/openni2_viewer.cpp b/tools/openni2_viewer.cpp index a1612da0c12..7296b4e54d4 100644 --- a/tools/openni2_viewer.cpp +++ b/tools/openni2_viewer.cpp @@ -336,10 +336,10 @@ main (int argc, char** argv) unsigned mode; if (pcl::console::parse (argc, argv, "-depthmode", mode) != -1) - depth_mode = pcl::io::OpenNI2Grabber::Mode (mode); + depth_mode = static_cast (mode); if (pcl::console::parse (argc, argv, "-imagemode", mode) != -1) - image_mode = pcl::io::OpenNI2Grabber::Mode (mode); + image_mode = static_cast (mode); if (pcl::console::find_argument (argc, argv, "-xyz") != -1) xyz = true; diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 792e9334021..7e65320e5cc 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -72,14 +72,14 @@ getTotalSystemMemory () std::uint64_t pages = sysconf (_SC_AVPHYS_PAGES); std::uint64_t page_size = sysconf (_SC_PAGE_SIZE); print_info ("Total available memory size: %lluMB.\n", (pages * page_size) / 1048576); - if (pages * page_size > std::uint64_t (std::numeric_limits::max ())) + if (pages * page_size > static_cast(std::numeric_limits::max ())) { return std::numeric_limits::max (); } - return std::size_t (pages * page_size); + return static_cast(pages * page_size); } -const int BUFFER_SIZE = int (getTotalSystemMemory () / (640 * 480) / 2); +const int BUFFER_SIZE = static_cast(getTotalSystemMemory () / (640 * 480) / 2); #else constexpr int BUFFER_SIZE = 200; @@ -223,13 +223,13 @@ class Buffer getSize () { std::lock_guard buff_lock (bmutex_); - return (int (buffer_.size ())); + return (static_cast(buffer_.size ())); } inline int getCapacity () { - return (int (buffer_.capacity ())); + return (static_cast(buffer_.capacity ())); } inline void diff --git a/tools/openni_save_image.cpp b/tools/openni_save_image.cpp index b7cf2e6cacd..54a86287f13 100644 --- a/tools/openni_save_image.cpp +++ b/tools/openni_save_image.cpp @@ -290,10 +290,10 @@ main(int argc, char ** argv) unsigned imagemode; if (pcl::console::parse (argc, argv, "-imagemode", imagemode) != -1) - image_mode = pcl::OpenNIGrabber::Mode (imagemode); + image_mode = static_cast(imagemode); unsigned depthmode; if (pcl::console::parse (argc, argv, "-depthmode", depthmode) != -1) - depth_mode = pcl::OpenNIGrabber::Mode (depthmode); + depth_mode = static_cast(depthmode); pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode); diff --git a/tools/openni_viewer.cpp b/tools/openni_viewer.cpp index b2e70ce5106..7098f4609ee 100644 --- a/tools/openni_viewer.cpp +++ b/tools/openni_viewer.cpp @@ -340,10 +340,10 @@ main (int argc, char** argv) unsigned mode; if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1) - depth_mode = pcl::OpenNIGrabber::Mode (mode); + depth_mode = static_cast(mode); if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1) - image_mode = pcl::OpenNIGrabber::Mode (mode); + image_mode = static_cast(mode); if (pcl::console::find_argument (argc, argv, "-xyz") != -1) xyz = true; diff --git a/tools/outlier_removal.cpp b/tools/outlier_removal.cpp index 0681095e026..6b2f883358b 100644 --- a/tools/outlier_removal.cpp +++ b/tools/outlier_removal.cpp @@ -111,7 +111,7 @@ compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output if (keep_organized) { xyz_cloud = xyz_cloud_pre; - for (int i = 0; i < int (xyz_cloud->size ()); ++i) + for (int i = 0; i < static_cast(xyz_cloud->size ()); ++i) valid_indices.push_back (i); } else diff --git a/tools/pcd_grabber_viewer.cpp b/tools/pcd_grabber_viewer.cpp index dd46219c774..f1ca85a7a24 100644 --- a/tools/pcd_grabber_viewer.cpp +++ b/tools/pcd_grabber_viewer.cpp @@ -114,7 +114,7 @@ mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie) int main (int argc, char** argv) { - srand (unsigned (time (nullptr))); + srand (static_cast(time (nullptr))); if (argc > 1) { diff --git a/tools/pcd_viewer.cpp b/tools/pcd_viewer.cpp index 82664b676e3..7d045fc9cb7 100644 --- a/tools/pcd_viewer.cpp +++ b/tools/pcd_viewer.cpp @@ -323,7 +323,7 @@ main (int argc, char** argv) print_highlight ("Multi-viewport rendering enabled.\n"); int y_s = static_cast(std::floor (std::sqrt (static_cast(p_file_indices.size () + vtk_file_indices.size ())))); - x_s = y_s + static_cast(std::ceil (double (p_file_indices.size () + vtk_file_indices.size ()) / double (y_s) - y_s)); + x_s = y_s + static_cast(std::ceil (static_cast(p_file_indices.size () + vtk_file_indices.size ()) / static_cast(y_s) - y_s)); if (!p_file_indices.empty ()) { diff --git a/tools/voxel_grid_occlusion_estimation.cpp b/tools/voxel_grid_occlusion_estimation.cpp index 48ee5de786e..897c7f20e1f 100644 --- a/tools/voxel_grid_occlusion_estimation.cpp +++ b/tools/voxel_grid_occlusion_estimation.cpp @@ -68,7 +68,7 @@ createDataSetFromVTKPoints (vtkPoints *points) // Iterate through the points for (vtkIdType i = 0; i < points->GetNumberOfPoints (); i++) - verts->InsertNextCell ((vtkIdType)1, &i); + verts->InsertNextCell (static_cast(1), &i); data->SetPoints (points); data->SetVerts (verts); return data; @@ -201,7 +201,7 @@ int main (int argc, char** argv) std::vector > occluded_voxels; vg.occlusionEstimationAll (occluded_voxels); - print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", (int)occluded_voxels.size ()); print_info (" occluded voxels]\n"); + print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", static_cast(occluded_voxels.size ())); print_info (" occluded voxels]\n"); CloudT::Ptr occ_centroids (new CloudT); occ_centroids->width = occluded_voxels.size (); diff --git a/tools/xyz2pcd.cpp b/tools/xyz2pcd.cpp index 40848038391..2a2cd74e7cd 100644 --- a/tools/xyz2pcd.cpp +++ b/tools/xyz2pcd.cpp @@ -79,7 +79,7 @@ loadCloud (const std::string &filename, PointCloud &cloud) if (st.size () != 3) continue; - cloud.push_back (PointXYZ (float (atof (st[0].c_str ())), float (atof (st[1].c_str ())), float (atof (st[2].c_str ())))); + cloud.push_back (PointXYZ (static_cast(atof (st[0].c_str ())), static_cast(atof (st[1].c_str ())), static_cast(atof (st[2].c_str ())))); } fs.close (); diff --git a/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter.hpp b/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter.hpp index 946a4c5d0cb..5f0085f80ba 100644 --- a/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter.hpp +++ b/tracking/include/pcl/tracking/impl/kld_adaptive_particle_filter.hpp @@ -69,7 +69,7 @@ KLDAdaptiveParticleFilterTracker::resample() x_t.sample(zero_mean, step_noise_covariance_); // motion - if (rand() / double(RAND_MAX) < motion_ratio_) + if (rand() / static_cast(RAND_MAX) < motion_ratio_) x_t = x_t + motion_; S->points.push_back(x_t); diff --git a/tracking/include/pcl/tracking/impl/particle_filter.hpp b/tracking/include/pcl/tracking/impl/particle_filter.hpp index e0d75058b0a..ab55443d3b1 100644 --- a/tracking/include/pcl/tracking/impl/particle_filter.hpp +++ b/tracking/include/pcl/tracking/impl/particle_filter.hpp @@ -164,9 +164,9 @@ ParticleFilterTracker::cropInputPointCloud( { double x_min, y_min, z_min, x_max, y_max, z_max; calcBoundingBox(x_min, x_max, y_min, y_max, z_min, z_max); - pass_x_.setFilterLimits(float(x_min), float(x_max)); - pass_y_.setFilterLimits(float(y_min), float(y_max)); - pass_z_.setFilterLimits(float(z_min), float(z_max)); + pass_x_.setFilterLimits(static_cast(x_min), static_cast(x_max)); + pass_y_.setFilterLimits(static_cast(y_min), static_cast(y_max)); + pass_z_.setFilterLimits(static_cast(z_min), static_cast(z_max)); // x PointCloudInPtr xcloud(new PointCloudIn); diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index 06883af3831..88cec70e390 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -618,7 +618,7 @@ pcl::visualization::PCLVisualizer::addSphere (const PointT ¢er, double radiu vtkSmartPointer data = vtkSmartPointer::New (); data->SetRadius (radius); - data->SetCenter (double (center.x), double (center.y), double (center.z)); + data->SetCenter (static_cast(center.x), static_cast(center.y), static_cast(center.z)); data->SetPhiResolution (10); data->SetThetaResolution (10); data->LatLongTessellationOff (); @@ -896,7 +896,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( // If the cloud is organized, then distribute the normal step in both directions if (cloud->isOrganized () && normals->isOrganized ()) { - auto point_step = static_cast (sqrt (double (level))); + auto point_step = static_cast (sqrt (static_cast(level))); nr_normals = (static_cast ((cloud->width - 1)/ point_step) + 1) * (static_cast ((cloud->height - 1) / point_step) + 1); pts = new float[2 * nr_normals * 3]; @@ -1216,7 +1216,7 @@ pcl::visualization::PCLVisualizer::addCorrespondences ( overwrite = false; // Correspondences doesn't exist, add them instead of updating them } - int n_corr = int (correspondences.size () / nth); + int n_corr = static_cast(correspondences.size () / nth); vtkSmartPointer line_data = vtkSmartPointer::New (); // Prepare colors diff --git a/visualization/src/common/common.cpp b/visualization/src/common/common.cpp index 9dd3777eae5..807fe6d077e 100644 --- a/visualization/src/common/common.cpp +++ b/visualization/src/common/common.cpp @@ -77,9 +77,9 @@ pcl::visualization::getRandomColors (pcl::RGB &rgb, double min, double max) sum = r + g + b; } while (sum <= min || sum >= max); - rgb.r = std::uint8_t (r * 255.0); - rgb.g = std::uint8_t (g * 255.0); - rgb.b = std::uint8_t (b * 255.0); + rgb.r = static_cast(r * 255.0); + rgb.g = static_cast(g * 255.0); + rgb.b = static_cast(b * 255.0); } ///////////////////////////////////////////////////////////////////////////////////////////// @@ -109,8 +109,8 @@ pcl::visualization::worldToView (const Eigen::Vector4d &world_pt, const Eigen::M world /= world.w (); // X/Y screen space coordinate - int screen_x = int (std::floor (double (((world.x () + 1) / 2.0) * width) + 0.5)); - int screen_y = int (std::floor (double (((world.y () + 1) / 2.0) * height) + 0.5)); + int screen_x = static_cast(std::floor ((((world.x () + 1) / 2.0) * width) + 0.5)); + int screen_y = static_cast(std::floor ((((world.y () + 1) / 2.0) * height) + 0.5)); // Calculate -world_pt.y () because the screen Y axis is oriented top->down, ie 0 is top-left //int winY = (int) std::floor ( (double) (((1 - world_pt.y ()) / 2.0) * height) + 0.5); // top left @@ -288,7 +288,7 @@ pcl::visualization::viewScreenArea ( int num = hull_vertex_table[pos][6]; if (num == 0) { - return (float (width * height)); + return (static_cast(width * height)); } //return 0.0; @@ -359,7 +359,7 @@ pcl::visualization::viewScreenArea ( sum += (dst[i].x () - dst[(i+1) % num].x ()) * (dst[i].y () + dst[(i+1) % num].y ()); } - return (std::abs (float (sum * 0.5f))); + return (std::abs (static_cast(sum * 0.5f))); } ///////////////////////////////////////////////////////////////////////////////////////////// diff --git a/visualization/src/common/float_image_utils.cpp b/visualization/src/common/float_image_utils.cpp index 50cfa387bd1..e901860a03c 100644 --- a/visualization/src/common/float_image_utils.cpp +++ b/visualization/src/common/float_image_utils.cpp @@ -225,7 +225,7 @@ pcl::visualization::FloatImageUtils::getVisualImage (const unsigned short* short auto* data = new unsigned char[arraySize]; unsigned char* dataPtr = data; - float factor = 1.0f / float (max_value - min_value), offset = float (-min_value); + float factor = 1.0f / static_cast(max_value - min_value), offset = static_cast(-min_value); for (int i=0; i(getSize ()[0]) != width || + static_cast(getSize ()[1]) != height)) setSize (width, height); // Check to see if this ID entry already exists (has it been already added to the visualizer?) @@ -170,8 +170,8 @@ pcl::visualization::ImageViewer::addMonoImage ( const unsigned char* rgb_data, unsigned width, unsigned height, const std::string &layer_id, double opacity) { - if (unsigned (getSize ()[0]) != width || - unsigned (getSize ()[1]) != height) + if (static_cast(getSize ()[0]) != width || + static_cast(getSize ()[1]) != height) setSize (width, height); // Check to see if this ID entry already exists (has it been already added to the visualizer?) @@ -504,7 +504,7 @@ pcl::visualization::ImageViewer::emitMouseEvent (unsigned long event_id) void pcl::visualization::ImageViewer::emitKeyboardEvent (unsigned long event_id) { - KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ()); + KeyboardEvent event ((event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ()); keyboard_signal_ (event); } diff --git a/visualization/src/pcl_plotter.cpp b/visualization/src/pcl_plotter.cpp index e95c0d840e1..413ff946775 100644 --- a/visualization/src/pcl_plotter.cpp +++ b/visualization/src/pcl_plotter.cpp @@ -262,7 +262,7 @@ pcl::visualization::PCLPlotter::addPlotData ( while (ss >> temp) pnames.push_back(temp); - int nop = int (pnames.size ());// number of plots (y coordinate vectors) + int nop = static_cast(pnames.size ());// number of plots (y coordinate vectors) std::vector xarray; //array of X coordinates std::vector< std::vector > yarrays (nop); //a set of array of Y coordinates @@ -612,8 +612,8 @@ pcl::visualization::PCLPlotter::computeHistogram ( { if (std::isfinite (value)) { - auto index = (unsigned int) (std::floor ((value - min) / size)); - if (index == (unsigned int) nbins) index = nbins - 1; //including right boundary + auto index = static_cast(std::floor ((value - min) / size)); + if (index == static_cast(nbins)) index = nbins - 1; //including right boundary histogram[index].second++; } } diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 70657c3d6bb..99f40b0b167 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -1197,7 +1197,7 @@ pcl::visualization::PCLVisualizer::createActorFromVTKDataSet (const vtkSmartPoin } } - actor->SetNumberOfCloudPoints (int (std::max (1, data->GetNumberOfPoints () / 10))); + actor->SetNumberOfCloudPoints (static_cast(std::max (1, data->GetNumberOfPoints () / 10))); actor->GetProperty ()->SetInterpolationToFlat (); /// FIXME disabling backface culling due to known VTK bug: vtkTextActors are not @@ -1527,7 +1527,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties ( { case PCL_VISUALIZER_POINT_SIZE: { - actor->GetProperty ()->SetPointSize (float (value)); + actor->GetProperty ()->SetPointSize (static_cast(value)); actor->Modified (); break; } @@ -1549,7 +1549,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties ( } case PCL_VISUALIZER_LINE_WIDTH: { - actor->GetProperty ()->SetLineWidth (float (value)); + actor->GetProperty ()->SetLineWidth (static_cast(value)); actor->Modified (); break; } @@ -1587,7 +1587,7 @@ pcl::visualization::PCLVisualizer::setPointCloudRenderingProperties ( if (actor->GetMapper ()->GetInput ()->GetPointData ()->GetScalars ()->IsA ("vtkUnsignedCharArray")) break; - switch (int(value)) + switch (static_cast(value)) { case PCL_VISUALIZER_LUT_RANGE_AUTO: double range[2]; @@ -1761,7 +1761,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( { case PCL_VISUALIZER_POINT_SIZE: { - actor->GetProperty ()->SetPointSize (float (value)); + actor->GetProperty ()->SetPointSize (static_cast(value)); actor->Modified (); break; } @@ -1773,7 +1773,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( } case PCL_VISUALIZER_LINE_WIDTH: { - actor->GetProperty ()->SetLineWidth (float (value)); + actor->GetProperty ()->SetLineWidth (static_cast(value)); actor->Modified (); break; } @@ -1783,13 +1783,13 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( if (!text_actor) return (false); vtkSmartPointer tprop = text_actor->GetTextProperty (); - tprop->SetFontSize (int (value)); + tprop->SetFontSize (static_cast(value)); text_actor->Modified (); break; } case PCL_VISUALIZER_REPRESENTATION: { - switch (int (value)) + switch (static_cast(value)) { case PCL_VISUALIZER_REPRESENTATION_POINTS: { @@ -1812,7 +1812,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( } case PCL_VISUALIZER_SHADING: { - switch (int (value)) + switch (static_cast(value)) { case PCL_VISUALIZER_SHADING_FLAT: { @@ -1881,7 +1881,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( if (actor->GetMapper ()->GetInput ()->GetPointData ()->GetScalars ()->IsA ("vtkUnsignedCharArray")) break; - switch (int(value)) + switch (static_cast(value)) { case PCL_VISUALIZER_LUT_RANGE_AUTO: double range[2]; @@ -2948,9 +2948,9 @@ pcl::visualization::PCLVisualizer::updateColorHandlerIndex (const std::string &i } std::size_t color_handler_size = am_it->second.color_handlers.size (); - if (!(std::size_t (index) < color_handler_size)) + if (!(static_cast(index) < color_handler_size)) { - pcl::console::print_warn (stderr, "[updateColorHandlerIndex] Invalid index <%d> given! Index must be less than %d.\n", index, int (color_handler_size)); + pcl::console::print_warn (stderr, "[updateColorHandlerIndex] Invalid index <%d> given! Index must be less than %d.\n", index, static_cast(color_handler_size)); return (false); } // Get the handler @@ -3373,7 +3373,7 @@ pcl::visualization::PCLVisualizer::addTextureMesh (const pcl::TextureMesh &mesh, return (false); // hardware always supports multitexturing of some degree int texture_units = tex_manager->GetNumberOfTextureUnits (); - if ((std::size_t) texture_units < mesh.tex_materials.size ()) + if (static_cast(texture_units) < mesh.tex_materials.size ()) PCL_WARN ("[PCLVisualizer::addTextureMesh] GPU texture units %d < mesh textures %d!\n", texture_units, mesh.tex_materials.size ()); // Load textures @@ -3650,7 +3650,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( sphere->GetPoint (ptIds_com[1], p2_com); sphere->GetPoint (ptIds_com[2], p3_com); vtkTriangle::TriangleCenter (p1_com, p2_com, p3_com, center); - cam_positions[i] = Eigen::Vector3f (float (center[0]), float (center[1]), float (center[2])); + cam_positions[i] = Eigen::Vector3f (static_cast(center[0]), static_cast(center[1]), static_cast(center[2])); cam_positions[i].normalize (); i++; } @@ -3663,7 +3663,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( { double cam_pos[3]; sphere->GetPoint (i, cam_pos); - cam_positions[i] = Eigen::Vector3f (float (cam_pos[0]), float (cam_pos[1]), float (cam_pos[2])); + cam_positions[i] = Eigen::Vector3f (static_cast(cam_pos[0]), static_cast(cam_pos[1]), static_cast(cam_pos[2])); cam_positions[i].normalize (); } } @@ -3958,8 +3958,8 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo win_->SetSize (xres, yres); win_->Render (); - float dwidth = 2.0f / float (xres), - dheight = 2.0f / float (yres); + float dwidth = 2.0f / static_cast(xres), + dheight = 2.0f / static_cast(yres); cloud->points.resize (xres * yres); cloud->width = xres; @@ -3997,8 +3997,8 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo continue; } - Eigen::Vector4f world_coords (dwidth * float (x) - 1.0f, - dheight * float (y) - 1.0f, + Eigen::Vector4f world_coords (dwidth * static_cast(x) - 1.0f, + dheight * static_cast(y) - 1.0f, depth[ptr], 1.0f); world_coords = mat2 * mat1 * world_coords; diff --git a/visualization/src/point_picking_event.cpp b/visualization/src/point_picking_event.cpp index cb13eea1a3c..aae888cb5d3 100644 --- a/visualization/src/point_picking_event.cpp +++ b/visualization/src/point_picking_event.cpp @@ -161,7 +161,7 @@ pcl::visualization::PointPickingCallback::performSinglePick ( { double p[3]; point_picker->GetDataSet ()->GetPoint (idx, p); - x = float (p[0]); y = float (p[1]); z = float (p[2]); + x = static_cast(p[0]); y = static_cast(p[1]); z = static_cast(p[2]); actor_ = point_picker->GetActor(); } diff --git a/visualization/src/window.cpp b/visualization/src/window.cpp index 53b04809920..0e1e0a40c9b 100644 --- a/visualization/src/window.cpp +++ b/visualization/src/window.cpp @@ -301,7 +301,7 @@ pcl::visualization::Window::emitMouseEvent (unsigned long event_id) void pcl::visualization::Window::emitKeyboardEvent (unsigned long event_id) { - KeyboardEvent event (bool(event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ()); + KeyboardEvent event ((event_id == vtkCommand::KeyPressEvent), interactor_->GetKeySym (), interactor_->GetKeyCode (), interactor_->GetAltKey (), interactor_->GetControlKey (), interactor_->GetShiftKey ()); keyboard_signal_ (event); } From ad7a7a8de7efe420cadbda90a71390f652918820 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Wed, 18 Jan 2023 08:28:55 -0800 Subject: [PATCH 034/288] Added initial set of readability-* clang-tidy checks Added readability-simplify* checks Removed readability-misleading-indentation check Fixed clang-tidy escapes Fixed another clang-tidy escape Removed unnecessary cast to bool --- .clang-tidy | 37 ++++++++++++++++++- common/include/pcl/PolygonMesh.h | 2 +- common/src/io.cpp | 5 +-- .../include/pcl/features/impl/brisk_2d.hpp | 1 + .../impl/range_image_border_extractor.hpp | 5 +-- .../pcl/filters/impl/conditional_removal.hpp | 2 +- .../filters/impl/radius_outlier_removal.hpp | 5 +-- filters/include/pcl/filters/passthrough.h | 6 +-- filters/include/pcl/filters/voxel_grid.h | 4 +- io/src/openni2/openni2_device.cpp | 20 +++++----- io/src/openni2_grabber.cpp | 28 ++++---------- io/src/openni_camera/openni_driver.cpp | 2 +- io/src/openni_grabber.cpp | 28 ++++---------- io/src/ply/ply_parser.cpp | 8 ++-- io/src/tim_grabber.cpp | 2 +- .../face_detection/rf_face_detector_trainer.h | 2 +- .../pcl/recognition/impl/cg/hough_3d.hpp | 2 +- .../pcl/segmentation/impl/region_growing.hpp | 8 ++-- surface/include/pcl/surface/impl/mls.hpp | 4 +- .../include/pcl/surface/organized_fast_mesh.h | 5 +-- .../pcl/visualization/interactor_style.h | 2 +- visualization/src/pcl_visualizer.cpp | 4 +- visualization/src/point_cloud_handlers.cpp | 15 ++------ 23 files changed, 93 insertions(+), 104 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 2a85603d5c8..ca88077447b 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,5 +1,38 @@ --- -Checks: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast,google-readability-casting' -WarningsAsErrors: '-*,modernize-use-auto,modernize-deprecated-headers,modernize-redundant-void-arg,modernize-replace-random-shuffle,modernize-use-equals-default,modernize-use-equals-delete,modernize-use-nullptr,modernize-use-override,modernize-use-using,performance-faster-string-find,performance-for-range-copy,performance-implicit-conversion-in-loop,performance-inefficient-algorithm,performance-inefficient-vector-operation,performance-move-const-arg,performance-move-constructor-init,performance-no-automatic-move,performance-noexcept-move-constructor,performance-type-promotion-in-math-fn,cppcoreguidelines-pro-type-cstyle-cast,cppcoreguidelines-pro-type-static-cast-downcast,google-readability-casting' +Checks: > + -*, + cppcoreguidelines-pro-type-cstyle-cast, + cppcoreguidelines-pro-type-static-cast-downcast, + google-readability-casting, + modernize-deprecated-headers, + modernize-redundant-void-arg, + modernize-replace-random-shuffle, + modernize-use-auto, + modernize-use-equals-default, + modernize-use-equals-delete, + modernize-use-nullptr, + modernize-use-override, + modernize-use-using, + performance-faster-string-find, + performance-for-range-copy, + performance-implicit-conversion-in-loop, + performance-inefficient-algorithm, + performance-inefficient-vector-operation, + performance-move-const-arg, + performance-move-constructor-init, + performance-no-automatic-move, + performance-noexcept-move-constructor, + performance-type-promotion-in-math-fn, + readability-container-size-empty, + readability-delete-null-pointer, + readability-duplicate-include, + readability-redundant-declaration, + readability-redundant-smartptr-get, + readability-redundant-string-cstr, + readability-redundant-string-init, + readability-simplify-boolean-expr, + readability-simplify-subscript-expr, +WarningsAsErrors: '*' CheckOptions: - {key: modernize-use-auto.MinTypeNameLength, value: 7} +UseColor: true diff --git a/common/include/pcl/PolygonMesh.h b/common/include/pcl/PolygonMesh.h index dd15962f828..53626db2c27 100644 --- a/common/include/pcl/PolygonMesh.h +++ b/common/include/pcl/PolygonMesh.h @@ -32,7 +32,7 @@ namespace pcl const auto point_offset = mesh1.cloud.width * mesh1.cloud.height; bool success = pcl::PCLPointCloud2::concatenate(mesh1.cloud, mesh2.cloud); - if (success == false) { + if (!success) { return false; } // Make the resultant polygon mesh take the newest stamp diff --git a/common/src/io.cpp b/common/src/io.cpp index 46d9ca814ca..85d6f27dc3a 100644 --- a/common/src/io.cpp +++ b/common/src/io.cpp @@ -201,10 +201,7 @@ pcl::concatenateFields (const pcl::PCLPointCloud2 &cloud1, point_offset += field_offset; } - if (!cloud1.is_dense || !cloud2.is_dense) - cloud_out.is_dense = false; - else - cloud_out.is_dense = true; + cloud_out.is_dense = cloud1.is_dense && cloud2.is_dense; return (true); } diff --git a/features/include/pcl/features/impl/brisk_2d.hpp b/features/include/pcl/features/impl/brisk_2d.hpp index 79e738aac11..1897bc3e08b 100644 --- a/features/include/pcl/features/impl/brisk_2d.hpp +++ b/features/include/pcl/features/impl/brisk_2d.hpp @@ -564,6 +564,7 @@ BRISK2DEstimation::compute ( int* pvalues = values; const float& x = (kp.x); const float& y = (kp.y); + // NOLINTNEXTLINE(readability-simplify-boolean-expr) if (true) // kp.angle==-1 { if (!rotation_invariance_enabled_) diff --git a/features/include/pcl/features/impl/range_image_border_extractor.hpp b/features/include/pcl/features/impl/range_image_border_extractor.hpp index bfc8867c39c..092dbd3c09c 100644 --- a/features/include/pcl/features/impl/range_image_border_extractor.hpp +++ b/features/include/pcl/features/impl/range_image_border_extractor.hpp @@ -334,10 +334,7 @@ bool RangeImageBorderExtractor::calculateMainPrincipalCurvature(int x, int y, in bool& beam_valid = beams_valid[beam_idx++]; if (step==1) { - if (x2==x && y2==y) - beam_valid = false; - else - beam_valid = true; + beam_valid = !(x2==x && y2==y); } else if (!beam_valid) diff --git a/filters/include/pcl/filters/impl/conditional_removal.hpp b/filters/include/pcl/filters/impl/conditional_removal.hpp index 16da3accb9c..99cc9295b58 100644 --- a/filters/include/pcl/filters/impl/conditional_removal.hpp +++ b/filters/include/pcl/filters/impl/conditional_removal.hpp @@ -624,7 +624,7 @@ pcl::ConditionalRemoval::setCondition (ConditionBasePtr condition) template void pcl::ConditionalRemoval::applyFilter (PointCloud &output) { - if (capable_ == false) + if (!capable_) { PCL_WARN ("[pcl::%s::applyFilter] not capable!\n", getClassName ().c_str ()); return; diff --git a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp index 15926d8f2e1..47c7a8e44be 100644 --- a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp +++ b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp @@ -109,10 +109,7 @@ pcl::RadiusOutlierRemoval::applyFilterIndices (Indices &indices) } else { - if (negative_) - chk_neighbors = true; - else - chk_neighbors = false; + chk_neighbors = negative_; } // Points having too few neighbors are outliers and are passed to removed indices diff --git a/filters/include/pcl/filters/passthrough.h b/filters/include/pcl/filters/passthrough.h index 7edc84bfbc0..644b9d4ea9d 100644 --- a/filters/include/pcl/filters/passthrough.h +++ b/filters/include/pcl/filters/passthrough.h @@ -97,7 +97,7 @@ namespace pcl */ PassThrough (bool extract_removed_indices = false) : FilterIndices (extract_removed_indices), - filter_field_name_ (""), + filter_limit_min_ (std::numeric_limits::lowest()), filter_limit_max_ (std::numeric_limits::max()) { @@ -212,8 +212,8 @@ namespace pcl public: /** \brief Constructor. */ PassThrough (bool extract_removed_indices = false) : - FilterIndices::FilterIndices (extract_removed_indices), filter_field_name_("") - , filter_limit_min_(std::numeric_limits::lowest()) + FilterIndices::FilterIndices (extract_removed_indices), + filter_limit_min_(std::numeric_limits::lowest()) , filter_limit_max_(std::numeric_limits::max()) { filter_name_ = "PassThrough"; diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index cde68c0a132..186fccebc65 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -202,7 +202,7 @@ namespace pcl max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), divb_mul_ (Eigen::Vector4i::Zero ()), - filter_field_name_ (""), + filter_limit_min_ (std::numeric_limits::lowest()), filter_limit_max_ (std::numeric_limits::max()), filter_limit_negative_ (false), @@ -528,7 +528,7 @@ namespace pcl max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), divb_mul_ (Eigen::Vector4i::Zero ()), - filter_field_name_ (""), + filter_limit_min_ (std::numeric_limits::lowest()), filter_limit_max_ (std::numeric_limits::max()), filter_limit_negative_ (false), diff --git a/io/src/openni2/openni2_device.cpp b/io/src/openni2/openni2_device.cpp index 25f9fc300d9..027285bcb41 100644 --- a/io/src/openni2/openni2_device.cpp +++ b/io/src/openni2/openni2_device.cpp @@ -163,7 +163,7 @@ pcl::io::openni2::OpenNI2Device::getStringID () const bool pcl::io::openni2::OpenNI2Device::isValid () const { - return (openni_device_.get () != nullptr) && openni_device_->isValid (); + return (openni_device_ != nullptr) && openni_device_->isValid (); } float @@ -332,7 +332,7 @@ pcl::io::openni2::OpenNI2Device::stopAllStreams () void pcl::io::openni2::OpenNI2Device::stopIRStream () { - if (ir_video_stream_.get () != nullptr) + if (ir_video_stream_ != nullptr) { ir_video_stream_->stop (); ir_video_started_ = false; @@ -341,7 +341,7 @@ pcl::io::openni2::OpenNI2Device::stopIRStream () void pcl::io::openni2::OpenNI2Device::stopColorStream () { - if (color_video_stream_.get () != nullptr) + if (color_video_stream_ != nullptr) { color_video_stream_->stop (); color_video_started_ = false; @@ -350,7 +350,7 @@ pcl::io::openni2::OpenNI2Device::stopColorStream () void pcl::io::openni2::OpenNI2Device::stopDepthStream () { - if (depth_video_stream_.get () != nullptr) + if (depth_video_stream_ != nullptr) { depth_video_stream_->stop (); depth_video_started_ = false; @@ -360,13 +360,13 @@ pcl::io::openni2::OpenNI2Device::stopDepthStream () void pcl::io::openni2::OpenNI2Device::shutdown () { - if (ir_video_stream_.get () != nullptr) + if (ir_video_stream_ != nullptr) ir_video_stream_->destroy (); - if (color_video_stream_.get () != nullptr) + if (color_video_stream_ != nullptr) color_video_stream_->destroy (); - if (depth_video_stream_.get () != nullptr) + if (depth_video_stream_ != nullptr) depth_video_stream_->destroy (); } @@ -747,7 +747,7 @@ bool OpenNI2Device::setPlaybackSpeed (double speed) std::shared_ptr pcl::io::openni2::OpenNI2Device::getIRVideoStream () const { - if (ir_video_stream_.get () == nullptr) + if (ir_video_stream_ == nullptr) { if (hasIRSensor ()) { @@ -764,7 +764,7 @@ pcl::io::openni2::OpenNI2Device::getIRVideoStream () const std::shared_ptr pcl::io::openni2::OpenNI2Device::getColorVideoStream () const { - if (color_video_stream_.get () == nullptr) + if (color_video_stream_ == nullptr) { if (hasColorSensor ()) { @@ -781,7 +781,7 @@ pcl::io::openni2::OpenNI2Device::getColorVideoStream () const std::shared_ptr pcl::io::openni2::OpenNI2Device::getDepthVideoStream () const { - if (depth_video_stream_.get () == nullptr) + if (depth_video_stream_ == nullptr) { if (hasDepthSensor ()) { diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index fff500446d3..de0ed7d95f8 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -169,12 +169,9 @@ void pcl::io::OpenNI2Grabber::checkImageAndDepthSynchronizationRequired () { // do we have anyone listening to images or color point clouds? - if (num_slots () > 0 || + sync_required_ = (num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - sync_required_ = true; - else - sync_required_ = false; + num_slots () > 0); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -182,13 +179,10 @@ void pcl::io::OpenNI2Grabber::checkImageStreamRequired () { // do we have anyone listening to images or color point clouds? - if (num_slots () > 0 || + image_required_ = (num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - image_required_ = true; - else - image_required_ = false; + num_slots () > 0); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -196,28 +190,22 @@ void pcl::io::OpenNI2Grabber::checkDepthStreamRequired () { // do we have anyone listening to depth images or (color) point clouds? - if (num_slots () > 0 || + depth_required_ = (num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || - num_slots () > 0 ) - depth_required_ = true; - else - depth_required_ = false; + num_slots () > 0 ); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void pcl::io::OpenNI2Grabber::checkIRStreamRequired () { - if (num_slots () > 0 || + ir_required_ = (num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - ir_required_ = true; - else - ir_required_ = false; + num_slots () > 0); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index ffa91d3e8b7..f561f28ec15 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -201,7 +201,7 @@ openni_wrapper::OpenNIDriver::updateDeviceList () } else #endif - if (vendor_id == 0x1d27 && device.image_node.get () == nullptr) + if (vendor_id == 0x1d27 && device.image_node == nullptr) { strcpy (const_cast (device.device_node.GetDescription ().strVendor), "ASUS"); strcpy (const_cast (device.device_node.GetDescription ().strName), "Xtion Pro"); diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index adddad8cc63..bc8f3b7fcd1 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -163,12 +163,9 @@ void pcl::OpenNIGrabber::checkImageAndDepthSynchronizationRequired () { // do we have anyone listening to images or color point clouds? - if (num_slots () > 0 || + sync_required_ = num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - sync_required_ = true; - else - sync_required_ = false; + num_slots () > 0; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -176,13 +173,10 @@ void pcl::OpenNIGrabber::checkImageStreamRequired () { // do we have anyone listening to images or color point clouds? - if (num_slots () > 0 || + image_required_ = num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - image_required_ = true; - else - image_required_ = false; + num_slots () > 0; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -190,28 +184,22 @@ void pcl::OpenNIGrabber::checkDepthStreamRequired () { // do we have anyone listening to depth images or (color) point clouds? - if (num_slots () > 0 || + depth_required_ = num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || num_slots () > 0 || - num_slots () > 0 ) - depth_required_ = true; - else - depth_required_ = false; + num_slots () > 0; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void pcl::OpenNIGrabber::checkIRStreamRequired () { - if (num_slots () > 0 || + ir_required_ = num_slots () > 0 || num_slots () > 0 || - num_slots () > 0) - ir_required_ = true; - else - ir_required_ = false; + num_slots () > 0; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/ply/ply_parser.cpp b/io/src/ply/ply_parser.cpp index 91011f8b6d0..335c0fb1808 100644 --- a/io/src/ply/ply_parser.cpp +++ b/io/src/ply/ply_parser.cpp @@ -454,7 +454,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) { for (const auto &element_ptr: elements) { - auto& element = *(element_ptr.get ()); + auto& element = *(element_ptr); for (std::size_t element_index = 0; element_index < element.count; ++element_index) { if (element.begin_element_callback) @@ -472,7 +472,7 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) for (const auto &property_ptr: element.properties) { - auto& property = *(property_ptr.get ()); + auto& property = *(property_ptr); if (!property.parse (*this, format, stringstream)) { error_callback_ (line_number_, "parse error: element property count doesn't match the declaration in the header"); @@ -508,14 +508,14 @@ bool pcl::io::ply::ply_parser::parse (const std::string& filename) for (const auto &element_ptr: elements) { - auto& element = *(element_ptr.get ()); + auto& element = *(element_ptr); for (std::size_t element_index = 0; element_index < element.count; ++element_index) { if (element.begin_element_callback) element.begin_element_callback (); for (const auto &property_ptr: element.properties) { - auto& property = *(property_ptr.get ()); + auto& property = *(property_ptr); if (!property.parse (*this, format, istream)) { return false; diff --git a/io/src/tim_grabber.cpp b/io/src/tim_grabber.cpp index f33e49b1987..3dc1c0b7742 100644 --- a/io/src/tim_grabber.cpp +++ b/io/src/tim_grabber.cpp @@ -83,7 +83,7 @@ pcl::TimGrabber::updateLookupTables () { /////////////////////////////////////////////////////////////////////////////////////////////////// bool pcl::TimGrabber::isValidPacket () const { - return received_packet_.data ()[length_-1] == '\03'; + return received_packet_[length_-1] == '\03'; } /////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h index 32b68f3203a..175f94f86c9 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h @@ -28,7 +28,7 @@ namespace pcl std::size_t min_votes_size_; int used_for_pose_ {std::numeric_limits::max ()}; bool use_normals_ {false}; - std::string directory_ {""}; + std::string directory_; float HEAD_ST_DIAMETER_ {0.2364f}; float larger_radius_ratio_ {1.5f}; std::vector > head_center_votes_{}; diff --git a/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp b/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp index bac7e9f9db3..bdfde3cd836 100644 --- a/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp +++ b/recognition/include/pcl/recognition/impl/cg/hough_3d.hpp @@ -366,7 +366,7 @@ pcl::Hough3DGrouping::re //} this->deinitCompute (); - return (transformations.size ()); + return (!transformations.empty()); } diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index 2b8653e4f54..5ed4b03bc01 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -140,7 +140,7 @@ pcl::RegionGrowing::setCurvatureTestFlag (bool value) { curvature_flag_ = value; - if (curvature_flag_ == false && residual_flag_ == false) + if (!curvature_flag_ && !residual_flag_) residual_flag_ = true; } @@ -157,7 +157,7 @@ pcl::RegionGrowing::setResidualTestFlag (bool value) { residual_flag_ = value; - if (curvature_flag_ == false && residual_flag_ == false) + if (!curvature_flag_ && !residual_flag_) curvature_flag_ = true; } @@ -382,7 +382,7 @@ pcl::RegionGrowing::applySmoothRegionGrowingAlgorithm () std::pair pair; point_residual.resize (num_of_pts, pair); - if (normal_flag_ == true) + if (normal_flag_) { for (int i_point = 0; i_point < num_of_pts; i_point++) { @@ -495,7 +495,7 @@ pcl::RegionGrowing::validatePoint (pcl::index_t initial_seed, p Eigen::Map initial_normal (static_cast ((*normals_)[point].normal)); //check the angle between normals - if (smooth_mode_flag_ == true) + if (smooth_mode_flag_) { Eigen::Map nghbr_normal (static_cast ((*normals_)[nghbr].normal)); float dot_product = std::abs (nghbr_normal.dot (initial_normal)); diff --git a/surface/include/pcl/surface/impl/mls.hpp b/surface/include/pcl/surface/impl/mls.hpp index 329a3f2c375..e13a8af9d08 100644 --- a/surface/include/pcl/surface/impl/mls.hpp +++ b/surface/include/pcl/surface/impl/mls.hpp @@ -388,7 +388,7 @@ pcl::MovingLeastSquares::performUpsampling (PointCloudOut & // If the closest point did not have a valid MLS fitting result // OR if it is too far away from the sampled point - if (mls_results_[input_index].valid == false) + if (!mls_results_[input_index].valid) continue; Eigen::Vector3d add_point = (*distinct_cloud_)[dp_i].getVector3fMap ().template cast (); @@ -425,7 +425,7 @@ pcl::MovingLeastSquares::performUpsampling (PointCloudOut & // If the closest point did not have a valid MLS fitting result // OR if it is too far away from the sampled point - if (mls_results_[input_index].valid == false) + if (!mls_results_[input_index].valid) continue; Eigen::Vector3d add_point = p.getVector3fMap ().template cast (); diff --git a/surface/include/pcl/surface/organized_fast_mesh.h b/surface/include/pcl/surface/organized_fast_mesh.h index 4aeafec644f..b05f19b8496 100644 --- a/surface/include/pcl/surface/organized_fast_mesh.h +++ b/surface/include/pcl/surface/organized_fast_mesh.h @@ -120,10 +120,7 @@ namespace pcl max_edge_length_a_ = a; max_edge_length_b_ = b; max_edge_length_c_ = c; - if ((max_edge_length_a_ + max_edge_length_b_ + max_edge_length_c_) > std::numeric_limits::min()) - max_edge_length_set_ = true; - else - max_edge_length_set_ = false; + max_edge_length_set_ = (max_edge_length_a_ + max_edge_length_b_ + max_edge_length_c_) > std::numeric_limits::min(); }; inline void diff --git a/visualization/include/pcl/visualization/interactor_style.h b/visualization/include/pcl/visualization/interactor_style.h index c605ab1e898..5f9ae34bae9 100644 --- a/visualization/include/pcl/visualization/interactor_style.h +++ b/visualization/include/pcl/visualization/interactor_style.h @@ -116,7 +116,7 @@ namespace pcl init_ (), win_height_ (), win_width_ (), win_pos_x_ (), win_pos_y_ (), max_win_height_ (), max_win_width_ (), use_vbos_ (false), grid_enabled_ (), lut_enabled_ (), stereo_anaglyph_mask_default_ (), - modifier_ (), camera_saved_ (), lut_actor_id_ ("") + modifier_ (), camera_saved_ () {} /** \brief Empty destructor */ diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 99f40b0b167..63b09df13c6 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -92,10 +92,10 @@ #include #endif +#include #include #include -#include -#include + #include // for BOOST_VERSION #if (BOOST_VERSION >= 106600) #include diff --git a/visualization/src/point_cloud_handlers.cpp b/visualization/src/point_cloud_handlers.cpp index 06d3d53ae74..4b70dd9ec17 100644 --- a/visualization/src/point_cloud_handlers.cpp +++ b/visualization/src/point_cloud_handlers.cpp @@ -419,10 +419,7 @@ pcl::visualization::PointCloudColorHandlerGenericField::Poi field_name_ (field_name) { field_idx_ = pcl::getFieldIndex (*cloud, field_name); - if (field_idx_ != -1) - capable_ = true; - else - capable_ = false; + capable_ = field_idx_ != -1; } /////////////////////////////////////////////////////////////////////////////////////////// @@ -494,10 +491,7 @@ pcl::visualization::PointCloudColorHandlerRGBAField::PointC { // Handle the 24-bit packed RGBA values field_idx_ = pcl::getFieldIndex (*cloud, "rgba"); - if (field_idx_ != -1) - capable_ = true; - else - capable_ = false; + capable_ = field_idx_ != -1; } /////////////////////////////////////////////////////////////////////////////////////////// @@ -579,10 +573,7 @@ pcl::visualization::PointCloudColorHandlerLabelField::Point : pcl::visualization::PointCloudColorHandler::PointCloudColorHandler (cloud) { field_idx_ = pcl::getFieldIndex (*cloud, "label"); - if (field_idx_ != -1) - capable_ = true; - else - capable_ = false; + capable_ = field_idx_ != -1; static_mapping_ = static_mapping; } From a0488589e73ca7aaba86abe35a8f2b0771442caa Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 19 Jan 2023 20:21:14 +0100 Subject: [PATCH 035/288] Fix access violation in IntegralImageNormalEstimation when using depth dependent smoothing Also some minor fixes: remove unnecessary `smoothing_constant`, make some variables const for readability, and provide better guidance in `setNormalSmoothingSize` --- .../features/impl/integral_image_normal.hpp | 30 +++++++++---------- .../pcl/features/integral_image_normal.h | 4 +-- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/features/include/pcl/features/impl/integral_image_normal.hpp b/features/include/pcl/features/impl/integral_image_normal.hpp index 43b61bf5912..f76765a1bcc 100644 --- a/features/include/pcl/features/impl/integral_image_normal.hpp +++ b/features/include/pcl/features/impl/integral_image_normal.hpp @@ -845,7 +845,7 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con // top and bottom borders // That sets the output density to false! output.is_dense = false; - auto border = static_cast(normal_smoothing_size_); + const auto border = static_cast(normal_smoothing_size_); PointOutT* vec1 = &output [0]; PointOutT* vec2 = vec1 + input_->width * (input_->height - border); @@ -895,7 +895,13 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con if (smoothing > 2.0f) { setRectSize (static_cast (smoothing), static_cast (smoothing)); - computePointNormal (ci, ri, index, output [index]); + // Since depth can be anything, we have no guarantee that the border is sufficient, so we need to check + if(ci>static_cast(rect_width_2_) && ri>static_cast(rect_height_2_) && (ci+rect_width_2_)width && (ri+rect_height_2_)height) { + computePointNormal (ci, ri, index, output [index]); + } else { + output[index].getNormalVector3fMap ().setConstant (bad_point); + output[index].curvature = bad_point; + } } else { @@ -907,8 +913,6 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con } else { - float smoothing_constant = normal_smoothing_size_; - index = border + input_->width * border; unsigned skip = (border << 1); for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip) @@ -924,7 +928,7 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con continue; } - float smoothing = (std::min)(distanceMap[index], smoothing_constant); + float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_); if (smoothing > 2.0f) { @@ -981,8 +985,6 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con } else { - float smoothing_constant = normal_smoothing_size_; - //index = border + input_->width * border; //unsigned skip = (border << 1); //for (unsigned ri = border; ri < input_->height - border; ++ri, index += skip) @@ -1000,7 +1002,7 @@ pcl::IntegralImageNormalEstimation::computeFeatureFull (con continue; } - float smoothing = (std::min)(distanceMap[index], smoothing_constant); + float smoothing = (std::min)(distanceMap[index], normal_smoothing_size_); if (smoothing > 2.0f) { @@ -1027,9 +1029,9 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con if (border_policy_ == BORDER_POLICY_IGNORE) { output.is_dense = false; - auto border = static_cast(normal_smoothing_size_); - unsigned bottom = input_->height > border ? input_->height - border : 0; - unsigned right = input_->width > border ? input_->width - border : 0; + const auto border = static_cast(normal_smoothing_size_); + const unsigned bottom = input_->height > border ? input_->height - border : 0; + const unsigned right = input_->width > border ? input_->width - border : 0; if (use_depth_dependent_smoothing_) { // Iterating over the entire index vector @@ -1075,7 +1077,6 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con } else { - float smoothing_constant = normal_smoothing_size_; // Iterating over the entire index vector for (std::size_t idx = 0; idx < indices_->size (); ++idx) { @@ -1103,7 +1104,7 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con continue; } - float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant); + float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_); if (smoothing > 2.0f) { @@ -1154,7 +1155,6 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con } else { - float smoothing_constant = normal_smoothing_size_; for (std::size_t idx = 0; idx < indices_->size (); ++idx) { unsigned pt_index = (*indices_)[idx]; @@ -1168,7 +1168,7 @@ pcl::IntegralImageNormalEstimation::computeFeaturePart (con continue; } - float smoothing = (std::min)(distanceMap[pt_index], smoothing_constant); + float smoothing = (std::min)(distanceMap[pt_index], normal_smoothing_size_); if (smoothing > 2.0f) { diff --git a/features/include/pcl/features/integral_image_normal.h b/features/include/pcl/features/integral_image_normal.h index b9bc0628422..e4baa843a9a 100644 --- a/features/include/pcl/features/integral_image_normal.h +++ b/features/include/pcl/features/integral_image_normal.h @@ -189,9 +189,9 @@ namespace pcl void setNormalSmoothingSize (float normal_smoothing_size) { - if (normal_smoothing_size <= 0) + if (normal_smoothing_size < 2.0f) { - PCL_ERROR ("[pcl::%s::setNormalSmoothingSize] Invalid normal smoothing size given! (%f). Allowed ranges are: 0 < N. Defaulting to %f.\n", + PCL_ERROR ("[pcl::%s::setNormalSmoothingSize] Invalid normal smoothing size given! (%g). Must be at least 2. Defaulting to %g.\n", feature_name_.c_str (), normal_smoothing_size, normal_smoothing_size_); return; } From a9da50be0a6eec145b5c27ac9e59dbc83245f441 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sun, 22 Jan 2023 10:47:36 +0100 Subject: [PATCH 036/288] Fix crash in SpinImageEstimation (#5586) * Fix crash in SpinImageEstimation The image width (set by the user) must fit together with the size of the output histogram. `setImageWidth` now checks the given parameter and provides advice if they do not work well together. Minor additional change: in the constructor, change the assert to an if-statement since the support_angle_cos should always be checked. Fixes https://github.com/PointCloudLibrary/pcl/issues/1834 Fixes https://github.com/PointCloudLibrary/pcl/issues/5039 (already closed, but same issue) --- .../include/pcl/features/impl/spin_image.hpp | 7 +++-- features/include/pcl/features/spin_image.h | 26 +++++++++++++++++-- 2 files changed, 29 insertions(+), 4 deletions(-) diff --git a/features/include/pcl/features/impl/spin_image.hpp b/features/include/pcl/features/impl/spin_image.hpp index 857c0a4f597..1741ec48375 100644 --- a/features/include/pcl/features/impl/spin_image.hpp +++ b/features/include/pcl/features/impl/spin_image.hpp @@ -53,10 +53,13 @@ pcl::SpinImageEstimation::SpinImageEstimation ( unsigned int image_width, double support_angle_cos, unsigned int min_pts_neighb) : input_normals_ (), rotation_axes_cloud_ (), is_angular_ (false), rotation_axis_ (), use_custom_axis_(false), use_custom_axes_cloud_ (false), - is_radial_ (false), image_width_ (image_width), support_angle_cos_ (support_angle_cos), + is_radial_ (false), support_angle_cos_ (support_angle_cos), min_pts_neighb_ (min_pts_neighb) { - assert (support_angle_cos_ <= 1.0 && support_angle_cos_ >= 0.0); // may be permit negative cosine? + if (0.0 > support_angle_cos || support_angle_cos > 1.0) { // may be permit negative cosine? + throw PCLException ("Cosine of support angle should be between 0 and 1", "spin_image.hpp", "SpinImageEstimation"); + } + setImageWidth(image_width); feature_name_ = "SpinImageEstimation"; } diff --git a/features/include/pcl/features/spin_image.h b/features/include/pcl/features/spin_image.h index 73a22356709..e8418b88700 100644 --- a/features/include/pcl/features/spin_image.h +++ b/features/include/pcl/features/spin_image.h @@ -69,7 +69,9 @@ namespace pcl * * With the default parameters, pcl::Histogram<153> is a good choice for PointOutT. * Of course the dimension of this descriptor must change to match the number - * of bins set by the parameters. + * of bins set by the parameters. If you use SpinImageEstimation with something + * other than pcl::Histogram<153>, you may need to put `#define PCL_NO_PRECOMPILE 1` + * before including `pcl/features/spin_image.h`. * * For further information please see: * @@ -131,7 +133,27 @@ namespace pcl void setImageWidth (unsigned int bin_count) { - image_width_ = bin_count; + const unsigned int necessary_desc_size = (bin_count+1)*(2*bin_count+1); + if (necessary_desc_size > static_cast(PointOutT::descriptorSize())) { + for(int i=0; ; ++i) { // Find the biggest possible image_width_ + if(((i+1)*(2*i+1)) <= PointOutT::descriptorSize()) { + image_width_ = i; + } else { + break; + } + } + PCL_ERROR("[pcl::SpinImageEstimation] The chosen image width is too large, setting it to %u instead. " + "Consider using pcl::Histogram<%u> as output type of SpinImageEstimation " + "(possibly with `#define PCL_NO_PRECOMPILE 1`).\n", image_width_, ((bin_count+1)*(2*bin_count+1))); + } else if (necessary_desc_size < static_cast(PointOutT::descriptorSize())) { + image_width_ = bin_count; + PCL_WARN("[pcl::SpinImageEstimation] The chosen image width is smaller than the output histogram allows. " + "This is not an error, but the last few histogram bins will not be set. " + "Consider using pcl::Histogram<%u> as output type of SpinImageEstimation " + "(possibly with `#define PCL_NO_PRECOMPILE 1`).\n", ((bin_count+1)*(2*bin_count+1))); + } else { + image_width_ = bin_count; + } } /** \brief Sets the maximum angle for the point normal to get to support region. From 08d1f301e087a3c0a1173f0258925a16618515dc Mon Sep 17 00:00:00 2001 From: Jochen Sprickerhof Date: Thu, 26 Jan 2023 16:33:23 +0100 Subject: [PATCH 037/288] Adopt for failing tests on i386 (#5575) * Adopt for failing tests on i386 * Update test/io/test_tim_grabber.cpp Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> * Update test/sample_consensus/test_sample_consensus_plane_models.cpp Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- test/filters/test_convolution.cpp | 2 ++ test/io/test_tim_grabber.cpp | 6 +++--- test/octree/test_octree.cpp | 2 +- .../test_sample_consensus_plane_models.cpp | 10 +++++++--- 4 files changed, 13 insertions(+), 7 deletions(-) diff --git a/test/filters/test_convolution.cpp b/test/filters/test_convolution.cpp index cd9a1d7f798..9029e6642e7 100644 --- a/test/filters/test_convolution.cpp +++ b/test/filters/test_convolution.cpp @@ -396,12 +396,14 @@ TEST (Convolution, convolveRowsXYZRGB) // check result for (std::uint32_t i = 0; i < output->width ; ++i) { +#ifndef __i386__ EXPECT_EQ ((*output) (i, 0).r, output_results[i * 2 + 0].r); EXPECT_EQ ((*output) (i, 0).g, output_results[i * 2 + 0].g); EXPECT_EQ ((*output) (i, 0).b, output_results[i * 2 + 0].b); EXPECT_EQ ((*output) (i, 47).r, output_results[i * 2 + 1].r); EXPECT_EQ ((*output) (i, 47).g, output_results[i * 2 + 1].g); EXPECT_EQ ((*output) (i, 47).b, output_results[i * 2 + 1].b); +#endif } } diff --git a/test/io/test_tim_grabber.cpp b/test/io/test_tim_grabber.cpp index f245e0c762f..f846f7656eb 100644 --- a/test/io/test_tim_grabber.cpp +++ b/test/io/test_tim_grabber.cpp @@ -89,9 +89,9 @@ TEST_F (TimGrabberTest, Test1) for (std::size_t j = 0; j < correct_clouds_.at(i).size (); j++) { PointT const& correct_point = correct_clouds_.at(i).at(j); PointT const& answer_point = answer_cloud->at(j); - EXPECT_NEAR (correct_point.x, answer_point.x, 1.0e-3); - EXPECT_NEAR (correct_point.y, answer_point.y, 1.0e-3); - EXPECT_NEAR (correct_point.z, answer_point.z, 1.0e-3); + EXPECT_NEAR (correct_point.x, answer_point.x, 2.0e-3); + EXPECT_NEAR (correct_point.y, answer_point.y, 2.0e-3); + EXPECT_NEAR (correct_point.z, answer_point.z, 2.0e-3); } } } diff --git a/test/octree/test_octree.cpp b/test/octree/test_octree.cpp index 128ebb2266a..7fbd7bb0925 100644 --- a/test/octree/test_octree.cpp +++ b/test/octree/test_octree.cpp @@ -1538,7 +1538,7 @@ TEST (PCL, Octree_Pointcloud_Ray_Traversal) { pt = (*cloudIn)[i]; d = Eigen::Vector3f (pt.x, pt.y, pt.z) - o; - ASSERT_GE (d.norm (), min_dist); + ASSERT_GE (d.norm (), 0.999 * min_dist); } } } diff --git a/test/sample_consensus/test_sample_consensus_plane_models.cpp b/test/sample_consensus/test_sample_consensus_plane_models.cpp index a9f4b32328e..4dc7ab45517 100644 --- a/test/sample_consensus/test_sample_consensus_plane_models.cpp +++ b/test/sample_consensus/test_sample_consensus_plane_models.cpp @@ -556,10 +556,14 @@ TEST (SampleConsensusModelPlane, OptimizeFarFromOrigin) Eigen::VectorXf coeffs(4); // Doesn't have to be initialized, the function doesn't use them Eigen::VectorXf optimized_coeffs(4); model.optimizeModelCoefficients(inliers, coeffs, optimized_coeffs); - EXPECT_NEAR(optimized_coeffs[0], z[0], 5e-6); - EXPECT_NEAR(optimized_coeffs[1], z[1], 5e-6); - EXPECT_NEAR(optimized_coeffs[2], z[2], 5e-6); + EXPECT_NEAR(optimized_coeffs[0], z[0], 6e-6); + EXPECT_NEAR(optimized_coeffs[1], z[1], 6e-6); + EXPECT_NEAR(optimized_coeffs[2], z[2], 6e-6); +#ifndef __i386__ EXPECT_NEAR(optimized_coeffs[3], -z.dot(center), 5e-2); +#else + EXPECT_NEAR(optimized_coeffs[3], -z.dot(center), 1e-1); +#endif } int From aee41ff23feb343eedc3d0f162d7bf52240119f7 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 26 Jan 2023 21:03:01 +0100 Subject: [PATCH 038/288] Clang-format: make regex case sensitive To avoid confusion between and Qt includes Fixes https://github.com/PointCloudLibrary/pcl/issues/5212 --- .clang-format | 1 + 1 file changed, 1 insertion(+) diff --git a/.clang-format b/.clang-format index 3578d7f1cad..c921cd9a5e9 100644 --- a/.clang-format +++ b/.clang-format @@ -44,6 +44,7 @@ IncludeCategories: # Major 3rd-Party components of apps - Regex: '^$' Priority: 300 + CaseSensitive: true - Regex: '^$' Priority: 300 - Regex: '^$' From 7b7dabe813de6c90ead0cf165631696505823e96 Mon Sep 17 00:00:00 2001 From: Filbert <115785598+sfilbertf@users.noreply.github.com> Date: Tue, 31 Jan 2023 17:43:12 +0100 Subject: [PATCH 039/288] OpenNI apps: Improve handling of command line arguments (#5494) * #5491 * Fixed typo at line 212 in parse.h * Fixed formatting. * Deleted whitespaces. * Dependency update before attempting fix. * Fixed formatting style. * Revert . . formatting? * Weird formatting error test? * Fixed dependency, this should hopefully build. * Removed unused variable in openni_ii_normal_estimation.cpp * Build test after improvements and refactors. * Build Test #2. * deleted whitespace. * Fixed formatting errors. * Fixed formatting openni_boundary_estimation.cpp. * Fixed formatting openni_boundary_estimation.cpp. * Fixed formatting openni_boundary_estimation.cpp. * Formatting check #1. * Formatting check 2. * Deleted whitespace. * Changed general parsing structure, improved usage(). * Fixed formatting errors. * Fixed! * resolve merge conflict * resolve merge conflict * format test * new format test * test formatting * test formatting * test formatting * command line behavior mimics previous version(s), consistent help flags * rest of the files --- apps/src/openni_3d_concave_hull.cpp | 43 ++++++++----- apps/src/openni_3d_convex_hull.cpp | 43 ++++++++----- apps/src/openni_boundary_estimation.cpp | 41 +++++++++---- apps/src/openni_color_filter.cpp | 46 ++++++++------ apps/src/openni_fast_mesh.cpp | 53 +++++++++------- apps/src/openni_feature_persistence.cpp | 61 +++++++++++-------- apps/src/openni_grab_images.cpp | 12 ++-- apps/src/openni_ii_normal_estimation.cpp | 44 +++++++++----- apps/src/openni_klt.cpp | 10 ++-- apps/src/openni_mls_smoothing.cpp | 62 ++++++++++++------- apps/src/openni_mobile_server.cpp | 22 ++++--- apps/src/openni_organized_edge_detection.cpp | 39 ++++++++---- apps/src/openni_planar_convex_hull.cpp | 41 ++++++++----- apps/src/openni_planar_segmentation.cpp | 51 ++++++++++------ apps/src/openni_tracking.cpp | 51 ++++++++-------- apps/src/openni_uniform_sampling.cpp | 46 ++++++++------ apps/src/openni_voxel_grid.cpp | 63 +++++++++++++------- 17 files changed, 457 insertions(+), 271 deletions(-) diff --git a/apps/src/openni_3d_concave_hull.cpp b/apps/src/openni_3d_concave_hull.cpp index 822f7a81d7c..d4c0309704a 100644 --- a/apps/src/openni_3d_concave_hull.cpp +++ b/apps/src/openni_3d_concave_hull.cpp @@ -34,6 +34,7 @@ */ #include +#include #include #include #include @@ -165,19 +166,29 @@ class OpenNI3DConcaveHull { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -186,24 +197,28 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - pcl::OpenNIGrabber grabber(arg); + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { PCL_INFO("PointXYZRGBA mode enabled.\n"); - OpenNI3DConcaveHull v(arg); + OpenNI3DConcaveHull v(device_id); v.run(); } else { PCL_INFO("PointXYZ mode enabled.\n"); - OpenNI3DConcaveHull v(arg); + OpenNI3DConcaveHull v(device_id); v.run(); } return 0; diff --git a/apps/src/openni_3d_convex_hull.cpp b/apps/src/openni_3d_convex_hull.cpp index 841e429a36f..674ea43ead0 100644 --- a/apps/src/openni_3d_convex_hull.cpp +++ b/apps/src/openni_3d_convex_hull.cpp @@ -34,6 +34,7 @@ */ #include +#include #include #include #include @@ -163,19 +164,29 @@ class OpenNI3DConvexHull { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -184,24 +195,28 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - pcl::OpenNIGrabber grabber(arg); + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { PCL_INFO("PointXYZRGBA mode enabled.\n"); - OpenNI3DConvexHull v(arg); + OpenNI3DConvexHull v(device_id); v.run(); } else { PCL_INFO("PointXYZ mode enabled.\n"); - OpenNI3DConvexHull v(arg); + OpenNI3DConvexHull v(device_id); v.run(); } return 0; diff --git a/apps/src/openni_boundary_estimation.cpp b/apps/src/openni_boundary_estimation.cpp index 89467dd0c27..d0e45444d3a 100644 --- a/apps/src/openni_boundary_estimation.cpp +++ b/apps/src/openni_boundary_estimation.cpp @@ -36,6 +36,7 @@ */ #include +#include #include #include #include @@ -180,19 +181,29 @@ class OpenNIIntegralImageNormalEstimation { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -201,18 +212,22 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - pcl::OpenNIGrabber grabber(arg); + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { - OpenNIIntegralImageNormalEstimation v(arg); + OpenNIIntegralImageNormalEstimation v(device_id); v.run(); } else diff --git a/apps/src/openni_color_filter.cpp b/apps/src/openni_color_filter.cpp index e06e45f5121..56203ed36f6 100644 --- a/apps/src/openni_color_filter.cpp +++ b/apps/src/openni_color_filter.cpp @@ -159,21 +159,33 @@ class OpenNIPassthrough { void usage(char** argv) { - std::cout << "usage: " << argv[0] - << " [-rgb [-radius ] ]\n\n" - << std::endl; + std::cout << "usage: " << argv[0] << " [options]\n\n" + << "where options are:\n" + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -rgb R G B: -- (default: 0 0 0)\n" + << " -radius X: -- (default: 442)\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -182,22 +194,21 @@ usage(char** argv) int main(int argc, char** argv) { - if (argc < 2) { - usage(argv); - return 1; - } - - std::string arg(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; unsigned char red = 0, green = 0, blue = 0; int rr, gg, bb; unsigned char radius = 442; // all colors! + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; if (pcl::console::parse_3x_arguments(argc, argv, "-rgb", rr, gg, bb, true) != -1) { std::cout << "-rgb present" << std::endl; int rad; @@ -213,8 +224,9 @@ main(int argc, char** argv) if (bb >= 0 && bb < 256) blue = (unsigned char)bb; } + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { OpenNIPassthrough v(grabber, red, green, blue, radius); diff --git a/apps/src/openni_fast_mesh.cpp b/apps/src/openni_fast_mesh.cpp index 63b1026c310..e3701033940 100644 --- a/apps/src/openni_fast_mesh.cpp +++ b/apps/src/openni_fast_mesh.cpp @@ -34,6 +34,7 @@ */ #include +#include #include #include #include @@ -151,27 +152,29 @@ class OpenNIFastMesh { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { - std::cout << "Device: " << deviceIdx + 1 - << ", vendor: " << driver.getVendorName(deviceIdx) - << ", product: " << driver.getProductName(deviceIdx) - << ", connected: " << driver.getBus(deviceIdx) << " @ " - << driver.getAddress(deviceIdx) << ", serial number: \'" - << driver.getSerialNumber(deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in " - "the list or" - << std::endl - << " bus@address for the device connected to a " - "specific usb-bus / address combination (works only in Linux) or" - << std::endl - << " (only in Linux and for devices " - "which provide serial numbers)" + // clang-format off + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; + // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -180,24 +183,28 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - pcl::OpenNIGrabber grabber(arg); + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { PCL_INFO("PointXYZRGBA mode enabled.\n"); - OpenNIFastMesh v(arg); + OpenNIFastMesh v(device_id); v.run(argc, argv); } else { PCL_INFO("PointXYZ mode enabled.\n"); - OpenNIFastMesh v(arg); + OpenNIFastMesh v(device_id); v.run(argc, argv); } return 0; diff --git a/apps/src/openni_feature_persistence.cpp b/apps/src/openni_feature_persistence.cpp index f61571d91a6..0b397bffd51 100644 --- a/apps/src/openni_feature_persistence.cpp +++ b/apps/src/openni_feature_persistence.cpp @@ -232,12 +232,13 @@ void usage(char** argv) { // clang-format off - std::cout << "usage: " << argv[0] << " \n\n" + std::cout << "usage: " << argv[0] << " [options]\n\n" << "where options are:\n" - << " -octree_leaf_size X = size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n" - << " -normal_search_radius X = size of the neighborhood to consider for calculating the local plane and extracting the normals (default: " << default_normal_search_radius << "\n" - << " -persistence_alpha X = value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n" - << " -scales X1 X2 ... = values for the multiple scales for extracting features (default: "; + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -octree_leaf_size X: size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n" + << " -normal_search_radius X: size of the neighborhood to consider for calculating the local plane and extracting the normals (default: " << default_normal_search_radius << "\n" + << " -persistence_alpha X: value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n" + << " -scales X1 X2 ...: values for the multiple scales for extracting features (default: "; // clang-format on for (const double& i : default_scales_vector) std::cout << i << " "; @@ -247,13 +248,23 @@ usage(char** argv) if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -266,41 +277,43 @@ main(int argc, char** argv) "MultiscaleFeaturePersistence class using the FPFH features\n" << "Use \"-h\" to get more info about the available options.\n"; - std::string arg = ""; - if ((argc > 1) && (argv[1][0] != '-')) - arg = std::string(argv[1]); - - if (pcl::console::find_argument(argc, argv, "-h") == -1) { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - // Parse arguments + std::string device_id = ""; float subsampling_leaf_size = default_subsampling_leaf_size; - pcl::console::parse_argument(argc, argv, "-octree_leaf_size", subsampling_leaf_size); double normal_search_radius = default_normal_search_radius; + std::vector scales_vector_double = default_scales_vector; + std::vector scales_vector(scales_vector_double.size()); + float alpha = default_alpha; + + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + pcl::console::parse_argument(argc, argv, "-octree_leaf_size", subsampling_leaf_size); pcl::console::parse_argument( argc, argv, "-normal_search_radius", normal_search_radius); - std::vector scales_vector_double = default_scales_vector; pcl::console::parse_multiple_arguments(argc, argv, "-scales", scales_vector_double); - std::vector scales_vector(scales_vector_double.size()); for (std::size_t i = 0; i < scales_vector_double.size(); ++i) scales_vector[i] = float(scales_vector_double[i]); - - float alpha = default_alpha; pcl::console::parse_argument(argc, argv, "-persistence_alpha", alpha); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { PCL_INFO("PointXYZRGBA mode enabled.\n"); OpenNIFeaturePersistence v( - subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg); + subsampling_leaf_size, normal_search_radius, scales_vector, alpha, device_id); v.run(); } else { PCL_INFO("PointXYZ mode enabled.\n"); OpenNIFeaturePersistence v( - subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg); + subsampling_leaf_size, normal_search_radius, scales_vector, alpha, device_id); v.run(); } diff --git a/apps/src/openni_grab_images.cpp b/apps/src/openni_grab_images.cpp index 68503d9df8c..3d1dc8ba9e3 100644 --- a/apps/src/openni_grab_images.cpp +++ b/apps/src/openni_grab_images.cpp @@ -360,13 +360,15 @@ main(int argc, char** argv) std::string device_id(""); pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode; + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { + usage(argv); + return 1; + } + if (argc >= 2) { device_id = argv[1]; - if (device_id == "--help" || device_id == "-h") { - usage(argv); - return 0; - } - else if (device_id == "-l") { + if (device_id == "-l") { if (argc >= 3) { pcl::OpenNIGrabber grabber(argv[2]); auto device = grabber.getDevice(); diff --git a/apps/src/openni_ii_normal_estimation.cpp b/apps/src/openni_ii_normal_estimation.cpp index ea918916989..942447f35b2 100644 --- a/apps/src/openni_ii_normal_estimation.cpp +++ b/apps/src/openni_ii_normal_estimation.cpp @@ -34,6 +34,7 @@ */ #include +#include #include #include #include @@ -190,19 +191,29 @@ class OpenNIIntegralImageNormalEstimation { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " []\n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -211,16 +222,19 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); - if (arg == "--help" || arg == "-h" || driver.getNumberDevices() == 0) { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + // clang-format off std::cout << "Press following keys to switch to the different integral image normal estimation methods:\n"; std::cout << "<1> COVARIANCE_MATRIX method\n"; @@ -230,15 +244,15 @@ main(int argc, char** argv) std::cout << " quit\n\n"; // clang-format on - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { PCL_INFO("PointXYZRGBA mode enabled.\n"); - OpenNIIntegralImageNormalEstimation v(arg); + OpenNIIntegralImageNormalEstimation v(device_id); v.run(); } else { PCL_INFO("PointXYZ mode enabled.\n"); - OpenNIIntegralImageNormalEstimation v(arg); + OpenNIIntegralImageNormalEstimation v(device_id); v.run(); } diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index 6bab5e4e972..41b5f81c067 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -312,12 +312,14 @@ main(int argc, char** argv) pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode; bool xyz = false; + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { + printHelp(argc, argv); + return 1; + } + if (argc >= 2) { device_id = argv[1]; - if (device_id == "--help" || device_id == "-h") { - printHelp(argc, argv); - return 0; - } if (device_id == "-l") { if (argc >= 3) { pcl::OpenNIGrabber grabber(argv[2]); diff --git a/apps/src/openni_mls_smoothing.cpp b/apps/src/openni_mls_smoothing.cpp index c45514323c5..641c341c745 100644 --- a/apps/src/openni_mls_smoothing.cpp +++ b/apps/src/openni_mls_smoothing.cpp @@ -177,24 +177,35 @@ void usage(char** argv) { // clang-format off - std::cout << "usage: " << argv[0] << " \n\n" + std::cout << "usage: " << argv[0] << " [options]\n\n" << "where options are:\n" - << " -search_radius X = sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n" - << " -sqr_gauss_param X = parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n" - << " -polynomial_order X = order of the polynomial to be fit (0 means tangent estimation) (default: " << default_polynomial_order << ")\n"; + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -search_radius X: sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n" + << " -sqr_gauss_param X: parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n" + << " -polynomial_order X: order of the polynomial to be fit (0 means tangent estimation) (default: " << default_polynomial_order << ")\n\n"; // clang-format on openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -203,39 +214,44 @@ usage(char** argv) int main(int argc, char** argv) { - if (argc < 2) { - usage(argv); - return 1; - } - - std::string arg(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } - // Command line parsing + std::string device_id = ""; double search_radius = default_search_radius; double sqr_gauss_param = default_sqr_gauss_param; bool sqr_gauss_param_set = true; int polynomial_order = default_polynomial_order; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; pcl::console::parse_argument(argc, argv, "-search_radius", search_radius); if (pcl::console::parse_argument(argc, argv, "-sqr_gauss_param", sqr_gauss_param) == -1) sqr_gauss_param_set = false; pcl::console::parse_argument(argc, argv, "-polynomial_order", polynomial_order); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { - OpenNISmoothing v( - search_radius, sqr_gauss_param_set, sqr_gauss_param, polynomial_order, arg); + OpenNISmoothing v(search_radius, + sqr_gauss_param_set, + sqr_gauss_param, + polynomial_order, + device_id); v.run(); } else { - OpenNISmoothing v( - search_radius, sqr_gauss_param_set, sqr_gauss_param, polynomial_order, arg); + OpenNISmoothing v(search_radius, + sqr_gauss_param_set, + sqr_gauss_param, + polynomial_order, + device_id); v.run(); } diff --git a/apps/src/openni_mobile_server.cpp b/apps/src/openni_mobile_server.cpp index e4440dcd0f0..bf6778d1ff5 100644 --- a/apps/src/openni_mobile_server.cpp +++ b/apps/src/openni_mobile_server.cpp @@ -221,29 +221,33 @@ class PCLMobileServer { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n" + std::cout << "usage: " << argv[0] << " [options]\n\n" << "where options are:\n" - << " -port p :: set the server port (default: 11111)\n" - << " -leaf x, y, z :: set the voxel grid leaf size (default: 0.01)\n"; + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -port p: set the server port (default: 11111)\n" + << " -leaf x, y, z: set the voxel grid leaf size (default: 0.01)\n"; } int main(int argc, char** argv) { - std::string device_id = ""; - if ((argc > 1) && (argv[1][0] != '-')) - device_id = std::string(argv[1]); - - if (pcl::console::find_argument(argc, argv, "-h") != -1) { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); - return 0; + return 1; } + std::string device_id = ""; int port = 11111; float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; pcl::console::parse_argument(argc, argv, "-port", port); pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z, false); + ///////////////////////////////////////////////////////////////////// pcl::OpenNIGrabber grabber(device_id); if (!grabber.providesCallback()) { diff --git a/apps/src/openni_organized_edge_detection.cpp b/apps/src/openni_organized_edge_detection.cpp index 1fc6aee478a..0042f36ffcb 100644 --- a/apps/src/openni_organized_edge_detection.cpp +++ b/apps/src/openni_organized_edge_detection.cpp @@ -34,6 +34,7 @@ */ #include +#include #include #include #include @@ -286,19 +287,29 @@ class OpenNIOrganizedEdgeDetection { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n"; + std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -307,15 +318,19 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg; - if (argc > 1) - arg = std::string(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + ///////////////////////////////////////////////////////////////////// + // clang-format off std::cout << "Press following keys to enable/disable the different edge types:" << std::endl; std::cout << "<1> EDGELABEL_NAN_BOUNDARY edge" << std::endl; @@ -325,7 +340,7 @@ main(int argc, char** argv) //std::cout << "<5> EDGELABEL_RGB_CANNY edge" << std::endl; std::cout << " quit" << std::endl; // clang-format on - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { OpenNIOrganizedEdgeDetection app; app.run(); diff --git a/apps/src/openni_planar_convex_hull.cpp b/apps/src/openni_planar_convex_hull.cpp index fab465bcf93..d42481a2caa 100644 --- a/apps/src/openni_planar_convex_hull.cpp +++ b/apps/src/openni_planar_convex_hull.cpp @@ -150,9 +150,11 @@ class OpenNIPlanarSegmentation { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n" - << "where options are:\n -thresh X :: set the planar " - "segmentation threshold (default: 0.5)\n"; + std::cout + << "usage: " << argv[0] << " [options]\n\n" + << "where options are:\n" + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -thresh X: set the planar segmentation threshold (default: 0.5)\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { @@ -165,6 +167,16 @@ usage(char** argv) << " (only in Linux and for devices which provide serial numbers)" << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -173,28 +185,29 @@ usage(char** argv) int main(int argc, char** argv) { - if (argc < 2) { - usage(argv); - return 1; - } - - std::string arg(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; double threshold = 0.05; + + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; pcl::console::parse_argument(argc, argv, "-thresh", threshold); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { - OpenNIPlanarSegmentation v(arg, threshold); + OpenNIPlanarSegmentation v(device_id, threshold); v.run(); } else { - OpenNIPlanarSegmentation v(arg, threshold); + OpenNIPlanarSegmentation v(device_id, threshold); v.run(); } diff --git a/apps/src/openni_planar_segmentation.cpp b/apps/src/openni_planar_segmentation.cpp index cb9afd704be..d06d4fde3b0 100644 --- a/apps/src/openni_planar_segmentation.cpp +++ b/apps/src/openni_planar_segmentation.cpp @@ -143,21 +143,33 @@ class OpenNIPlanarSegmentation { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n" - << "where options are:\n -thresh X :: set the planar " - "segmentation threshold (default: 0.5)\n"; + std::cout + << "usage: " << argv[0] << " [options]\n\n" + << "where options are:\n" + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -thresh X: set the planar segmentation threshold (default: 0.5)\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -166,28 +178,29 @@ usage(char** argv) int main(int argc, char** argv) { - if (argc < 2) { - usage(argv); - return 1; - } - - std::string arg(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; double threshold = 0.05; + + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; pcl::console::parse_argument(argc, argv, "-thresh", threshold); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { - OpenNIPlanarSegmentation v(arg, threshold); + OpenNIPlanarSegmentation v(device_id, threshold); v.run(); } else { - OpenNIPlanarSegmentation v(arg, threshold); + OpenNIPlanarSegmentation v(device_id, threshold); v.run(); } diff --git a/apps/src/openni_tracking.cpp b/apps/src/openni_tracking.cpp index 1ea742c688f..174f889a19c 100644 --- a/apps/src/openni_tracking.cpp +++ b/apps/src/openni_tracking.cpp @@ -646,46 +646,49 @@ class OpenNISegmentTracking { void usage(char** argv) { - // clang-format off - std::cout << "usage: " << argv[0] << " [-C] [-g]\n\n"; - std::cout << " -C: initialize the pointcloud to track without plane segmentation\n"; - std::cout << " -D: visualizing with non-downsampled pointclouds.\n"; - std::cout << " -P: not visualizing particle cloud.\n"; - std::cout << " -fixed: use the fixed number of the particles.\n"; - std::cout << " -d : specify the grid size of downsampling (defaults to 0.01)." << std::endl; - // clang-format on + // clang format off + std::cout + << "usage: " << argv[0] << " [options]\n\n" + << "where options are:\n" + << " -device_id device_id: specify the device id (defaults to \"#1\").\n" + << " -C: initialize the pointcloud to track without plane segmentation.\n" + << " -D: visualizing with non-downsampled pointclouds.\n" + << " -P: not visualizing particle cloud.\n" + << " -fixed: use the fixed number of the particles.\n" + << " -d: specify the grid size of downsampling (defaults to 0.01)."; + // clang format on } int main(int argc, char** argv) { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { + usage(argv); + return 1; + } + + std::string device_id = ""; bool use_convex_hull = true; bool visualize_non_downsample = false; bool visualize_particles = true; bool use_fixed = false; - double downsampling_grid_size = 0.01; - if (pcl::console::find_argument(argc, argv, "-C") > 0) + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + if (pcl::console::find_argument(argc, argv, "-C") != -1) use_convex_hull = false; - if (pcl::console::find_argument(argc, argv, "-D") > 0) + if (pcl::console::find_argument(argc, argv, "-D") != -1) visualize_non_downsample = true; - if (pcl::console::find_argument(argc, argv, "-P") > 0) + if (pcl::console::find_argument(argc, argv, "-P") != -1) visualize_particles = false; - if (pcl::console::find_argument(argc, argv, "-fixed") > 0) + if (pcl::console::find_argument(argc, argv, "-fixed") != -1) use_fixed = true; pcl::console::parse_argument(argc, argv, "-d", downsampling_grid_size); - if (argc < 2) { - usage(argv); - exit(1); - } - - std::string device_id = std::string(argv[1]); - - if (device_id == "--help" || device_id == "-h") { - usage(argv); - exit(1); - } + ///////////////////////////////////////////////////////////////////// // open kinect OpenNISegmentTracking v(device_id, diff --git a/apps/src/openni_uniform_sampling.cpp b/apps/src/openni_uniform_sampling.cpp index fbce9edc772..6167cdacb3c 100644 --- a/apps/src/openni_uniform_sampling.cpp +++ b/apps/src/openni_uniform_sampling.cpp @@ -147,22 +147,32 @@ class OpenNIUniformSampling { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n" + std::cout << "usage: " << argv[0] << " [options]\n\n" << "where options are:\n" - << " -leaf X :: set the UniformSampling leaf " - "size (default: 0.01)\n"; + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -leaf X: set the UniformSampling leaf size (default: 0.01)\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -171,24 +181,24 @@ usage(char** argv) int main(int argc, char** argv) { - if (argc < 2) { - usage(argv); - return 1; - } - - std::string arg(argv[1]); - - if (arg == "--help" || arg == "-h") { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; float leaf_res = 0.05f; + + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; pcl::console::parse_argument(argc, argv, "-leaf", leaf_res); PCL_INFO("Using %f as a leaf size for UniformSampling.\n", leaf_res); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); - OpenNIUniformSampling v(arg, leaf_res); + OpenNIUniformSampling v(device_id, leaf_res); v.run(); return 0; diff --git a/apps/src/openni_voxel_grid.cpp b/apps/src/openni_voxel_grid.cpp index 91274e7312e..27749cbe325 100644 --- a/apps/src/openni_voxel_grid.cpp +++ b/apps/src/openni_voxel_grid.cpp @@ -141,26 +141,37 @@ class OpenNIVoxelGrid { void usage(char** argv) { - std::cout << "usage: " << argv[0] << " \n\n" - << "where options are:\n -minmax min-max :: set the " - "ApproximateVoxelGrid min-max cutting values (default: 0-5.0)\n" - << " -field X :: use field/dimension 'X' to filter data on " - "(default: 'z')\n" - - << " -leaf x, y, z :: set the " - "ApproximateVoxelGrid leaf size (default: 0.01)\n"; + std::cout + << "usage: " << argv[0] << " [options]\n\n" + << "where options are:\n" + << " -device_id X: specify the device id (default: \"#1\").\n" + << " -minmax min-max: set the ApproximateVoxelGrid min-max cutting values " + "(default: 0-5.0)\n" + << " -field X: use field/dimension 'X' to filter data on (default: 'z')\n" + << " -leaf x, y, z: set the ApproximateVoxelGrid leaf size (default: " + "0.01)\n\n"; openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance(); if (driver.getNumberDevices() > 0) { for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { // clang-format off - std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx) - << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl; - std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl - << " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl - << " (only in Linux and for devices which provide serial numbers)" << std::endl; + std::cout << "Device: " << deviceIdx + 1 + << ", vendor: " << driver.getVendorName (deviceIdx) + << ", product: " << driver.getProductName (deviceIdx) + << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" + << std::endl; // clang-format on } + + std::cout << "\ndevice_id may be:" << std::endl + << " #1, #2, ... for the first second etc device in the list or" + << std::endl + + << " bus@address for the device connected to a specific " + "usb-bus/address combination (works only in Linux) or" + + << " (only in Linux and for devices which provide " + "serial numbers)"; } else std::cout << "No devices connected." << std::endl; @@ -169,34 +180,40 @@ usage(char** argv) int main(int argc, char** argv) { - std::string arg = ""; - if ((argc > 1) && (argv[1][0] != '-')) - arg = std::string(argv[1]); - - if (pcl::console::find_argument(argc, argv, "-h") != -1) { + ///////////////////////////////////////////////////////////////////// + if (pcl::console::find_argument(argc, argv, "-h") != -1 || + pcl::console::find_argument(argc, argv, "--help") != -1) { usage(argv); return 1; } + std::string device_id = ""; float min_v = 0.0f, max_v = 5.0f; + std::string field_name = "z"; + float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f; + + if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 && + argc > 1 && argv[1][0] != '-') + device_id = argv[1]; + pcl::console::parse_2x_arguments(argc, argv, "-minmax", min_v, max_v); - std::string field_name("z"); pcl::console::parse_argument(argc, argv, "-field", field_name); PCL_INFO( "Filtering data on %s between %f -> %f.\n", field_name.c_str(), min_v, max_v); - float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f; + pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z); PCL_INFO("Using %f, %f, %f as a leaf size for VoxelGrid.\n", leaf_x, leaf_y, leaf_z); + ///////////////////////////////////////////////////////////////////// - pcl::OpenNIGrabber grabber(arg); + pcl::OpenNIGrabber grabber(device_id); if (grabber.providesCallback()) { OpenNIVoxelGrid v( - arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z); + device_id, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z); v.run(); } else { OpenNIVoxelGrid v( - arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z); + device_id, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z); v.run(); } From 4f5dedb171c3be7da29651c0ef50fad105b8eb19 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Wed, 1 Feb 2023 12:18:12 -0800 Subject: [PATCH 040/288] Added readability-container-data-pointer clang-tidy check (#5588) * Added readability-container-data-pointer clang-tidy check Removed extraneous parentheses left from conversion to data() Removed extraneous conversion to data() Disabled clang-tidy for more Eigen::Vector4f Fixed typo in NOLINTEND Fixed another Eigen::Vector4f clang-tidy escape Added more NOLINT for readability-container-data-pointer check * Revised per review * Consolidated duplicated code per review --- .clang-tidy | 1 + .../include/pcl/common/impl/intersections.hpp | 4 +- common/include/pcl/common/impl/io.hpp | 16 +++---- common/src/range_image.cpp | 2 +- .../include/pcl/features/impl/brisk_2d.hpp | 8 ++-- .../pcl/features/impl/integral_image2D.hpp | 12 +++--- filters/src/passthrough.cpp | 4 +- filters/src/voxel_grid.cpp | 4 +- .../compression/impl/entropy_range_coder.hpp | 6 +-- .../impl/organized_pointcloud_compression.hpp | 16 +++---- io/include/pcl/io/impl/lzf_image_io.hpp | 16 +++---- .../io/impl/point_cloud_image_extractors.hpp | 4 +- io/src/ascii_io.cpp | 2 +- io/src/ifs_io.cpp | 11 ++--- io/src/libpng_wrapper.cpp | 2 +- io/src/lzf_image_io.cpp | 12 +++--- io/src/pcd_io.cpp | 10 ++--- io/src/png_io.cpp | 10 ++--- io/src/vtk_lib_io.cpp | 2 +- .../include/pcl/kdtree/impl/kdtree_flann.hpp | 8 ++-- keypoints/src/agast_2d.cpp | 8 ++-- keypoints/src/brisk_2d.cpp | 42 +++++++++---------- .../pcl/recognition/color_gradient_modality.h | 2 +- .../include/pcl/recognition/distance_map.h | 2 +- .../recognition/impl/implicit_shape_model.hpp | 4 +- .../include/pcl/recognition/quantized_map.h | 4 +- recognition/src/dotmod.cpp | 2 +- .../face_detector_data_provider.cpp | 12 +++--- .../rf_face_detector_trainer.cpp | 12 +++--- .../include/pcl/registration/impl/ia_fpcs.hpp | 2 +- .../include/pcl/registration/impl/icp.hpp | 2 + .../pcl/registration/impl/registration.hpp | 4 +- .../correspondence_rejection_var_trimmed.cpp | 2 +- .../include/pcl/search/impl/flann_search.hpp | 2 +- .../segmentation/impl/sac_segmentation.hpp | 4 +- simulation/src/model.cpp | 4 +- simulation/src/range_likelihood.cpp | 2 +- surface/src/vtk_smoothing/vtk_utils.cpp | 2 +- test/common/test_plane_intersection.cpp | 4 +- test/io/test_ply_io.cpp | 2 +- test/io/test_ply_mesh_io.cpp | 2 +- test/io/test_point_cloud_image_extractors.cpp | 12 +++--- tools/openni_image.cpp | 6 +-- .../include/pcl/visualization/pcl_painter2D.h | 8 ++-- visualization/src/pcl_plotter.cpp | 4 +- visualization/src/vtk/pcl_context_item.cpp | 8 ++-- 46 files changed, 154 insertions(+), 154 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index ca88077447b..fb4b590a1b4 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -23,6 +23,7 @@ Checks: > performance-no-automatic-move, performance-noexcept-move-constructor, performance-type-promotion-in-math-fn, + readability-container-data-pointer, readability-container-size-empty, readability-delete-null-pointer, readability-duplicate-include, diff --git a/common/include/pcl/common/impl/intersections.hpp b/common/include/pcl/common/impl/intersections.hpp index ba7686ed792..75bbf74f77c 100644 --- a/common/include/pcl/common/impl/intersections.hpp +++ b/common/include/pcl/common/impl/intersections.hpp @@ -70,8 +70,8 @@ lineWithLineIntersection (const pcl::ModelCoefficients &line_a, const pcl::ModelCoefficients &line_b, Eigen::Vector4f &point, double sqr_eps) { - Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a.values[0], line_a.values.size ()); - Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b.values[0], line_b.values.size ()); + Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (line_a.values.data(), line_a.values.size ()); + Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (line_b.values.data(), line_b.values.size ()); return (lineWithLineIntersection (coeff1, coeff2, point, sqr_eps)); } diff --git a/common/include/pcl/common/impl/io.hpp b/common/include/pcl/common/impl/io.hpp index be77397dab3..aa40a9a4f7a 100644 --- a/common/include/pcl/common/impl/io.hpp +++ b/common/include/pcl/common/impl/io.hpp @@ -133,7 +133,7 @@ namespace detail 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]); + std::copy (cloud_in.data(), cloud_in.data() + cloud_in.size (), cloud_out.data()); } } // namespace detail @@ -360,8 +360,8 @@ copyPointCloud (const pcl::PointCloud &cloud_in, pcl::PointCloud if (border_type == pcl::BORDER_TRANSPARENT) { - const PointT* in = &(cloud_in[0]); - PointT* out = &(cloud_out[0]); + const PointT* in = cloud_in.data(); + PointT* out = cloud_out.data(); PointT* out_inner = out + cloud_out.width*top + left; for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) { @@ -387,8 +387,8 @@ copyPointCloud (const pcl::PointCloud &cloud_in, pcl::PointCloud for (int i = 0; i < right; i++) padding[i+left] = pcl::interpolatePointIndex (cloud_in.width+i, cloud_in.width, border_type); - const PointT* in = &(cloud_in[0]); - PointT* out = &(cloud_out[0]); + const PointT* in = cloud_in.data(); + PointT* out = cloud_out.data(); PointT* out_inner = out + cloud_out.width*top + left; for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) @@ -428,9 +428,9 @@ copyPointCloud (const pcl::PointCloud &cloud_in, pcl::PointCloud int right = cloud_out.width - cloud_in.width - left; int bottom = cloud_out.height - cloud_in.height - top; std::vector buff (cloud_out.width, value); - PointT* buff_ptr = &(buff[0]); - const PointT* in = &(cloud_in[0]); - PointT* out = &(cloud_out[0]); + PointT* buff_ptr = buff.data(); + const PointT* in = cloud_in.data(); + PointT* out = cloud_out.data(); PointT* out_inner = out + cloud_out.width*top + left; for (std::uint32_t i = 0; i < cloud_in.height; i++, out_inner += cloud_out.width, in += cloud_in.width) diff --git a/common/src/range_image.cpp b/common/src/range_image.cpp index f94221408f1..89455135aad 100644 --- a/common/src/range_image.cpp +++ b/common/src/range_image.cpp @@ -826,7 +826,7 @@ RangeImage::extractFarRanges (const pcl::PCLPointCloud2& point_cloud_data, } int point_step = point_cloud_data.point_step; - const unsigned char* data = &point_cloud_data.data[0]; + const unsigned char* data = point_cloud_data.data.data(); int x_offset = point_cloud_data.fields[x_idx].offset, y_offset = point_cloud_data.fields[y_idx].offset, z_offset = point_cloud_data.fields[z_idx].offset, diff --git a/features/include/pcl/features/impl/brisk_2d.hpp b/features/include/pcl/features/impl/brisk_2d.hpp index 1897bc3e08b..d067e0c5608 100644 --- a/features/include/pcl/features/impl/brisk_2d.hpp +++ b/features/include/pcl/features/impl/brisk_2d.hpp @@ -249,7 +249,7 @@ BRISK2DEstimation::smoothedIntensity const int r_y_1 = (1024 - r_y); //+const unsigned char* ptr = static_cast (&image[0].r) + x + y * imagecols; - const unsigned char* ptr = static_cast(&image[0]) + x + y * imagecols; + const unsigned char* ptr = static_cast(image.data()) + x + y * imagecols; // just interpolate: ret_val = (r_x_1 * r_y_1 * static_cast(*ptr)); @@ -312,7 +312,7 @@ BRISK2DEstimation::smoothedIntensity // now the calculation: //+const unsigned char* ptr = static_cast (&image[0].r) + x_left + imagecols * y_top; - const unsigned char* ptr = static_cast(&image[0]) + x_left + imagecols * y_top; + const unsigned char* ptr = static_cast(image.data()) + x_left + imagecols * y_top; // first the corners: ret_val = A * static_cast(*ptr); @@ -334,7 +334,7 @@ BRISK2DEstimation::smoothedIntensity // next the edges: //+int* ptr_integral;// = static_cast (integral.data) + x_left + integralcols * y_top + 1; - const int* ptr_integral = static_cast (&integral_image[0]) + x_left + integralcols * y_top + 1; + const int* ptr_integral = static_cast (integral_image.data()) + x_left + integralcols * y_top + 1; // find a simple path through the different surface corners const int tmp1 = (*ptr_integral); @@ -374,7 +374,7 @@ BRISK2DEstimation::smoothedIntensity // now the calculation: //const unsigned char* ptr = static_cast (&image[0].r) + x_left + imagecols * y_top; - const unsigned char* ptr = static_cast(&image[0]) + x_left + imagecols * y_top; + const unsigned char* ptr = static_cast(image.data()) + x_left + imagecols * y_top; // first row: ret_val = A * static_cast(*ptr); diff --git a/features/include/pcl/features/impl/integral_image2D.hpp b/features/include/pcl/features/impl/integral_image2D.hpp index 4fd45947b39..88902cf6ddc 100644 --- a/features/include/pcl/features/impl/integral_image2D.hpp +++ b/features/include/pcl/features/impl/integral_image2D.hpp @@ -156,12 +156,12 @@ template void IntegralImage2D::computeIntegralImages ( const DataType *data, unsigned row_stride, unsigned element_stride) { - ElementType* previous_row = &first_order_integral_image_[0]; + ElementType* previous_row = first_order_integral_image_.data(); ElementType* current_row = previous_row + (width_ + 1); for (unsigned int i = 0; i < (width_ + 1); ++i) previous_row[i].setZero(); - unsigned* count_previous_row = &finite_values_integral_image_[0]; + unsigned* count_previous_row = finite_values_integral_image_.data(); unsigned* count_current_row = count_previous_row + (width_ + 1); std::fill_n(count_previous_row, width_ + 1, 0); @@ -188,7 +188,7 @@ IntegralImage2D::computeIntegralImages ( } else { - SecondOrderType* so_previous_row = &second_order_integral_image_[0]; + SecondOrderType* so_previous_row = second_order_integral_image_.data(); SecondOrderType* so_current_row = so_previous_row + (width_ + 1); for (unsigned int i = 0; i < (width_ + 1); ++i) so_previous_row[i].setZero(); @@ -327,11 +327,11 @@ template void IntegralImage2D::computeIntegralImages ( const DataType *data, unsigned row_stride, unsigned element_stride) { - ElementType* previous_row = &first_order_integral_image_[0]; + ElementType* previous_row = first_order_integral_image_.data(); ElementType* current_row = previous_row + (width_ + 1); std::fill_n(previous_row, width_ + 1, 0); - unsigned* count_previous_row = &finite_values_integral_image_[0]; + unsigned* count_previous_row = finite_values_integral_image_.data(); unsigned* count_current_row = count_previous_row + (width_ + 1); std::fill_n(count_previous_row, width_ + 1, 0); @@ -357,7 +357,7 @@ IntegralImage2D::computeIntegralImages ( } else { - SecondOrderType* so_previous_row = &second_order_integral_image_[0]; + SecondOrderType* so_previous_row = second_order_integral_image_.data(); SecondOrderType* so_current_row = so_previous_row + (width_ + 1); std::fill_n(so_previous_row, width_ + 1, 0); diff --git a/filters/src/passthrough.cpp b/filters/src/passthrough.cpp index c8fdd255e0f..c56a285a0f5 100644 --- a/filters/src/passthrough.cpp +++ b/filters/src/passthrough.cpp @@ -217,7 +217,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) } // Unoptimized memcpys: assume fields x, y, z are in random order - memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); + memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer) memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float)); memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float)); @@ -245,7 +245,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) { // Unoptimized memcpys: assume fields x, y, z are in random order - memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); + memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer) memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof(float)); memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof(float)); diff --git a/filters/src/voxel_grid.cpp b/filters/src/voxel_grid.cpp index b926499fab4..2a3ab968bfd 100644 --- a/filters/src/voxel_grid.cpp +++ b/filters/src/voxel_grid.cpp @@ -45,7 +45,7 @@ #include using Array4size_t = Eigen::Array; - +// NOLINTBEGIN(readability-container-data-pointer) /////////////////////////////////////////////////////////////////////////////////////////// void pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, @@ -525,7 +525,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) ++index; } } - +// NOLINTEND(readability-container-data-pointer) #ifndef PCL_NO_PRECOMPILE #include #include diff --git a/io/include/pcl/compression/impl/entropy_range_coder.hpp b/io/include/pcl/compression/impl/entropy_range_coder.hpp index be1190fddb3..8300722e0fe 100644 --- a/io/include/pcl/compression/impl/entropy_range_coder.hpp +++ b/io/include/pcl/compression/impl/entropy_range_coder.hpp @@ -119,7 +119,7 @@ pcl::AdaptiveRangeCoder::encodeCharVectorToStream (const std::vector& inpu } // write to stream - outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ()); return (static_cast (outputCharVector_.size ())); } @@ -340,7 +340,7 @@ pcl::StaticRangeCoder::encodeIntVectorToStream (std::vector& input } // write encoded data to stream - outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ()); streamByteCount += static_cast (outputCharVector_.size ()); @@ -528,7 +528,7 @@ pcl::StaticRangeCoder::encodeCharVectorToStream (const std::vector& inputB } // write encoded data to stream - outputByteStream_arg.write (&outputCharVector_[0], outputCharVector_.size ()); + outputByteStream_arg.write (outputCharVector_.data(), outputCharVector_.size ()); streamByteCount += static_cast (outputCharVector_.size ()); diff --git a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp index f86425e2ab4..4072e574012 100644 --- a/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp +++ b/io/include/pcl/compression/impl/organized_pointcloud_compression.hpp @@ -109,7 +109,7 @@ namespace pcl // Encode size of compressed disparity image data compressedDataOut_arg.write (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); // Output compressed disparity to ostream - compressedDataOut_arg.write (reinterpret_cast (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t)); + compressedDataOut_arg.write (reinterpret_cast (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t)); // Compress color information if (CompressionPointTraits::hasColor && doColorEncoding) @@ -127,7 +127,7 @@ namespace pcl // Encode size of compressed Color image data compressedDataOut_arg.write (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); // Output compressed disparity to ostream - compressedDataOut_arg.write (reinterpret_cast (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t)); + compressedDataOut_arg.write (reinterpret_cast (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t)); if (bShowStatistics_arg) { @@ -194,8 +194,8 @@ namespace pcl std::uint32_t compressedColorSize = 0; // Remove color information of invalid points - std::uint16_t* depth_ptr = &disparityMap_arg[0]; - std::uint8_t* color_ptr = &colorImage_arg[0]; + std::uint16_t* depth_ptr = disparityMap_arg.data(); + std::uint8_t* color_ptr = colorImage_arg.data(); for (std::size_t i = 0; i < cloud_size; ++i, ++depth_ptr, color_ptr += sizeof(std::uint8_t) * 3) { @@ -211,7 +211,7 @@ namespace pcl // Encode size of compressed disparity image data compressedDataOut_arg.write (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); // Output compressed disparity to ostream - compressedDataOut_arg.write (reinterpret_cast (&compressedDisparity[0]), compressedDisparity.size () * sizeof(std::uint8_t)); + compressedDataOut_arg.write (reinterpret_cast (compressedDisparity.data()), compressedDisparity.size () * sizeof(std::uint8_t)); // Compress color information if (!colorImage_arg.empty () && doColorEncoding) @@ -244,7 +244,7 @@ namespace pcl // Encode size of compressed Color image data compressedDataOut_arg.write (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); // Output compressed disparity to ostream - compressedDataOut_arg.write (reinterpret_cast (&compressedColor[0]), compressedColor.size () * sizeof(std::uint8_t)); + compressedDataOut_arg.write (reinterpret_cast (compressedColor.data()), compressedColor.size () * sizeof(std::uint8_t)); if (bShowStatistics_arg) { @@ -320,12 +320,12 @@ namespace pcl // reading compressed disparity data compressedDataIn_arg.read (reinterpret_cast (&compressedDisparitySize), sizeof (compressedDisparitySize)); compressedDisparity.resize (compressedDisparitySize); - compressedDataIn_arg.read (reinterpret_cast (&compressedDisparity[0]), compressedDisparitySize * sizeof(std::uint8_t)); + compressedDataIn_arg.read (reinterpret_cast (compressedDisparity.data()), compressedDisparitySize * sizeof(std::uint8_t)); // reading compressed rgb data compressedDataIn_arg.read (reinterpret_cast (&compressedColorSize), sizeof (compressedColorSize)); compressedColor.resize (compressedColorSize); - compressedDataIn_arg.read (reinterpret_cast (&compressedColor[0]), compressedColorSize * sizeof(std::uint8_t)); + compressedDataIn_arg.read (reinterpret_cast (compressedColor.data()), compressedColorSize * sizeof(std::uint8_t)); std::size_t png_width = 0; std::size_t png_height = 0; diff --git a/io/include/pcl/io/impl/lzf_image_io.hpp b/io/include/pcl/io/impl/lzf_image_io.hpp index 294ce4f1d16..5e4e4ce50fc 100644 --- a/io/include/pcl/io/impl/lzf_image_io.hpp +++ b/io/include/pcl/io/impl/lzf_image_io.hpp @@ -236,7 +236,7 @@ LZFRGB24ImageReader::read ( cloud.resize (getWidth () * getHeight ()); int rgb_idx = 0; - auto *color_r = reinterpret_cast (&uncompressed_data[0]); + auto *color_r = reinterpret_cast (uncompressed_data.data()); auto *color_g = reinterpret_cast (&uncompressed_data[getWidth () * getHeight ()]); auto *color_b = reinterpret_cast (&uncompressed_data[2 * getWidth () * getHeight ()]); @@ -284,7 +284,7 @@ LZFRGB24ImageReader::readOMP ( cloud.height = getHeight (); cloud.resize (getWidth () * getHeight ()); - auto *color_r = reinterpret_cast (&uncompressed_data[0]); + auto *color_r = reinterpret_cast (uncompressed_data.data()); auto *color_g = reinterpret_cast (&uncompressed_data[getWidth () * getHeight ()]); auto *color_b = reinterpret_cast (&uncompressed_data[2 * getWidth () * getHeight ()]); @@ -341,7 +341,7 @@ LZFYUV422ImageReader::read ( cloud.resize (getWidth () * getHeight ()); int wh2 = getWidth () * getHeight () / 2; - auto *color_u = reinterpret_cast (&uncompressed_data[0]); + auto *color_u = reinterpret_cast (uncompressed_data.data()); auto *color_y = reinterpret_cast (&uncompressed_data[wh2]); auto *color_v = reinterpret_cast (&uncompressed_data[wh2 + getWidth () * getHeight ()]); @@ -399,7 +399,7 @@ LZFYUV422ImageReader::readOMP ( cloud.resize (getWidth () * getHeight ()); int wh2 = getWidth () * getHeight () / 2; - auto *color_u = reinterpret_cast (&uncompressed_data[0]); + auto *color_u = reinterpret_cast (uncompressed_data.data()); auto *color_y = reinterpret_cast (&uncompressed_data[wh2]); auto *color_v = reinterpret_cast (&uncompressed_data[wh2 + getWidth () * getHeight ()]); @@ -462,8 +462,8 @@ LZFBayer8ImageReader::read ( // Convert Bayer8 to RGB24 std::vector rgb_buffer (getWidth () * getHeight () * 3); DeBayer i; - i.debayerEdgeAware (reinterpret_cast (&uncompressed_data[0]), - static_cast (&rgb_buffer[0]), + i.debayerEdgeAware (reinterpret_cast (uncompressed_data.data()), + static_cast (rgb_buffer.data()), getWidth (), getHeight ()); // Copy to PointT cloud.width = getWidth (); @@ -512,8 +512,8 @@ LZFBayer8ImageReader::readOMP ( // Convert Bayer8 to RGB24 std::vector rgb_buffer (getWidth () * getHeight () * 3); DeBayer i; - i.debayerEdgeAware (reinterpret_cast (&uncompressed_data[0]), - static_cast (&rgb_buffer[0]), + i.debayerEdgeAware (reinterpret_cast (uncompressed_data.data()), + static_cast (rgb_buffer.data()), getWidth (), getHeight ()); // Copy to PointT cloud.width = getWidth (); diff --git a/io/include/pcl/io/impl/point_cloud_image_extractors.hpp b/io/include/pcl/io/impl/point_cloud_image_extractors.hpp index 9678e9b7366..c5025efe963 100644 --- a/io/include/pcl/io/impl/point_cloud_image_extractors.hpp +++ b/io/include/pcl/io/impl/point_cloud_image_extractors.hpp @@ -154,7 +154,7 @@ pcl::io::PointCloudImageExtractorFromLabelField::extractImpl (const Poin img.height = cloud.height; img.step = img.width * sizeof (unsigned short); img.data.resize (img.step * img.height); - auto* data = reinterpret_cast(&img.data[0]); + auto* data = reinterpret_cast(img.data.data()); for (std::size_t i = 0; i < cloud.size (); ++i) { std::uint32_t val; @@ -255,7 +255,7 @@ pcl::io::PointCloudImageExtractorWithScaling::extractImpl (const PointCl img.height = cloud.height; img.step = img.width * sizeof (unsigned short); img.data.resize (img.step * img.height); - auto* data = reinterpret_cast(&img.data[0]); + auto* data = reinterpret_cast(img.data.data()); float scaling_factor = scaling_factor_; float data_min = 0.0f; diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index 00fd22bf27b..9803c7f3322 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -143,7 +143,7 @@ pcl::ASCIIReader::read ( int total=0; - std::uint8_t* data = &cloud.data[0]; + std::uint8_t* data = cloud.data.data(); while (std::getline (ifile, line)) { boost::algorithm::trim (line); diff --git a/io/src/ifs_io.cpp b/io/src/ifs_io.cpp index 5246b9c7c5f..d3bc8c7a1e4 100644 --- a/io/src/ifs_io.cpp +++ b/io/src/ifs_io.cpp @@ -213,7 +213,7 @@ pcl::IFSReader::read (const std::string &file_name, } // Copy the data - memcpy (&cloud.data[0], mapped_file.data () + data_idx, cloud.data.size ()); + memcpy (cloud.data.data(), mapped_file.data () + data_idx, cloud.data.size ()); mapped_file.close (); @@ -264,7 +264,7 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int } // Copy the data - memcpy (&mesh.cloud.data[0], mapped_file.data () + data_idx, mesh.cloud.data.size ()); + memcpy (mesh.cloud.data.data(), mapped_file.data () + data_idx, mesh.cloud.data.size ()); mapped_file.close (); @@ -308,6 +308,7 @@ pcl::IFSReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, int { pcl::Vertices &facet = mesh.polygons[i]; facet.vertices.resize (3); + // NOLINTNEXTLINE(readability-container-data-pointer) fs.read (reinterpret_cast(&(facet.vertices[0])), sizeof (std::uint32_t)); fs.read (reinterpret_cast(&(facet.vertices[1])), sizeof (std::uint32_t)); fs.read (reinterpret_cast(&(facet.vertices[2])), sizeof (std::uint32_t)); @@ -345,7 +346,7 @@ pcl::IFSWriter::write (const std::string &file_name, const pcl::PCLPointCloud2 & sizeof (std::uint32_t) + cloud_name.size () + 1 + sizeof (std::uint32_t) + vertices.size () + 1 + sizeof (std::uint32_t)); - char* addr = &(header[0]); + char* addr = header.data(); const std::uint32_t magic_size = static_cast (magic.size ()) + 1; memcpy (addr, &magic_size, sizeof (std::uint32_t)); addr+= sizeof (std::uint32_t); @@ -396,10 +397,10 @@ pcl::IFSWriter::write (const std::string &file_name, const pcl::PCLPointCloud2 & } // copy header - memcpy (sink.data (), &header[0], data_idx); + memcpy (sink.data (), header.data(), data_idx); // Copy the data - memcpy (sink.data () + data_idx, &cloud.data[0], cloud.data.size ()); + memcpy (sink.data () + data_idx, cloud.data.data(), cloud.data.size ()); sink.close (); diff --git a/io/src/libpng_wrapper.cpp b/io/src/libpng_wrapper.cpp index f267ed7cc25..ff5cc6ec119 100644 --- a/io/src/libpng_wrapper.cpp +++ b/io/src/libpng_wrapper.cpp @@ -201,7 +201,7 @@ namespace pcl // Setup Exception handling setjmp (png_jmpbuf(png_ptr)); - std::uint8_t* input_pointer = &pngData_arg[0]; + std::uint8_t* input_pointer = pngData_arg.data(); png_set_read_fn (png_ptr, reinterpret_cast (&input_pointer), user_read_data); png_read_info (png_ptr, info_ptr); diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index 78d787ea8fb..4cf8984f344 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -140,7 +140,7 @@ pcl::io::LZFImageWriter::compress (const char* input, if (itype.size () < 16) itype.insert (itype.end (), 16 - itype.size (), ' '); - memcpy (&output[13], &itype[0], 16); + memcpy (&output[13], itype.data(), 16); memcpy (&output[29], &compressed_size, sizeof (std::uint32_t)); memcpy (&output[33], &uncompressed_size, sizeof (std::uint32_t)); compressed_final_size = static_cast(compressed_size + header_size); @@ -238,7 +238,7 @@ pcl::io::LZFRGB24ImageWriter::write (const char *data, } char* compressed_rgb = static_cast (malloc (static_cast(static_cast(rrggbb.size ()) * 1.5f + static_cast(LZF_HEADER_SIZE)))); - std::size_t compressed_size = compress (reinterpret_cast (&rrggbb[0]), + std::size_t compressed_size = compress (reinterpret_cast (rrggbb.data()), static_cast(rrggbb.size ()), width, height, "rgb24", @@ -299,7 +299,7 @@ pcl::io::LZFYUV422ImageWriter::write (const char *data, } char* compressed_yuv = static_cast (malloc (static_cast(static_cast(uuyyvv.size ()) * 1.5f + static_cast(LZF_HEADER_SIZE)))); - std::size_t compressed_size = compress (reinterpret_cast (&uuyyvv[0]), + std::size_t compressed_size = compress (reinterpret_cast (uuyyvv.data()), static_cast(uuyyvv.size ()), width, height, "yuv422", @@ -442,7 +442,7 @@ pcl::io::LZFImageReader::loadImageBlob (const std::string &filename, memcpy (&uncompressed_size, &map[33], sizeof (std::uint32_t)); data.resize (compressed_size); - memcpy (&data[0], &map[header_size], compressed_size); + memcpy (data.data(), &map[header_size], compressed_size); #ifdef _WIN32 UnmapViewOfFile (map); @@ -466,9 +466,9 @@ pcl::io::LZFImageReader::decompress (const std::vector &input, PCL_ERROR ("[pcl::io::LZFImageReader::decompress] Output array needs to be preallocated! The correct uncompressed array value should have been stored during the compression.\n"); return (false); } - unsigned int tmp_size = pcl::lzfDecompress (static_cast(&input[0]), + unsigned int tmp_size = pcl::lzfDecompress (static_cast(input.data()), static_cast(input.size ()), - static_cast(&output[0]), + static_cast(output.data()), static_cast(output.size ())); if (tmp_size != output.size ()) diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index d99392be4e0..49075bcebb7 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -559,7 +559,7 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c auto data_size = static_cast (cloud.data.size ()); std::vector buf (data_size); // The size of the uncompressed data better be the same as what we stored in the header - unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, &buf[0], data_size); + unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, buf.data(), data_size); if (tmp_size != uncompressed_size) { PCL_ERROR ("[pcl::PCDReader::read] Size of decompressed lzf data (%u) does not match value stored in PCD header (%u). Errno: %d\n", tmp_size, uncompressed_size, errno); @@ -604,7 +604,7 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c } else // Copy the data - memcpy (&cloud.data[0], &map[0] + data_idx, cloud.data.size ()); + memcpy ((cloud.data).data(), &map[0] + data_idx, cloud.data.size ()); // Extra checks (not needed for ASCII) int point_size = (cloud.width * cloud.height == 0) ? 0 : static_cast (cloud.data.size () / (cloud.height * cloud.width)); @@ -1259,7 +1259,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl memcpy (&map[0], oss.str().c_str (), static_cast (data_idx)); // Copy the data - memcpy (&map[0] + data_idx, &cloud.data[0], cloud.data.size ()); + memcpy (&map[0] + data_idx, cloud.data.data(), cloud.data.size ()); #ifndef _WIN32 // If the user set the synchronization flag on, call msync @@ -1387,11 +1387,11 @@ pcl::PCDWriter::writeBinaryCompressed (std::ostream &os, const pcl::PCLPointClou { return (-1); } - memcpy (&temp_buf[0], &compressed_size, 4); + memcpy (temp_buf.data(), &compressed_size, 4); memcpy (&temp_buf[4], &data_size, 4); temp_buf.resize (compressed_size + 8); } else { - auto *header = reinterpret_cast(&temp_buf[0]); + auto *header = reinterpret_cast(temp_buf.data()); header[0] = 0; // compressed_size is 0 header[1] = 0; // data_size is 0 } diff --git a/io/src/png_io.cpp b/io/src/png_io.cpp index f8493eade43..4f3b17b6abd 100644 --- a/io/src/png_io.cpp +++ b/io/src/png_io.cpp @@ -103,13 +103,13 @@ pcl::io::saveRgbPNGFile (const std::string& file_name, const unsigned char *rgb_ void pcl::io::savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud) { - saveCharPNGFile(file_name, &cloud[0], cloud.width, cloud.height, 1); + saveCharPNGFile(file_name, cloud.data(), cloud.width, cloud.height, 1); } void pcl::io::savePNGFile (const std::string& file_name, const pcl::PointCloud& cloud) { - saveShortPNGFile(file_name, &cloud[0], cloud.width, cloud.height, 1); + saveShortPNGFile(file_name, cloud.data(), cloud.width, cloud.height, 1); } void @@ -117,15 +117,15 @@ pcl::io::savePNGFile (const std::string& file_name, const pcl::PCLImage& image) { if (image.encoding == "rgb8") { - saveRgbPNGFile(file_name, &image.data[0], image.width, image.height); + saveRgbPNGFile(file_name, image.data.data(), image.width, image.height); } else if (image.encoding == "mono8") { - saveCharPNGFile(file_name, &image.data[0], image.width, image.height, 1); + saveCharPNGFile(file_name, image.data.data(), image.width, image.height, 1); } else if (image.encoding == "mono16") { - saveShortPNGFile(file_name, reinterpret_cast(&image.data[0]), image.width, image.height, 1); + saveShortPNGFile(file_name, reinterpret_cast(image.data.data()), image.width, image.height, 1); } else { diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index f795312f99c..bb5a5cfe041 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -456,7 +456,7 @@ pcl::io::mesh2vtk (const pcl::PolygonMesh& mesh, vtkSmartPointer& p Eigen::Array4i xyz_offset (mesh.cloud.fields[idx_x].offset, mesh.cloud.fields[idx_y].offset, mesh.cloud.fields[idx_z].offset, 0); for (vtkIdType cp = 0; cp < static_cast (nr_points); ++cp, xyz_offset += mesh.cloud.point_step) { - memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof (float)); + memcpy(&pt[0], &mesh.cloud.data[xyz_offset[0]], sizeof (float)); // NOLINT(readability-container-data-pointer) memcpy(&pt[1], &mesh.cloud.data[xyz_offset[1]], sizeof (float)); memcpy(&pt[2], &mesh.cloud.data[xyz_offset[2]], sizeof (float)); vtk_mesh_points->InsertPoint (cp, pt[0], pt[1], pt[2]); diff --git a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp index d276dee8a17..5c777594111 100644 --- a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp +++ b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp @@ -169,7 +169,7 @@ knn_search(A& index, B& query, C& k_indices, D& dists, unsigned int k, F& params std::vector indices(k); k_indices.resize(k); // Wrap indices vector (no data allocation) - ::flann::Matrix indices_mat(&indices[0], 1, k); + ::flann::Matrix indices_mat(indices.data(), 1, k); auto ret = index.knnSearch(query, indices_mat, dists, k, params); // cast appropriately std::transform(indices.cbegin(), @@ -253,10 +253,10 @@ pcl::KdTreeFLANN::nearestKSearch (const PointT &point, unsigned in point_representation_->vectorize (static_cast (point), query); // Wrap the k_distances vector (no data copy) - ::flann::Matrix k_distances_mat (&k_distances[0], 1, k); + ::flann::Matrix k_distances_mat (k_distances.data(), 1, k); knn_search(*flann_index_, - ::flann::Matrix(&query[0], 1, dim_), + ::flann::Matrix(query.data(), 1, dim_), k_indices, k_distances_mat, k, @@ -392,7 +392,7 @@ pcl::KdTreeFLANN::radiusSearch (const PointT &point, double radius else params.max_neighbors = max_nn; - auto query_mat = ::flann::Matrix(&query[0], 1, dim_); + auto query_mat = ::flann::Matrix(query.data(), 1, dim_); int neighbors_in_radius = radius_search(*flann_index_, query_mat, k_indices, diff --git a/keypoints/src/agast_2d.cpp b/keypoints/src/agast_2d.cpp index 541d59698f9..f81fc9198e3 100644 --- a/keypoints/src/agast_2d.cpp +++ b/keypoints/src/agast_2d.cpp @@ -81,7 +81,7 @@ pcl::keypoints::agast::AbstractAgastDetector::detectKeypoints ( const std::vector & intensity_data, pcl::PointCloud &output) const { - detect (&(intensity_data[0]), output.points); + detect (intensity_data.data(), output.points); output.height = 1; output.width = output.size (); @@ -93,7 +93,7 @@ pcl::keypoints::agast::AbstractAgastDetector::detectKeypoints ( const std::vector & intensity_data, pcl::PointCloud &output) const { - detect (&(intensity_data[0]), output.points); + detect (intensity_data.data(), output.points); output.height = 1; output.width = output.size (); @@ -244,7 +244,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression ( pcl::PointCloud &output) { std::vector scores; - computeCornerScores (&(intensity_data[0]), input.points, scores); + computeCornerScores (intensity_data.data(), input.points, scores); // If a threshold for the maximum number of keypoints is given if (nr_max_keypoints_ <= scores.size ()) //std::numeric_limits::max ()) @@ -272,7 +272,7 @@ pcl::keypoints::agast::AbstractAgastDetector::applyNonMaxSuppression ( pcl::PointCloud &output) { std::vector scores; - computeCornerScores (&(intensity_data[0]), input.points, scores); + computeCornerScores (intensity_data.data(), input.points, scores); // If a threshold for the maximum number of keypoints is given if (nr_max_keypoints_ <= scores.size ()) //std::numeric_limits::max ()) diff --git a/keypoints/src/brisk_2d.cpp b/keypoints/src/brisk_2d.cpp index b1da7714112..c836dec780b 100644 --- a/keypoints/src/brisk_2d.cpp +++ b/keypoints/src/brisk_2d.cpp @@ -374,7 +374,7 @@ pcl::keypoints::brisk::ScaleSpace::isMax2D ( { const std::vector& scores = pyramid_[layer].getScores (); const int scorescols = pyramid_[layer].getImageWidth (); - const unsigned char* data = &scores[0] + y_layer * scorescols + x_layer; + const unsigned char* data = scores.data() + y_layer * scorescols + x_layer; // decision tree: const unsigned char center = (*data); @@ -456,7 +456,7 @@ pcl::keypoints::brisk::ScaleSpace::isMax2D ( for (unsigned int i = 0; i < deltasize; i+= 2) { - data = &scores[0] + (y_layer - 1 + delta[i+1]) * scorescols + x_layer + delta[i] - 1; + data = scores.data() + (y_layer - 1 + delta[i+1]) * scorescols + x_layer + delta[i] - 1; int othercenter = *data; data++; @@ -1347,7 +1347,7 @@ pcl::keypoints::brisk::Layer::getAgastPoints ( std::uint8_t threshold, std::vector > &keypoints) { oast_detector_->setThreshold (threshold); - oast_detector_->detect (&img_[0], keypoints); + oast_detector_->detect (img_.data(), keypoints); // also write scores const int num = static_cast(keypoints.size ()); @@ -1356,7 +1356,7 @@ pcl::keypoints::brisk::Layer::getAgastPoints ( for (int i = 0; i < num; i++) { const int offs = static_cast(keypoints[i].u + keypoints[i].v * static_cast(imcols)); - *(&scores_[0] + offs) = static_cast (oast_detector_->computeCornerScore (&img_[0] + offs)); + *((scores_).data() + offs) = static_cast (oast_detector_->computeCornerScore (img_.data() + offs)); } } @@ -1372,13 +1372,13 @@ pcl::keypoints::brisk::Layer::getAgastScore (int x, int y, std::uint8_t threshol { return (0); } - std::uint8_t& score = *(&scores_[0] + x + y * img_width_); + std::uint8_t& score = *(scores_.data() + x + y * img_width_); if (score > 2) { return (score); } oast_detector_->setThreshold (threshold - 1); - score = static_cast(oast_detector_->computeCornerScore (&img_[0] + x + y * img_width_)); + score = static_cast(oast_detector_->computeCornerScore (img_.data() + x + y * img_width_)); if (score < threshold) score = 0; return (score); } @@ -1398,7 +1398,7 @@ pcl::keypoints::brisk::Layer::getAgastScore_5_8 (int x, int y, std::uint8_t thre } agast_detector_5_8_->setThreshold (threshold - 1); - auto score = static_cast(agast_detector_5_8_->computeCornerScore (&img_[0] + x + y * img_width_)); + auto score = static_cast(agast_detector_5_8_->computeCornerScore (img_.data() + x + y * img_width_)); if (score < threshold) score = 0; return (score); } @@ -1465,7 +1465,7 @@ pcl::keypoints::brisk::Layer::getValue ( const int r_y = static_cast ((yf - static_cast(y)) * 1024); const int r_x_1 = (1024 - r_x); const int r_y_1 = (1024 - r_y); - const unsigned char* ptr = &image[0] + x + y * imagecols; + const unsigned char* ptr = image.data() + x + y * imagecols; // just interpolate: ret_val = (r_x_1 * r_y_1 * static_cast(*ptr)); @@ -1512,7 +1512,7 @@ pcl::keypoints::brisk::Layer::getValue ( const int r_y1_i = static_cast (r_y1 * static_cast(scaling)); // now the calculation: - const unsigned char* ptr = &image[0] + x_left + imagecols * y_top; + const unsigned char* ptr = image.data() + x_left + imagecols * y_top; // first row: ret_val = A * static_cast(*ptr); ptr++; @@ -1571,9 +1571,9 @@ pcl::keypoints::brisk::Layer::halfsample ( __m128i mask = _mm_set_epi32 (0x00FF00FF, 0x00FF00FF, 0x00FF00FF, 0x00FF00FF); // data pointers: - const auto* p1 = reinterpret_cast (&srcimg[0]); - const auto* p2 = reinterpret_cast (&srcimg[0] + srcwidth); - auto* p_dest = reinterpret_cast<__m128i*> (&dstimg[0]); + const auto* p1 = reinterpret_cast (srcimg.data()); + const auto* p2 = reinterpret_cast (srcimg.data() + srcwidth); + auto* p_dest = reinterpret_cast<__m128i*> (dstimg.data()); unsigned char* p_dest_char;//=(unsigned char*)p_dest; // size: @@ -1675,8 +1675,8 @@ pcl::keypoints::brisk::Layer::halfsample ( if (noleftover) { row++; - p_dest = reinterpret_cast<__m128i*> (&dstimg[0] + row * dstwidth); - p1 = reinterpret_cast (&srcimg[0] + 2 * row * srcwidth); + p_dest = reinterpret_cast<__m128i*> (dstimg.data() + row * dstwidth); + p1 = reinterpret_cast (srcimg.data() + 2 * row * srcwidth); //p2=(__m128i*)(srcimg.data+(2*row+1)*srcwidth); //p1+=hsize; p2 = p1 + hsize; @@ -1692,9 +1692,9 @@ pcl::keypoints::brisk::Layer::halfsample ( } // done with the two rows: row++; - p_dest = reinterpret_cast<__m128i*> (&dstimg[0] + row * dstwidth); - p1 = reinterpret_cast (&srcimg[0] + 2 * row * srcwidth); - p2 = reinterpret_cast (&srcimg[0] + (2 * row + 1) * srcwidth); + p_dest = reinterpret_cast<__m128i*> (dstimg.data() + row * dstwidth); + p1 = reinterpret_cast (srcimg.data() + 2 * row * srcwidth); + p2 = reinterpret_cast (srcimg.data() + (2 * row + 1) * srcwidth); } } #else @@ -1726,10 +1726,10 @@ pcl::keypoints::brisk::Layer::twothirdsample ( __m128i store_mask = _mm_set_epi8 (0x0,0x0,0x0,0x0,0x0,0x0,static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80),static_cast(0x80)); // data pointers: - const unsigned char* p1 = &srcimg[0]; + const unsigned char* p1 = srcimg.data(); const unsigned char* p2 = p1 + srcwidth; const unsigned char* p3 = p2 + srcwidth; - unsigned char* p_dest1 = &dstimg[0]; + unsigned char* p_dest1 = dstimg.data(); unsigned char* p_dest2 = p_dest1 + dstwidth; const unsigned char* p_end = p1 + (srcwidth * srcheight); @@ -1801,10 +1801,10 @@ pcl::keypoints::brisk::Layer::twothirdsample ( row_dest += 2; // reset pointers - p1 = &srcimg[0] + row * srcwidth; + p1 = srcimg.data() + row * srcwidth; p2 = p1 + srcwidth; p3 = p2 + srcwidth; - p_dest1 = &dstimg[0] + row_dest * dstwidth; + p_dest1 = dstimg.data() + row_dest * dstwidth; p_dest2 = p_dest1 + dstwidth; } #else diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 359d6c4d308..7e5bae23a7d 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -310,7 +310,7 @@ computeGaussianKernel (const std::size_t kernel_size, const float sigma, std::ve //CV_Assert( ktype == CV_32F || ktype == CV_64F ); /*Mat kernel(n, 1, ktype);*/ kernel_values.resize (n); - float* cf = &(kernel_values[0]); + float* cf = kernel_values.data(); //double* cd = (double*)kernel.data; double sigmaX = sigma > 0 ? sigma : ((n-1)*0.5 - 1)*0.3 + 0.8; diff --git a/recognition/include/pcl/recognition/distance_map.h b/recognition/include/pcl/recognition/distance_map.h index 92353f22f1c..d641265125d 100644 --- a/recognition/include/pcl/recognition/distance_map.h +++ b/recognition/include/pcl/recognition/distance_map.h @@ -69,7 +69,7 @@ namespace pcl inline float * getData () { - return (&data_[0]); + return (data_.data()); } /** \brief Resizes the map to the specified size. diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index 3319533e7d6..2e736eb76ba 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -1280,7 +1280,7 @@ pcl::ism::ImplicitShapeModelEstimation::computeKMe Eigen::MatrixXf old_centers (number_of_clusters, feature_dimension); std::vector counters (number_of_clusters); std::vector > boxes (feature_dimension); - Eigen::Vector2f* box = &boxes[0]; + Eigen::Vector2f* box = boxes.data(); double best_compactness = std::numeric_limits::max (); double compactness = 0.0; @@ -1428,7 +1428,7 @@ pcl::ism::ImplicitShapeModelEstimation::generateCe std::size_t dimension = data.cols (); auto number_of_points = static_cast (data.rows ()); std::vector centers_vec (number_of_clusters); - int* centers = ¢ers_vec[0]; + int* centers = centers_vec.data(); std::vector dist (number_of_points); std::vector tdist (number_of_points); std::vector tdist2 (number_of_points); diff --git a/recognition/include/pcl/recognition/quantized_map.h b/recognition/include/pcl/recognition/quantized_map.h index 756c4ba49f7..24f75f15857 100644 --- a/recognition/include/pcl/recognition/quantized_map.h +++ b/recognition/include/pcl/recognition/quantized_map.h @@ -59,10 +59,10 @@ namespace pcl getHeight () const { return (height_); } inline unsigned char* - getData () { return (&data_[0]); } + getData () { return (data_.data()); } inline const unsigned char* - getData () const { return (&data_[0]); } + getData () const { return (data_.data()); } inline QuantizedMap getSubMap (std::size_t x, diff --git a/recognition/src/dotmod.cpp b/recognition/src/dotmod.cpp index 49a18f46ea7..268324e0f70 100644 --- a/recognition/src/dotmod.cpp +++ b/recognition/src/dotmod.cpp @@ -160,7 +160,7 @@ detectTemplates (const std::vector & modalities, const unsigned char * image_data = map.getData (); for (std::size_t template_index = 0; template_index < nr_templates; ++template_index) { - const unsigned char * template_data = &(templates_[template_index].modalities[modality_index].features[0]); + const unsigned char * template_data = templates_[template_index].modalities[modality_index].features.data(); for (std::size_t data_index = 0; data_index < (nr_template_horizontal_bins*nr_template_vertical_bins); ++data_index) { if ((image_data[data_index] & template_data[data_index]) != 0) diff --git a/recognition/src/face_detection/face_detector_data_provider.cpp b/recognition/src/face_detection/face_detector_data_provider.cpp index d87db82709a..95cedbdc3d2 100644 --- a/recognition/src/face_detection/face_detector_data_provider.cpp +++ b/recognition/src/face_detection/face_detector_data_provider.cpp @@ -254,7 +254,7 @@ void pcl::face_detection::FaceDetectorDataProviderwidth; - const float *data = reinterpret_cast (&(*cloud)[0]); + const float *data = reinterpret_cast (&(*cloud)[0]); // NOLINT(readability-container-data-pointer) integral_image_depth->setInput (data + 2, cloud->width, cloud->height, element_stride, row_stride); //Compute normals and normal integral images @@ -282,16 +282,14 @@ void pcl::face_detection::FaceDetectorDataProvider (false)); - const float *data_nx = reinterpret_cast (&(*normals)[0]); - integral_image_normal_x->setInput (data_nx, normals->width, normals->height, element_stride_normal, row_stride_normal); + const float *data = reinterpret_cast (normals->data()); + integral_image_normal_x->setInput (data + 0, normals->width, normals->height, element_stride_normal, row_stride_normal); integral_image_normal_y.reset (new pcl::IntegralImage2D (false)); - const float *data_ny = reinterpret_cast (&(*normals)[0]); - integral_image_normal_y->setInput (data_ny + 1, normals->width, normals->height, element_stride_normal, row_stride_normal); + integral_image_normal_y->setInput (data + 1, normals->width, normals->height, element_stride_normal, row_stride_normal); integral_image_normal_z.reset (new pcl::IntegralImage2D (false)); - const float *data_nz = reinterpret_cast (&(*normals)[0]); - integral_image_normal_z->setInput (data_nz + 2, normals->width, normals->height, element_stride_normal, row_stride_normal); + integral_image_normal_z->setInput (data + 2, normals->width, normals->height, element_stride_normal, row_stride_normal); } //Using cloud labels estimate a 2D window from where to extract positive samples diff --git a/recognition/src/face_detection/rf_face_detector_trainer.cpp b/recognition/src/face_detection/rf_face_detector_trainer.cpp index 3387a8ed457..e4a447b4d81 100644 --- a/recognition/src/face_detection/rf_face_detector_trainer.cpp +++ b/recognition/src/face_detection/rf_face_detector_trainer.cpp @@ -276,7 +276,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces() int element_stride = sizeof(pcl::PointXYZ) / sizeof(float); int row_stride = element_stride * cloud->width; - const float *data = reinterpret_cast (&(*cloud)[0]); + const float *data = reinterpret_cast (cloud->data()); integral_image_depth->setInput (data + 2, cloud->width, cloud->height, element_stride, row_stride); //Compute normals and normal integral images @@ -302,16 +302,14 @@ void pcl::RFFaceDetectorTrainer::detectFaces() if (use_normals_) { integral_image_normal_x.reset (new pcl::IntegralImage2D (false)); - const float *data_nx = reinterpret_cast (&(*normals)[0]); - integral_image_normal_x->setInput (data_nx, normals->width, normals->height, element_stride_normal, row_stride_normal); + const float *datum = reinterpret_cast (normals->data()); + integral_image_normal_x->setInput (datum + 0, normals->width, normals->height, element_stride_normal, row_stride_normal); integral_image_normal_y.reset (new pcl::IntegralImage2D (false)); - const float *data_ny = reinterpret_cast (&(*normals)[0]); - integral_image_normal_y->setInput (data_ny + 1, normals->width, normals->height, element_stride_normal, row_stride_normal); + integral_image_normal_y->setInput (datum + 1, normals->width, normals->height, element_stride_normal, row_stride_normal); integral_image_normal_z.reset (new pcl::IntegralImage2D (false)); - const float *data_nz = reinterpret_cast (&(*normals)[0]); - integral_image_normal_z->setInput (data_nz + 2, normals->width, normals->height, element_stride_normal, row_stride_normal); + integral_image_normal_z->setInput (datum + 2, normals->width, normals->height, element_stride_normal, row_stride_normal); } { diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index 9245f84cfe9..4ac4b615412 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -419,7 +419,7 @@ pcl::registration::FPCSInitialAlignment namespace pcl { +// NOLINTBEGIN(readability-container-data-pointer) template void @@ -317,6 +318,7 @@ IterativeClosestPointWithNormals::transformClo { pcl::transformPointCloudWithNormals(input, output, transform); } +// NOLINTEND(readability-container-data-pointer) } // namespace pcl diff --git a/registration/include/pcl/registration/impl/registration.hpp b/registration/include/pcl/registration/impl/registration.hpp index 1abc953f002..24a454efabd 100644 --- a/registration/include/pcl/registration/impl/registration.hpp +++ b/registration/include/pcl/registration/impl/registration.hpp @@ -124,8 +124,8 @@ Registration::getFitnessScore( { unsigned int nr_elem = static_cast(std::min(distances_a.size(), distances_b.size())); - Eigen::VectorXf map_a = Eigen::VectorXf::Map(&distances_a[0], nr_elem); - Eigen::VectorXf map_b = Eigen::VectorXf::Map(&distances_b[0], nr_elem); + Eigen::VectorXf map_a = Eigen::VectorXf::Map(distances_a.data(), nr_elem); + Eigen::VectorXf map_b = Eigen::VectorXf::Map(distances_b.data(), nr_elem); return (static_cast((map_a - map_b).sum()) / static_cast(nr_elem)); } diff --git a/registration/src/correspondence_rejection_var_trimmed.cpp b/registration/src/correspondence_rejection_var_trimmed.cpp index ff6ff5a363b..62c1c70f4bc 100644 --- a/registration/src/correspondence_rejection_var_trimmed.cpp +++ b/registration/src/correspondence_rejection_var_trimmed.cpp @@ -89,7 +89,7 @@ pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio( const int max_el = static_cast(std::floor(max_ratio_ * points_nbr)); using LineArray = Eigen::Array; - Eigen::Map sorted_dist(&dists[0], points_nbr); + Eigen::Map sorted_dist(dists.data(), points_nbr); const LineArray trunk_sorted_dist = sorted_dist.segment(min_el, max_el - min_el); const double lower_sum = sorted_dist.head(min_el).sum(); diff --git a/search/include/pcl/search/impl/flann_search.hpp b/search/include/pcl/search/impl/flann_search.hpp index db951a602b5..1cd7e7f87b4 100644 --- a/search/include/pcl/search/impl/flann_search.hpp +++ b/search/include/pcl/search/impl/flann_search.hpp @@ -126,7 +126,7 @@ pcl::search::FlannSearch::nearestKSearch (const PointT &p indices.resize (k,-1); if (dists.size() != static_cast (k)) dists.resize (k); - flann::Matrix d (&dists[0],1,k); + flann::Matrix d (dists.data(),1,k); int result = knn_search(*index_, m, indices, d, k, p); delete [] data; diff --git a/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp index d02c0871281..11686ae1dce 100644 --- a/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp @@ -118,14 +118,14 @@ pcl::SACSegmentation::segment (PointIndices &inliers, ModelCoefficients Eigen::VectorXf coeff_refined (model_->getModelSize ()); model_->optimizeModelCoefficients (inliers.indices, coeff, coeff_refined); model_coefficients.values.resize (coeff_refined.size ()); - memcpy (&model_coefficients.values[0], &coeff_refined[0], coeff_refined.size () * sizeof (float)); + memcpy (model_coefficients.values.data(), coeff_refined.data(), coeff_refined.size () * sizeof (float)); // Refine inliers model_->selectWithinDistance (coeff_refined, threshold_, inliers.indices); } else { model_coefficients.values.resize (coeff.size ()); - memcpy (&model_coefficients.values[0], &coeff[0], coeff.size () * sizeof (float)); + memcpy (model_coefficients.values.data(), coeff.data(), coeff.size () * sizeof (float)); } deinitCompute (); diff --git a/simulation/src/model.cpp b/simulation/src/model.cpp index 2e9368f2736..99ec4d45fc3 100644 --- a/simulation/src/model.cpp +++ b/simulation/src/model.cpp @@ -53,7 +53,7 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg) glBindBuffer(GL_ARRAY_BUFFER, vbo_); glBufferData(GL_ARRAY_BUFFER, vertices.size() * sizeof(vertices[0]), - &(vertices[0]), + vertices.data(), GL_STATIC_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); @@ -61,7 +61,7 @@ pcl::simulation::TriangleMeshModel::TriangleMeshModel(pcl::PolygonMesh::Ptr plg) glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, ibo_); glBufferData(GL_ELEMENT_ARRAY_BUFFER, indices.size() * sizeof(indices[0]), - &(indices[0]), + indices.data(), GL_STATIC_DRAW); glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, 0); diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index e40aeaa25af..f09315593dc 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -470,7 +470,7 @@ pcl::simulation::RangeLikelihood::RangeLikelihood( glBindBuffer(GL_ARRAY_BUFFER, quad_vbo_); glBufferData(GL_ARRAY_BUFFER, sizeof(Eigen::Vector3f) * vertices_.size(), - &(vertices_[0]), + vertices_.data(), GL_STATIC_DRAW); glBindBuffer(GL_ARRAY_BUFFER, 0); diff --git a/surface/src/vtk_smoothing/vtk_utils.cpp b/surface/src/vtk_smoothing/vtk_utils.cpp index ae85bf3a86c..3bcf78a35fe 100644 --- a/surface/src/vtk_smoothing/vtk_utils.cpp +++ b/surface/src/vtk_smoothing/vtk_utils.cpp @@ -212,7 +212,7 @@ pcl::VTKUtils::mesh2vtk (const pcl::PolygonMesh& mesh, vtkSmartPointerInsertPoint(cp, pt[0], pt[1], pt[2]); diff --git a/test/common/test_plane_intersection.cpp b/test/common/test_plane_intersection.cpp index cb0ee8c5bea..ec8425410db 100644 --- a/test/common/test_plane_intersection.cpp +++ b/test/common/test_plane_intersection.cpp @@ -169,8 +169,8 @@ TEST (PCL, lineWithLineIntersection) Eigen::Vector4f point_mod_case_2; double sqr_mod_case_2 = 1e-1; - Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (&line_a_mod_2.values[0], line_a_mod_2.values.size ()); - Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (&line_b_mod_2.values[0], line_b_mod_2.values.size ()); + Eigen::VectorXf coeff1 = Eigen::VectorXf::Map (line_a_mod_2.values.data(), line_a_mod_2.values.size ()); + Eigen::VectorXf coeff2 = Eigen::VectorXf::Map (line_b_mod_2.values.data(), line_b_mod_2.values.size ()); Eigen::Vector4f p1_mod, p2_mod; lineToLineSegment (coeff1, coeff2, p1_mod, p2_mod); diff --git a/test/io/test_ply_io.cpp b/test/io/test_ply_io.cpp index 89065bf9b2a..7fce8deea5e 100644 --- a/test/io/test_ply_io.cpp +++ b/test/io/test_ply_io.cpp @@ -590,7 +590,7 @@ TEST_F (PLYTest, Float64Cloud) } for (size_t pointIdx = 0; pointIdx < cloud.size(); ++pointIdx) { - unsigned char const * ptr = &cloud2.data[0] + pointIdx*cloud2.point_step; + unsigned char const * ptr = cloud2.data.data() + pointIdx*cloud2.point_step; double xValue, yValue, zValue; memcpy( reinterpret_cast(&xValue), diff --git a/test/io/test_ply_mesh_io.cpp b/test/io/test_ply_mesh_io.cpp index 8525f8d7491..ab069b81053 100644 --- a/test/io/test_ply_mesh_io.cpp +++ b/test/io/test_ply_mesh_io.cpp @@ -295,7 +295,7 @@ TEST (PCL, PLYPolygonMeshSpecificFieldOrder) mesh.cloud.data.resize(28); constexpr float x = 0.0, y = 1.0, z = 2.0, normal_x = 1.0, normal_y = 0.0, normal_z = 0.0; constexpr std::uint32_t rgba = 0x326496; - memcpy(&mesh.cloud.data[0], &x, sizeof(float)); + memcpy(&mesh.cloud.data[0], &x, sizeof(float)); // NOLINT(readability-container-data-pointer) memcpy(&mesh.cloud.data[4], &y, sizeof(float)); memcpy(&mesh.cloud.data[8], &z, sizeof(float)); memcpy(&mesh.cloud.data[12], &normal_x, sizeof(float)); diff --git a/test/io/test_point_cloud_image_extractors.cpp b/test/io/test_point_cloud_image_extractors.cpp index 5c5e58dc376..c34c2f8056c 100644 --- a/test/io/test_point_cloud_image_extractors.cpp +++ b/test/io/test_point_cloud_image_extractors.cpp @@ -178,7 +178,7 @@ TEST (PCL, PointCloudImageExtractorFromLabelFieldMono) pcie.setColorMode (pcie.COLORS_MONO); ASSERT_TRUE (pcie.extract (cloud, image)); - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ ("mono16", image.encoding); EXPECT_EQ (cloud.width, image.width); @@ -279,7 +279,7 @@ TEST (PCL, PointCloudImageExtractorFromZField) PointCloudImageExtractorFromZField pcie; ASSERT_TRUE (pcie.extract (cloud, image)); - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ ("mono16", image.encoding); EXPECT_EQ (cloud.width, image.width); @@ -309,7 +309,7 @@ TEST (PCL, PointCloudImageExtractorFromCurvatureField) PointCloudImageExtractorFromCurvatureField pcie; ASSERT_TRUE (pcie.extract (cloud, image)); - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ ("mono16", image.encoding); EXPECT_EQ (cloud.width, image.width); @@ -341,7 +341,7 @@ TEST (PCL, PointCloudImageExtractorFromIntensityField) PointCloudImageExtractorFromIntensityField pcie; ASSERT_TRUE (pcie.extract (cloud, image)); - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ ("mono16", image.encoding); EXPECT_EQ (cloud.width, image.width); @@ -412,7 +412,7 @@ TEST (PCL, PointCloudImageExtractorBlackNaNs) ASSERT_TRUE (pcie.extract (cloud, image)); { - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ (std::numeric_limits::max (), data[3]); } @@ -421,7 +421,7 @@ TEST (PCL, PointCloudImageExtractorBlackNaNs) ASSERT_TRUE (pcie.extract (cloud, image)); { - auto* data = reinterpret_cast (&image.data[0]); + auto* data = reinterpret_cast (image.data.data()); EXPECT_EQ (0, data[3]); } } diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 7e65320e5cc..d0855613704 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -501,14 +501,14 @@ class Viewer { frame->image->fillRGB (frame->image->getWidth (), frame->image->getHeight (), - &rgb_data[0]); + rgb_data.data()); } else - memcpy (&rgb_data[0], + memcpy (rgb_data.data(), frame->image->getMetaData ().Data (), rgb_data.size ()); - image_viewer_->addRGBImage (reinterpret_cast (&rgb_data[0]), + image_viewer_->addRGBImage (reinterpret_cast (rgb_data.data()), frame->image->getWidth (), frame->image->getHeight (), "rgb_image"); diff --git a/visualization/include/pcl/visualization/pcl_painter2D.h b/visualization/include/pcl/visualization/pcl_painter2D.h index 12b29321b53..cfed860035c 100644 --- a/visualization/include/pcl/visualization/pcl_painter2D.h +++ b/visualization/include/pcl/visualization/pcl_painter2D.h @@ -123,7 +123,7 @@ namespace pcl void draw (vtkContext2D * painter) override { applyInternals(painter); - painter->DrawPoly (&info_[0], static_cast (info_.size ()) / 2); + painter->DrawPoly (info_.data(), static_cast (info_.size ()) / 2); } }; @@ -137,7 +137,7 @@ namespace pcl void draw (vtkContext2D * painter) override { applyInternals(painter); - painter->DrawPoints (&info_[0], static_cast (info_.size ()) / 2); + painter->DrawPoints (info_.data(), static_cast (info_.size ()) / 2); } }; @@ -151,7 +151,7 @@ namespace pcl void draw (vtkContext2D * painter) override { applyInternals(painter); - painter->DrawQuad (&info_[0]); + painter->DrawQuad (info_.data()); } }; @@ -165,7 +165,7 @@ namespace pcl void draw (vtkContext2D * painter) override { applyInternals(painter); - painter->DrawPolygon (&info_[0], static_cast (info_.size ()) / 2); + painter->DrawPolygon (info_.data(), static_cast (info_.size ()) / 2); } }; diff --git a/visualization/src/pcl_plotter.cpp b/visualization/src/pcl_plotter.cpp index 413ff946775..707f79240ba 100644 --- a/visualization/src/pcl_plotter.cpp +++ b/visualization/src/pcl_plotter.cpp @@ -145,7 +145,7 @@ pcl::visualization::PCLPlotter::addPlotData ( int type /* = vtkChart::LINE */, std::vector const &color) { - this->addPlotData (&array_X[0], &array_Y[0], static_cast (array_X.size ()), name, type, (color.empty ()) ? nullptr : &color[0]); + this->addPlotData (array_X.data(), array_Y.data(), static_cast (array_X.size ()), name, type, (color.empty ()) ? nullptr : color.data()); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -164,7 +164,7 @@ pcl::visualization::PCLPlotter::addPlotData ( array_x[i] = plot_data[i].first; array_y[i] = plot_data[i].second; } - this->addPlotData (array_x, array_y, static_cast (plot_data.size ()), name, type, (color.empty ()) ? nullptr : &color[0]); + this->addPlotData (array_x, array_y, static_cast (plot_data.size ()), name, type, (color.empty ()) ? nullptr : color.data()); delete[] array_x; delete[] array_y; } diff --git a/visualization/src/vtk/pcl_context_item.cpp b/visualization/src/vtk/pcl_context_item.cpp index 48d1cf3c6a8..19a436dc534 100644 --- a/visualization/src/vtk/pcl_context_item.cpp +++ b/visualization/src/vtk/pcl_context_item.cpp @@ -197,7 +197,7 @@ pcl::visualization::context_items::Polygon::Paint (vtkContext2D *painter) { painter->GetBrush ()->SetColor (colors[0], colors[1], colors[2], static_cast ((255.0 * GetOpacity ()))); painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast ((255.0 * GetOpacity ()))); - painter->DrawPolygon (¶ms[0], static_cast (params.size () / 2)); + painter->DrawPolygon (params.data(), static_cast (params.size () / 2)); return (true); } @@ -215,7 +215,7 @@ bool pcl::visualization::context_items::Points::Paint (vtkContext2D *painter) { painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast ((255.0 * GetOpacity ()))); - painter->DrawPoints (¶ms[0], static_cast (params.size () / 2)); + painter->DrawPoints (params.data(), static_cast (params.size () / 2)); return (true); } @@ -259,10 +259,10 @@ pcl::visualization::context_items::Markers::Paint (vtkContext2D *painter) painter->GetPen ()->SetWidth (size); painter->GetPen ()->SetColor (colors[0], colors[1], colors[2], static_cast ((255.0 * GetOpacity ()))); - painter->DrawPointSprites (nullptr, ¶ms[0], nb_points); + painter->DrawPointSprites (nullptr, params.data(), nb_points); painter->GetPen ()->SetWidth (1); painter->GetPen ()->SetColor (point_colors[0], point_colors[1], point_colors[2], static_cast ((255.0 * GetOpacity ()))); - painter->DrawPointSprites (nullptr, ¶ms[0], nb_points); + painter->DrawPointSprites (nullptr, params.data(), nb_points); return (true); } From c85682781856892ce05ac5de702a98b9e7e2f877 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sun, 5 Feb 2023 15:16:33 +0100 Subject: [PATCH 041/288] [Doc] Add tutorial for using VCPKG on Windows (#4814) * Added VCPKG tutorial * Rewording * Remove specific note about 11(.1) --- .../images/vcpkg/cmake_configure_1.png | Bin 0 -> 23466 bytes .../images/vcpkg/cmake_configure_2.png | Bin 0 -> 18418 bytes doc/tutorials/content/index.rst | 15 ++ doc/tutorials/content/pcl_vcpkg_windows.rst | 143 ++++++++++++++++++ 4 files changed, 158 insertions(+) create mode 100644 doc/tutorials/content/images/vcpkg/cmake_configure_1.png create mode 100644 doc/tutorials/content/images/vcpkg/cmake_configure_2.png create mode 100644 doc/tutorials/content/pcl_vcpkg_windows.rst diff --git a/doc/tutorials/content/images/vcpkg/cmake_configure_1.png b/doc/tutorials/content/images/vcpkg/cmake_configure_1.png new file mode 100644 index 0000000000000000000000000000000000000000..7fee2aa2f164a4728574627e87fa072a2b53d9c6 GIT binary patch literal 23466 zcmb@ubyQr>)-Bq&YmnfC;F_j!cXxsZ3DQ8Y;1(bdLXgJYod7|C1Scf8H0~bUAvgqk zoBYmq-#vGn``!1(dw(#R-cnV2Rn=N^&b4-jX{gELV3K2kKp-4N1sN?62vG+3LqbOc zj=Wh;ngu=(T(#t-KovujJHQuYYe`i}5U45|>-IGY@Ezl=f`Katgxm4>htT6xYzYDx zi7U!TzVtFVXthhwnf!Lt{5>Oc|Hd|;;c_n$x|NmLxgMUQF*4L>oxNCb)2=wLxke$Y z^dgbUA?-?nnLq<$7_qFAl$rJdmnq!u|pILB(lz8;J^u^=XQWB~{F zWY|smOqTLm-vyMv`VuYnXWIg9P;qY!=d~+`KRy!eisd~j@JUY=N(KVG??eJ4fj}`{ zv{2v}Azmjo2qdu@n1TQTDTts%%!XVn`}tqsjR7Y?rSIE2_ah=qFPa1TjM~!f&-F|r zuz=&+wwU-em2LMv_j~dW^%VZCds}$^XMdo_kM zl}t(BEi4tN6OT^ZSDj=m$y^kTH}OmKD9Rv{$Ca}wy|Az(%rYV2-rCjTaHZrm$SMe0)gu;MwoG_D|bPZikGA4U~pbi&A9qrl0>G>IsnAUs6^hV^kS8ead7NedRJikh~z6RKD|JMk4-yU|~Xd+d3%{IaicZY!#75Uz%;>=6=I5zlM@HVqp2n(wXoNnj^fR5`-u-? zjlAW`K*8AccY*8lSv4eR!b3!>aampBvz z;YqeB8q!R(`#RgdTg-(4Ge5mgkVJaFgwa~t86K1W<;IL5U*1kZUeoOvw3fqn^P7im zHCw>(*vcA}gTsN7drQsM!?m6k_x<(nZzN$Cnj1ZA;p9dJZmoh25mDM9mKhuh6NQuT zqJbn~Y#c1K*Kf0m8Z|$BMp7SrgCw=8BXz;mpykD7 zJxRMF!C?_HqgBK3&f6DD4I3XbrlOwa+Acf;ooSUS!9@_*jE9>V;8$B*oUeq;hn7wG z_j;b_Q3pIsROR>J)_$Y%y*a3}bE-41yEF~BJx?~^vwkVPFc{&=pZ}7C>K9L~?Tya0 zx$>(e1&dE$euz*QOmf&{qn4PPoN|1UAy#28$3C|tU$FcW_PF)*uT6}0`;dmJ*ESg^ zJ?tHw^NksT*oUv0<})|kn!$q-n0SM$jCh4(s$3H|&Osk!Q5s*i2{;tk3G`T;f<}x= zsKF756@=&Z`cV`THbxf{a~Dn~!e1OO(w?ye+?#IQT~(Y%m;1WT?_3U3em`BVzs+xg zH=M^El?=|Nxf8K>h`2o?D992ZR&t*=gx*0_-VR$duu&Gi-OF9$cO*NEq7{hb^ugrP zhim91ry!6gcG2gTbSTor{%q+V@$_JZGuK?CxDwX2juXQ3xw|-?3y~5~lcYs_ew(KD zLcUpBLfvfN0Er%aMApxSj+K9oyC`IQnF0+ZP*-k7=$@a6p zm^I~mw^cz(ZSvjcSKRAlIN3?L;0G>0|K38^klWLfScu;6!s+i~QNM@zB&UFYy?U;B z&+|4vzvDb?B(Th(<_=ljz*{A8AXFv23g8j-yc_*9IS}xBRb9VtJ2pUJ_`9feuXwAM z@uJ<@v|HIr&_R(3_-4_|1LP)LMDuLcxDXH3@|wE6-9g zC-}Z;l5*2a^&ooa%h$Sam~ow#gE(1XS(57?84|`eti93v8SEr95QrsrJu|fwhTD~F z%l|s&V@oN)9(LtVBO8R^c)MO=F_lR1%By|y>Pn4wd}E4+FC5hv69gs7f1rMn)9es7 z18@kB6+ulkQTJ7_mPd0EX34rN2ZIZCU`J-VkMZZKW|LgI(2XE-sJ}c+jLsY9^d?_op4sZH&mE; z10aa7-xo1Q&jVJQq=A%#__rgm*zKYWU-s?=dhVqHJiZon+BVX{du zb%xh#KwIui0$3DO>m(3-ov7frv`6DTrG+*=q9_T(_bD5wkE;d)^lxj20h;{?j}+y? zX0w6M_w@e_4*R!d^q<#W-zEV_!Z1e9Jw@-mP^!oesJtEu z9naF+UaiNsHBW;i+>yWoswL(m3C65H$>wcJ2PgOvtC&4g`%x2gFnmI)se?kvSR}g{ zOh^(;U{n-i*hw)`9}9k5wX|ayBY}4Eu)ubiBkCrL;kj6Dfk%!RiZ`k@#MXG4r70|< zV5>h=uhSm<|~Geb56_Hgb^%-9M1?cgcFx#1wls!*Rh#t?3nA@ZB&w z&*xYnsDyQ9HXqL*Y=z+l+T|0AMRRkEpL4N|6FyIbJE93O;Zjj_Zu?hGoA3H2`S;w7 zNE@r~{<=hVsG$}Pa=3fSu74njGI=rHXc>{fE0ncuuEMtw1|5>+1V6X7iI{qoTw-@Y z*H}Wmw`=LjwD_hrM^vb~Dk@Daj+U8Qi845IT20bno?&8;R}f)4k%$&rz)jCF2YJoh z>Qg&}+{`?_?zLh4j82(M(hUDs9fyc&3ax-h#J6*cudInOq3O*aC1OZvMN>nadPyOZ zCd4mR^G#L4808$EBOMd#ZG_(XRt_=A`AA}*@4V_xVS zOZ!I*t}(ze6MTtRf|q8tPXyApUZ-nFzslR=_fo7@rT0#0$RGOfO1S1lo`?xOzcJG+ zJGlRajK$3JMeIl|ZsPrB9_Q0IE|;GWB9KI7{`<_-M4Vv@hjKE*=56O~#FMYTzZ$hF zP-$waMjSWK5R4j#;LU2{%?FdO67uVLD3L&xBvK;dmU2?RL{_29`J~uj&r|1C2q@Md zj0OviVKV0O^QCutQP*Kq?!-Nh+vj9r4Q%Ox%Xq~uxMf<#|0$MV3y(Y&dG<;XBAIIj zga9#=P%b{UM?7}B!B5nw5X(>@YPXk@hHt8I@XLw~q?Vp&`NGOp);t<{UK1~?c z6L5?e@=380vChVtM3fxu8bU{=7^QKkcP~OS*&GC3F35y|doJc69QH=RUggOrd;mtEJk&oi?1xeKqu! zAM}1n9>H9$f3+`!glUS^#mLS^9OGHM2BQIYXb&2aU-7a>@2gmYpuXCj%KjbQ&cTfk z%NkxQ{2Glw9USeTK94*5Jy4*CBlgO9_%yEGd8V^4+2I<6L{kbdd9lHgmT&PF4o#JX zGVOl8k(df|ks<%dZ5JEXE=`|);^o~;iw{xkeEJM*PQon9JhsrkA{3eT`$9=@cbC4~ z4Q1yx&?BY*1GO<$x1Ey75roj1QPHJh!WLX{vW{Wdf%BF8N8VPdlIBzAhSbI2Dymq6 zvixO@I5l;+l;FgB8>I~}))3ULpB9>vMgZQ!BupJ4Db+$gMXg2!h2~;`_s%8YT5A60 zQ>TWgfTsgI-ooR7EMWi_Bmy1_r;~jHaHR@p|D3>W1)T7XgvsPz z)`$3SjQIbFCx)_tXgPYnkQ1SFvd@lS{Q_dcwFF!V**wV}02T#Ep$1_R@Hm`K?DuXU zFdIRrK{XI4VsL4p42WQ5zJEM)nGE2-fv_PV^gbm~fz*6T+@i#R(A2h8eP=m9shLNj z#4RGl!GOoAKaT_8<}VR}M%@^ox?X8-AXWs=LJbW1SfF3BS=8dgi6G<`@HbTmAcXSr za&tj1HQ>^94ye-LoAg>D)e>F`-Zv+8gXoz@y^Ff#W{4Wd2AwcBD|iZ6*HBknnqv?$ zK$Xj#*ENbc37;C9ortl{8m+L_RnE>g^T{(0#(zIi?Rm6RR8$m6!LMW_t?HtcT>A{l z5MP-Rc4!0UCZ+t=Ql;p>L#(dNK^6;|Hlr}tCD#N;Y=^~VNH`^sr>fOu-cJtecdb56 zgx%09iSCF^T41NgXo8=GA>|~m?HIi5Lw_9cU6w%$QR7#is#p%%41@#~eK_I)26}?x z8eiAc$yQVi*yKf*O!LCiMYscbqgWl;6niM@x3yzvE4ygOxP|!+9I?F7pL&+=-p)aNAzfxC~AFgX4v@mJwlbI*KLACf+EXxZg?>ApT0uf;Y z<8H!-Xl$$#0gKff7!^9OlK!<=2?J9YC;+ds12Wg8!>_UYR~Y}hytV=HNdfJo6jk;S z(Ee{ko&UIm4XVA7K`|ujI#ip)W-*XB6kt{6lKxl*f%=#}rL>|g`Bsv5?LW~F+eZ1# z3#{i6I|E>==vKVCZZ4G!E@avUgX5QxwxPRwdmDwoAh^#AlK?DIN?1b~y6HwiObijc zoV|XUK;eV%4h5tj_V@Ht!Wz#n*s+!Sq4x=iN};LDI+Q2#=&sZWc)(Q{|8-Rgu(rl^ zJ`@`~)%+?T6WTB78E$ZsaDVr?Hq8Db{^VFMSLaH!Y)!zJj-KiqS7e6Fb641)IESXj z+e-)(o)YoV#bxS8V2zs6|BYERFh{@XoW7A9%bBijDecgRBw;8~k{RL2Gn?@4O)y zcv7_+aPLyQh&nr^`P-;gI%N}#nb{ZJ$8?PBDzz`59JqF7@ffPL#lQ#Q`|=_VZ(GF^<&R?RS4){b|4$S7H` zwFte~j6(bI)pbj)ic*BBHEBbK3VMCAL8ZwjI#+*`pPuJYe>?=`9oY0FQkwY_HUDlm zVLRnRTy41~__?}z1c24{yVKs-rDud_fjOY@cHdO2xjXc17=&N!usU!1eOd~*-Nk*g zR0Z?r@MTO}Vq-eIj=7SUx$8_US_@lLvzsBr7>Rl4f89}_j`Akjhp$zA--BkhZzVYL zB{G%X{Yf&>ZRZQy{sgr)VU=ORdepmZ1`HR0SRv>PAvG~(T-du$ZbTnZ{~U*0qtMUvFY%k#ksisI?f!(oJIueZKwYs`CK zJkO5L;Ny3HBaJsb>io9h$rIRg!%mQhhazK~urc2J;d5cD)*13pMf8yZt+IXdQ{`(n7gXxeN^q}y#uDyS|21EI_!%_} zxy(w{x7R}#F}QP=^~ z%9t-yx~_2Dx;OJ)J7%kVcZ*}i@m(~&(XZ;N)BL4TP$#xrD)wQ1e1D(QS88tir;#y% zP;;jo%%r*$O8ofFz|%&s2&+(Rc$IB!u82v~d(C_~Kd2zLD08*U;Mwz4OXbtuP#%l;3TkFEmY;ad?_Ig!e!7mvU+S)|)4$X@LUjmX|xI&}9KO}?bJ4ou}I z=_p?>dEI4D7m1N6=KUtHVkaEwL9>FMhYK9_3)OBrT8?p&sxB_^x&N5tq$v2qEWJhY|Hq?)vY=%L))uYT4xQymbl*1t6NPYl@d^&=u9fJfUc{Ntxm=3>HbM zmK_IDUMpX!wVd>awUlTeGWu^`$XXBIFIAsb`QK5`?~vPDI~sNJ5geR|Sjy8Zn$(f) zg@ugfv&Z#W;ACYx5SxWYIwKMBjONXE_C|c7_Sx1R$hAd6RS~9-^fGCLxNfnKDsN$jM5UFt&Zpd~HO;B%%N^~urEmGvcGiw*ez#Zq=?Qih zs{DhDc!F24l)E2u*q`j@-7=+|pO-lV6Y|ADtScFtYrhu6zIV_`rdoD)!XU6^&4}w# zS>78h;N&hvbr@l+FCQT#Ljr3bMN^GjUX=*n`G1>k;g|ER!t;nv>BHSGTk?L(B5vWe zTy5Mc-LS|zGqi9)I4@H>a2iA9=jJ;LEn^}l!Kw55=>gbAlx(e^z(VwyiMb+HlqeRS z*wwE9eOxuF7iPPXww>m5Er0C-`NlSx@7&exm4(lCPP{#r*v|*RcFdh|XZ}eY3^O+{-mYi`0$OZ9SKh)$Fc1--DNUsZz|Y?;+L$; zxO1swhwT&Ui(m_tqwtm8H;`r?2kj8Ff7rxl=YGay$O6{a)IO&V3-%WyJUl`9?TQ_? zD3FYnf=}o1W!sAJT;%_?f=7`h?0tTeh-t25@2N$^_@W5JUAB-d+wXDGE};y((W2_g`e20`bI$scd%3 zc(X9T^s6?-95#E{vqSwMstWB@F|7xY*F9983a}l_v1_CQTE!>WF3)XEHZTQ`Y}`)1 zh%hp8f7+s}omO)|3u#Z74qn%fJO3D!MpH5m{beGG{GRY1m(_B$8iAHyM&>T~U|QU8 z&vNlf>gez zE1O^Xvi1b2ndI?;=dzz$>8Z@J1Dyv0#-^XN$1Vtj_ZN)77aCnJ&zWy{(Qqkk?Ck8E zoS0glJFJycmpT*&y40eVvP0<{vr2E)cm>nl6jF0>Z4cG31^)}qj{IJ zL@n%_WC_!CLV>wQL|tDUuetqp!}QuxvPMp57rk8Qc*tM>8Bt&A8^Ib4;W8DnrU3o= z$4hx1Hf}9#YkJsv*j*ehDxY+>cgH0e4WBJ%g=K{$=;Wq!v63D20a~$_e(Sc)P6{54 zm6O+)IU8GKu+|ZCF_5hzHGmvS@)*SVSZ|EuF3D_B2(Bi zt}eDz6XCND^<>TVChT0Lpp3jz#f?4Ba;a_~o(d_mJV^wyy&$cgEKy(966-}~XqD2% z&GJJQw9q0aKkhjo{>2D+?9WL0bWc;{A7yua_h!`6WiT&VVv7h(ZT+EOE{F9$U76+o zXJ@v?dN@<~vWwL8-A-XLu#*~WM)SHNNVyEEEqBHW2a-69zQ4O3;A&GLm*(N+Eq9}} zVnvM2V<&nJ{X=L0_oFGWJZgIoV|iiAjq!~V4Csp!RRIt89iQ-M#Qifc#S;CNoH7Mn zLxSJ0zn2Lt2&7G=tumXWy*8sF&}3ng4NukK_B4|FB#9<1tTYE5lk6t|_=Ex#5Gw?| ze*a2$`mTubkmF^6g={CL^D>GM#xPe3eeOg zc4xlX=@}W#kLJs(X9!59L*}|$ZVsE5Hem{JDYKpf`&8FGQB=>nlKy3^!-YOQ@{(U| z=Tk<9o3QmCiy1okDWh5<;QViMb})7*{b=p6y^~Y&|FCV9)3VrHeN0NGi1*lhhPNJh zc?!WK1GLPN9eOc^Cxog6jkB5aq84~7@y~c{92^#Ftnm(vu9TiT4P5~{A!Bx4LV-nr zyHpl#<3j@RG}`?BTJFndi(k#+QIvvG^Xh`;z$BMg%-1wgT?0SqsKAS!|YOl&#ha zIBkiBrpk>x59VYQuN-Q&9cV9;in3f|}z|0H@GENI&VoPU?^d5Kn@-eo_WCF;@% znCSk3e=dG>sO$r8)LwG70^oZmZYLlwDR_Zv3|sx|}-+2ZwSVRxDL2Hp9Pjq_)~wR;Nhu)2bUO zzC!DUXSI~cgAF`?tuO9u`6p`e>f$&FoNOw#dv6yZE)STXG$Y`yg7uGhTFdVx8s@b* z14Fp3s9WP30>53OsO*{Fy~KJV+!s*iMWO6Y`#rDxr+17*IW~W_>a3c&zR=n5zhK~k!iIiA+A}zJM79WHC+U0fx$H? z6cTUk#DMvDhX`cT-mm{RDHiP_l~k}rcV)oco^_Tt^kRQ@Sp4A@h;LiN*==S&gFa%B zavIj!9ItjMCvzIt+0UMA44C>~TM?!+4l3b+0)i zM12xiANt~%Y@f(UNl!Lq^F^$D`TYN*g*Q{=EwE?zn0~|2VSz!^4}S?@kk~m(vd?x$-nmMYC8RisiGOih9stNZwtsM609- zT~ygdi;4LyJi%FG8lvqpJNT+)-c^`Gqgf=-L;^9noKCC!{%046LoHs%tALHZ18C*Z za5ckXH)rGOEO7}*!O0hI0M{hwzB^H6(c?u6OvG80@8#hKG(4@6&x=nTx{6Q6#bEre zYwzeZX>Do$#v;CPa2$^AulH#RfU2b&N(uNo z=E<9*Hm*pQ)2@$PH%o0->LRO@mvJw8mY0(30D;+`V&uQW%0%M9r=RXCD6U zcT?xM_-D!YDD2C-k)W+s|FfgYhx3YT@sY;YHC{l=2`ZSK_P>4vrZ!I{NW#nFMxW2F za?k`czCF(N|I@x~{7-GuovHXW1)nw072_B!v}S6ET;T0y)mUd)b0SRlru~m}fad}B zA8+^D`1H2()}f@xF*IP%JX+77Ok5R>Y>(Ot6LjFH7rh=nzyVz>x9r>sXuZm8-i(R! zTT3Iu@;`5%a(Xa(h{=9;$MClwR4qCvDQ6j3YKg4?c{9YwOS$MMC8^9Dn#j&iXiQW) zA-FeDx8HW_waH(Z3U=LH9ZY`bG{CTYV{^Ah_-HX?t>;kE@A{(L5OW;`cu=_ksd-(% zgMVz+VFrvu-t>PxFa zJHN=m=ZemT7pi0q;2yBObY(dD7i(a$@Aga|SeLjZ_ukcA(*pG@&IhoEyQJk>d%@a+ zv4J{&Wrrc5bbbX&U~!l$#;5olUu(ueq#_>u;C(#64G+A^oQ5*V#{GOQw%T6ZUWCrR zG4eQo9W4l2-`qd>ytF%W+;MNjc_$V&`~9c*{Vq@#1Jt_ZFpmLg)&PG?p*}KGsD1i` zsi}F(Nu5#CTq<}m*Sfa%^K@NR+X8ceC{*zhL`#+h@SpipQ+r?+Qo^o%f){T3;WAj-x-Zam^3*a^sMDU&*`I3gx#ohI^pXU;9 zmH2YD=c3hV#Z7WiwrI`nG!sPt$GdN;R17d)T?gZp~R$i`bHU-razb+=)tbtS! z*9a+F6MX4E{b5{sO8;`p3HkjJLT4HMZVPK!zkzY)Y?)#<>lBQ`eY2Xp3%-H*)QkH= zcN9)(bG@Cji{?a5w;Y81=2b|}fSb?HiGA+Z`1yY_6P(FDB&m^5+r7nWsd`@dY>0g{ zKIhYKrLF;Gi|91`D)qtTYI!l)9Ub>%+a+ z4mvGYLG-BkT1b17tVDdDM^Iso!CS6r+3ai2w+zo+kb)tkJ#c=wo z9?v{8VR@+;2tt_|b!?d#ZDg+|m#zEtjv>Sss%uXZ^1W2Z+Z>7?b>3x9 zJOw_^uWA$SMzg=?AjTIYRtv><27y>nfmto~A#;;`xdAudP1{><+VO(p(9V&))M;d*4sfxG7X#IpVNnC_MNp{5#_cXS{S06KJa z`T~S$(Xc7KxKgElH*Rp$<#QVgfRnug}pZN2-ws(@PW!pTx zygHMoN$2xupOEiXCxbYSbyzTo@oZL^Mv;3S-C0=r13R$f|1;9ShhRChppVU;ZViv) z!fNYlYT_?m(|5H!+#M|kJltIZLHlfH+^OyE;&`nGk4mW4dYJlOY;C+qRT!Y&&7Mxa zzBd5-EIG**@s9JbrAMySeEt`12zVY+I!!AGD2OS@=&Q;Y_M`pH`2PGa3m7Q20Kg%K zPGNQs5ty>=+c6p7p_+(8$sVtJbT5y{?XfcKk)Z(P)E^$X%W9u8oZP=m+@H_2qeecu z9@e-TF3(pe2{-Jy-00AH^`U)=KsX7P?OwB1<2fq%2S*3UH7EYEVQ{e-Ryqi zYbg_$^&&f*`+yRJwm02-G zqnVA3ma>~D9}mPW(2-&xcorb7Iap03HOYtflAAs1a|5s)q8e#+)AUB&sD?5DVTe2! z6F*wucBKHJuGNegOEOEFsG2ZbM`}$aQO6z5x<9wwS22K#$>ipqJW=s08 zwXX&DFX)flY<@WPJsh$h5O7VbSYC5t2G2u|m7HJk?nqR3+7A{FH2Ya^Vxk?%sTjQx zk{qOEeu|I$Hqz6ANSB3Ot>5=3lFdUb|t^zq|b0WRc0svQyphqtSzdii#95XVre# zRUbh=6r;K?L&d&~uGe1r)x0uu(jG7`>ce?Tazrf9^ll-3b^LlR!FtOS?nC`7_y8=i zF+FxqK30O8` z2u3sTJp&%i{2a&?hpu)36YKy6SWUAuabCeboRtImviC++pVpA1bgi^=5A%@Nvsx#N zpK}ib)#qu+SFqz-w}!pr+bS2r&W5!0s9KHp?m|CJ?Dt3XnLs(79gmrBnOO58PKcJb zOQ-$ilMcqiXMI;|G?(g4yQO_-V)q3OE)OaW@ixk{3Uw(}P(|adxJ9AY#S;#TCWOW4 z-&+0jC-QTkFLhrQUl?}adRoefa4T^{NoPvFrq?1EB8*CE8KWypyRK4`lC}hZf{j8q zkUMAAg)dM@aHq1-EOR825d*o{N=}GwbILiKMs>c_ajzi`KZLEJbYp>1C;_WA5qhuLDyg0mArLi1|pE9^YPg4D1Rb_%)8CkA<4V68(;U^^N~F{?n_&uj-N#LyC$R z$)(v%zrO>ragX#4ATxQg5s#`H!2G;VH$@+APXR(>Z())DkCt{kp{)*-$bWhxM*P5_ zoD@UZa(gmBkN?PpN_D>IR+_Xz2h*lad>s~>+&MTn_NFVBzrOC+ON%5QYp26E2!GB6 z&Nn7y;W$2QK8oAT8jC@ERJ!Q9=zE>MUo)~m9D3*G=4{mETvTiRrM%IKF`rRA*oF0uyErZtG>*k<-*?Ws>sW>)t#N+@FC2Ng^zvQYK<^C4}Gsycd ztm5oOW@cNlHvF~Hjzs=A0jv`($;9~%WGhhoGT&d)`@Rj=2L-=IYg9+0_k6CJJHBm6 zX2-=o>b(Z3PEa1{ie~pqtHPL5l`5rgLC-eCils=j1xsCZNKTJ1oFW6mb@m>7a^!&! z9LyT@bAZJwu}dSVebg$B62URq&@;7;(n>|gq)9{%AvRC{;sdK0n7BYludA3;8(t}K zSGv0kul{loAU1*oL|(cg^f+nJF|4QugFY_4^HK}cNGdk2t{>J?sJwjr;&K}dEIy>uPDQQKMINpM&B5M_}kYjsbt zKataj_}p;A&HUlpmylql6GU`sg$ComOjol0DQDLHrzZCz+9=4cq3qr& zM7|4w+!jMmNhz57W{Iy7h^Z-%4cXorn3Lvwcgs@rjH;w@s}*a_H@#Xxi;bmQ=zqNM${N|Mb3Js-76KvCp5 z58uf=>1Wm-Cq!L1b%ItVMPr{8ezzy6qDiK#X;>Kd(%|;u;_(7xDqpDgLc8bI6vv0( zmbhjUNEwN=)S+=f4EbBx-8+Qx!It9#lc#TCgHED+A?Up4GVIXNz>3%ovSyfm2jRSI zU2?zq(5E1zyw@hB@625&D`|GP*loISU%PmTJSQT%KCp8unZjE|*Y63+fk1*xps_;x+8^Nnp+rs+)d6rD>d^cQ;HT2cj(DC zZ>Rn^zaCbNLp0EG_~E@s5`mpQqWaKFgbUbA)lZ3^RQeLIl-RX{H?KWpr;bpVtGRwa z7OEVfp0#h9tbfkIsG#xI*`i-h!w4YNrDkPU3sp(9OY}Q7Wmwf(!cd$Qkg(Pbq77|i zzWfd*yS3I&OU(3~`gjxY9>m9?%W2TlWIO4Xd$Gy(%XXI~5M8CR#VNkjqLu_Te@LiW zfOI5^kdqZ2h=;WG#ly^~jmr#SJD7$sSddw0}=rJA# z_aaN}3A^0u9(<{cb;7T?n{ylNPVh zJXt`$d-c`qXN&h~R>1wWb+%t!Rh1@yfM5X4)*vX@hpv=-&Psz=<4(R~y;n|RekFqw`)CM-~qrL88CpEmD)mv?=& z7CoFT{?H?Se+<0Pw!6Q7`|AUq0*9ilqKl%JVxVHUZN8il&s_H7rsEvu0`!ito$8sm zS^(x)94)mT92@}8Uf3USvfc-z;g-THmi+MqtZA^Owqs;X@v! zvB!52{#!WuPr%G6eTG6f@YA(O6;AD3%s(PYm@gmg4@i;nk>uwi(s-g*z-UE&|G2wc zeuyx=T?K%3E0Cty+udCUd|UDsDKHhd_iN(!YZvoQ0UL>W1?9Pnf+fmx-bC{&9iO5p z1>=MMm^Vf9Y{q=d~(~JU=fm{);IZ^84=QbtO?xy23$nkadVkn zOZgY*zyAx{&LU>Z0$s?!@sFZg=qyuqEk|3&E4%&q`r*hLZ!_<|X^lo&vIrgSJpO(7 z_X6J0{+3MOx_3bXFaWUt<(~gSEdR`3Ru*B++?-(*-QR#sBo__T%#%Goc=30VKWch| zpHM+Ur=L0eRf!P+E+XaKr9z})m!eM~s+F@N5MHw%mVju`1d(XH3eS?}A_F z+vY(#-R@>#k0-WO-Fk3n8(D6K;CBLF^2g;TRD_WqiOZ5~f9L+`^KrYwcd`)%^Wne7 z%N)t35g$*T#WiIbMDD|juxY+8AHw;Dn~&udr11b|$3SHcEjhbP{oDPRM{4X8z*n@E ztpP%mL$2^8MQ8g4&Z;WEmLnNSHO8Dl_(>1l(27xen!TK7^i^^n{V!6G1fgO}%K83f zDnZj3W+P@Iahw(rgHT9P2;;keGTmx|H-Z z37z7(8aKYg_zNc{Iew?cNJd5$d5+YKto@HG^izd7aC4(kt32qqzzv-IgBvl+?pH@{0YI;-^!#VFwJt zE<_oIA7xHuL_zQ49u3+SxGF?ks>=|XdP0$WKJ&EOXMvOV#itaooQ0H{wBzS_4x>hObX1?zvd{yc1i!!?J!7;H zTg@odTg^IGO-v$cQY^hk(1XI7PA5jZvhzmH5`pi>x4uwL$Xlp561Ag?Y9|7S83_Qn zn&05Gyo2t7?rM|bTFn{!@4XljKjH7{qMkH>Q5BUPxt z?v{VvQ~zZ%i43CV9`5H&N+0e>bOAQ_44D#J$+KLUtl1Xqmxo z2U&TFDo`dq=3fJu7dh${yApfkMjSi%HN8Xozb5WG^cs@Mte0m#p#j2%0?iHq#C!O! zh|wCI5KhJkK?F%S(H)y7tpS_&EfRV;kf4x2iK$Ni$g>Z(QLW{6ver#CI&Btd1BjN= z|EhcZZ<*P@$0_wcU1ip7|8z@CduJ~9W#{J+DYX#=D*xq$50s>@C1L+2{m{x z_6P#pt$|Y@4cD*n`E>*EQ_xE!mc>+^T{g47|CjjwCo})g4Z@~m*iJp54Ud?|2M@pI zM1ra6`*;7|m}k7ayk`o0-UWcymEcDLvk@Eq08;+)QIxY|V^T~}x>C`W@tk&5b=;@|D}4 zDhr0!w1u@#9eN7+k+F1hB@4&|iYwHbchd^h+hNPcfQ%K!;AV7lUKPv~#)$@sVFo4-I+w|`-%fl*gIPdA2+|^FohytkIx{N7 zx7A})A;e7893`rk{SEH8yoP0rj=^pp{Wnxmqc*C})N8O%emFm;RYZxp0EqS{y$Rgs z;s)N|1kvuA(KR%FW1R7357%0lZw4!#vmB+0Y-Y^^JZi>ApE)}v19{3~TQTn78A>-m zK;Wny$xXQ7QMDphdVR(?@n=VK(>z0jurhND8AP7~>@=U>H*lbw-pJ6ffB@~Bw2zHuVJ9^s-Gt9`qBpU#CcXx;z83Je0`j<@E{Y_2_!`%TH*qE zxX=0xe0w1hfM!Y04qmK(HVKdQc+c5fRHPNC^Q|_&O6}DvXPwwVE%Og6Z_2pWf*e*n zSQ|ROFk#?{@XZWZHkTcEy=>rrv0$XfWY}FDyAir?#u%D_n?4S)kN;Iecp?vVTf2Kw zp$d}VR{R9WN$2p(RMm98^4#3O;g49}z3Q!F7dd}ezSMcr6!#B=K4(%S5Gt64sIg>6jp_up|T)T1ZnF|e?$dqYo^TSKAlYOUxvmAAb@oE01~ z+mwBhEz9->N_ij%&X3nOH5Iq)jY&%*_v!3005o9+#f~BS17jrXtnI2yGL9eqBQG)q zgyhdc@yJm@@0H@r!Cyvt3{*1&oPnC0cbuxGr*R6B=tdoRx?3zZ8aO zBlXoxJWW2Pb(|3pky+{hYKvmIM4N@Do;mdV^Jz9}@x_g5^^4Ci ztqFyLozveW)c6m-eST17Bre+j3g$`8Y$9BU0sQ7f!E0+dyS&8XA(bV_mx=Ogz%K&Y z-=jBOTY|Wby2O^}M94o04^u!CX2|r%|I{7%I-UB!pE->+lqo_hEJ^Sl-6VOQeqK}# zXnxTmdS_Bb^bHX`&U+J_$GpS8Z{fO+{Z$+-qjBYXf^B3Zn)E#upBgMMh^?&pe|3L7 z@R~rcODwcTznq#3ORBQBB)}0)!JsSb*gV6Yr@xw!zVC%OzLU4eOsOCRs;2<3*k5Zq zPEJk^{9s4Sr`rj(1N@iXle$v*%3t@s777z?_yCEiQSQTf;)>xJB?g||3#{=0wMGOP z-?M_KwBn+l={-AINI^x^j+^H=)-RdIaNpmTlzq5Y9L8fj|gVNb0gf_+XI%`D{XD*Xp{gxi)&0F+tiv!B}9O@ zNc6o-Pf>k(A^wB~5PU&C_T03rav5ic%e0A}zV@$Wm=tsjXZ z3_kvIBKlwZ1_+SFs9LPh#6OsiZ~IS5%ypKv|5r>0{K8`q)EOfoCsg##5Bh(#apmz) zcKv&b6d568Dmy7#rYSu3rOZST*|(S&dsOx%ONC+VWZ$xHiIFYKBgWPwk!2#X@7YDR z_YA-1_j!9i&%egp_qorR`#RV6dtKLIk;H;!R0^QY&(F_j^_S}et^#@LKUVrj@pd_6 zN1@4S%!+SaZ<*YrfL!*oIg6k0KHk=hJ)5hZ);ay*r8E=@1rz&-;KiUql0{2wHu-$q z`LgfQ=$<3I1J|M0im-rmfW#Uv9h>BJbn~f-2R?fn7aVF!b8-UM+cEqbnzVyldBKnE zMSh1=`Af!+#MLuti9dY4)*jI>glW8J)D`jd2fL>UaGpe*2Ag@8M`BX1nihOYos8OF!+N#Gb~Q|t(J_gTk2M9 z64#JffE&WnIOxM|)#ndccp6%3FtgF3OTP-GM^h4>t*f8^i@@-n72-=4r5T0AY;0`w znuI2}&gY4gV&r|P+pOa!UN3!NVq<4ux7@YcGetgqfa4gca=X2gG z>+VxhSDFy3e-A}Q4Y77ltc*fbe_#y@QUv8CU*5Z8M>VT8XkL;JRg$px5~#ZeVu&6U z&!mE+7hE|Ox!q%;A6SS{Lm(Ppf;1L7iRry9+Z09bAe)~Oz znipw7454;*-tAl65j!&o@jXS4kIE}4aj>@LdN|$^%8dryCb5XLBPgjkE1<1bdN#a8 z(6R!yIq&pa;bH*!rX=I=dHz~ax-O}ph*nt}S1YE6GNgc;D*<}BK6A9GJr^b|Ob7c# zOY+-O`iyawRgpiJ`WKxa4)pnP9o`dr4zEw4-A?^@T98Q}2G4vd{$v7WKt;+j5g&4F z@;yc|6B&!!{i+I=?DM0E7LNL&c!}>0a}Vl@v$RW))T?_M3Q*cp$|n;-uZ~3~H?qEz zU>jV?yEl(jF8idXep$k!mQEqcPIV(fjf?4QbcULw^H7c>B1SSZh zj3G(M_zZ+I6;L1ywAMECdjea6Y`Q;M`OcrDf=(g!c8so5tMh;j4Esc8iYme?VQr8_ z+vBhM5&V*In*$g9MiRbI|44pO)8Hq)P}!8y2AN;+Z;vo%xZx5_X*QbeAwg0Ujy~?u<4}QNZTRjdLLy?(~g%P|E;6cxSQxKM25^nM=f~n3X zYha`V4{vf{_BG0KvJ5Ek1*b*~-<%shDuR}Hve5zLiURy?j6kfu(U3Emx8sUo-Xj-t z5E&Gx63Z_cBvc{_2a31Jh znd3SD(sW8tsLJekW19aB!`SV6y;<#hMT(d@wwOUZbuBU=MgPpRG*X6ApfZk?D^wyc z4xKfscp~zn*Ov$PnPapxao3o2lkn0THD0F+8Mn%-!n=<_X3V;IFfyy&nDW%ADWfF1 zx#E(NIAveM$s|BdD(-0u_jl&jo~Xf{E)?K=2+`tr6EDnKAaD??UR&xkCdx;#7bspD z&*tuYGjxudYWT){7BjxGUxP{~VRx1e9!=2R-yyyMnjG*AsPcpzp_nRO zD12dn@OO}Z3?I}fuM~tQ$)cMz-Xo++H*@7uvI%y^-_s>K{uYRqVHIyPobR6`F|^FGzF?cc^`SHs%kuagTC6$;G{!Vin0VM0=#}1*o=j6a zK4Hj+AE52dpV~z~p`$oh8ibJA1To$Ik1ZUGnCb1!qi5!2U}-$EfXYOC~k^#^S5 z^c*wo395*>D&hdB=ar`)O|(Up(^>~|$!%x?2fx<1U0rD3&HR7@5oAHxc&XA*>5E{R zj(o1ROZr0^75ge_pAw!j4YGwgk2&sK_v5ilh0HQ3!r?H*wMQNGw1^K8-tbhjB+4}I zevZ&1KuaI|LfH2Z*kEIOy0OP`tVws^JuJM4<|hOuv7B2{r>!mS8}WA((L)L!yq7{c zqGML@Zn1y(*u;ca@XsnbLpL6cH?2bu#^U&AhNoKQb{{>-{aUE9WRe&XR#r`zVxaNS zxvKY?+ug`tbQ%J?`drRo(}Mny!TDr+cRNIh9W+f8xY^s@g?FiHRsF! zVP|7~&5Ri;iRuN{I^%UzSct5V*V64O0-SRdvt}l-c(1c3%T*l`F(;PgVedv_TX-y z?2QJ1ar~ChixTs|77-@)^#y_U$nrhGgF)t;phGMaMZ2~jw6V910rw{xG7?h8^NUYM1~UbQ>Mp7hR5IK z5H)Qs$TT2^mDGhaSk*{23r+Ry(uR;!s`q$)D6@ke7N@uQv#q9&B|bHTA&BBo{ni-{ z5w@01-~2@zOP7hDYQ%#&OC96Nsqyd}0OK*6$R6;z3ST>MSh(K9s4(Iy)3Rs{%xMl! z9!e+1R3O%_BKrFJf-Qmo&jXuA#~l)ZsC~7heLX9_4jkpk>3q+9i4M*qJ($f;z(s@q zK%LbZ{wRofaXDV0mhMnln0(RUNh09r*+TALJ6!4X}2d?`( z{!5~j#cC?-Cx#LXf-3eGBLTO@bTc2_LS@aYpepUNFO6jpCi}>;LUay5RBIn7UOr28 zztqxX_kgqoLQ-BEbG>)(-UVazU`~MZcmL)=vW~{Cb0gzV2rMOu*?$9O_Tf6u!NI|B zb{Un}gNgQNUOQgOEPGxWUMMg9bZ5%LmpuP?*l)fhuZh-ibx8L*xQ<`2Y;67dF>(vC z%X75mbFb(Pc_NxD8EKww7P_%60>6+`4aPzK868KzI(Jwq zAut#4Ar<(rqYUv7&XbUbi-&reKWjvbd2KneAdJA1gK&(t!u*S8dzZ>pGEp7e7+$Cl z=H`j!g)+0x;3%gokd1N!HPa7GF?i;a(CXZd0xqka3?|QqQHKa7WA09P*@0=6KVB+t*u^ek zMj0Mroa-6CIba_*%{Amk=sIB{uMuNmsSKn_auA3Yw;GZl7N`~^IL7iVfmee_log~D z9+upeA8NvSoGQ6}Q|4v#O?c9#sm4+Q*^b2ioeLADccrPiwq^O27?Rb>?s@@b&0XTU zN=kOY1^HwO-8%F4xr%nZ;}^{)%Bz%u`LJjgB?ec7BKWdK4U(8FgA*91ntVK0Wm)6- zu6srn&NDs4_ffR$rnhsNWz0olzho+JG9PS zCm^~B&oUuY>&$SN^_eecs}A;ed{#mp3;}HyL_1xLjoH9a zG$yxTggcusv#b(e7)58S%6e@rNAe&w^AEN^`#k$B^XuMZ!&3bY>Nx5YiVnquI*;N+ zT|x<+VxePUV2J$?IXljJ!&XBCj(__K4dlNzWf-Bz!#AGL%_D^$a#~SnVo7Bu_n4@_ z@B7fSwQf@NGj|mkCaUPbf(K{EJQ}G_QSk;5L2%dZD;UrR7^?FWCy(qUKg9ZXBo9vh zmRxZg1BOcg1EPYe*!VAVM=;yQg~?S*@%Z)Kwe+w9znJB2ITZ{WCX;8Tv&?v>`XecU zNoi6>+ZEBxXq{mRvT9GKXtAXCOZBQqU{pt*BEyxI;-vT5)F&Xe4^=vhfRb0AIP5WB z>^kfoNWhU}l9c|N(y?a|ze`k2#K?ZJ1Pm4fB0<1ga2V4R(i8RB-#usIW(M*@>M|Q& zqt#^(agcmrpy-1ZKxk;F)^eKnrhdWh{{@V0pEB`Uxdnnj0l;!rs`=I?!Ye4EcDD?r zs^8xAEW%X_H2JwgWgLG%u)+%O1wXQXdi3dy@%v%7acH;sw}%xK6_0>13?xFcy1^_O z0b_z~N!{k)$o{LtH;4RCDPp3)2Vrkx^V+`w^XYuSF6c{L5VPat;{1#A&&Ul*foy@L z37oVBkjSfT4^Hr0TnwaRdtE$=Ju@2;LcjXxiD63dzIvGz&)HhzJ*lZfQ-b^_s_Z)xw?q-z_By+`~i>UQY5 zKBw00d{6uCxw-hQF3!iLzSOg|(|En7#(TP=kIfKF$Z(nSc#iM|lacZ_?t62+wn;km zWE44E;L+EFkFQGHCSyn57}U8e+Ro>#Ru=iB@cOLrx7#I>Xp*r+Yj0~}_P2IUuxKVGd_?0_08c%XKxwv3t_tx(lT)drFcQQyJya2NxG*4t$qR7720<*%kK!cVY-N$&->Bn7PLbE& z&gr#}CS9Orh(()4a=$~Ps<$q+6VncMr-9`W#}_(k$WI;oHo3p**QB96-p59{KozOz zzdM!W(9IBK6m8Y8(sH3(gX~QN$xIL%tpzbp@IFTslssst&(6*Uo4LHUB3~lSjRrpD z>?9hA2Ehv3ei4DCa^}q9)ApuYSBa=5xBgpCOb^;{*&*)&mpb`xYSAEL+N<#ga@VsS g9Bii@Y#&fqPaP|Ed{@*7ND1WjEw!6(6ixmA16i|U?*IS* literal 0 HcmV?d00001 diff --git a/doc/tutorials/content/images/vcpkg/cmake_configure_2.png b/doc/tutorials/content/images/vcpkg/cmake_configure_2.png new file mode 100644 index 0000000000000000000000000000000000000000..b1d2e0ff48264d7262fa7c324160b7908aaad666 GIT binary patch literal 18418 zcmd742T)UA*EbqOK~z9MMX5@cD!n&pp@TF50TBX(D!msGfzU(mAcWo_gbpG~uc3G8 zy-DxiLEr!TeE0dDd*_|Gb7w9yY?7Rlz1LoQ)!$kNn2M4N?md!wAP@*w7A*M&1iB>+ z{NBEM3;4vI&FLNR2gCl2%xh3_FWDOK=C-N0qBsat7JmQ2@DA`E=Ob9#9t6T`x%tIt zv&l6Efn)+?CB@ZU^tYy6;~x(<>|9^=33r@cI$oVjd)si)H@Qc~zauEUlO~w#p6cEw zJR<}nF;ahkzO_bnI1m_=-v0b9LlmD+x&nuM=2vknh~;u#(pSjC+eGkmKHAn#K8dr= zxEhuD<~!4M$Ndf^mtMk`4kbF3Bl-EQ4I;%8cLeu4=+l@nKQl<_AB!-<%wUy#L164z$)a`0iVcehbu$soi zLY0?c=b|p24MlfAzdoqJj{-z5zV3q0e_v=_tMe}Cj*8Y?HLKQn+qKL#UQKKRgt`pw zmxoS#A>00pFH%a1m&bgjF!2OhF6nOA^T|e!SGCcL*W>ru&c(0I#7ZXvCK2o6(WY0b zvlnIg{549Q8%pa91k=4JFr2lxGJn=2`_AjdvU{G(MclI_ZE&iyhiPU!rol4vEw%Wy&T%B=7D@|4%05~VUY zN7y4t$;(?%o@gNH5yT#)RqUFhsD|!{S`J)a-Glb0`rO5i_Ju}?NT%x5ASd4Rz7(=9 zj{QPeY&Hjd#K1>;x^^MG6?^W^(=_Mn)we7f<~R^Iz-L|ZOK3WCalrv*Ty#5Mz756& zzgtSUufVMRTj495P9C{da3r64IbBI~eKi4#qDX6+LsMGU9|TY$%T>C#aq> zQ~KvfJN>lRTZO zW#l?YV zDiMStOZCaW=jZudb=q#km-F4w9W$FF(K#~9%+4sH;Tr{*Mo zHg}+Iu+v-N78|rEpcD&ZPG;Sb9-`vIr|x52S%qO1>?@G7KMbC6=qjZ{F$t7M7dlj= zCtp>rCYtfV&$%|s)Z?Z`A>M39G9e1bP!r~7WB~d)m|U{#0&`M<>qd3y(mh#zBHii z>mEHXDMl4V4beo$lT?268mQ>)__%IMM?J}w9BUlci~Lyq&Ztec$|dvTH=jYO8n(XT zWMBDqDt75w$lHbOd&Qh5Yat6f_d8W9o@!XN&}~{TifS?pbYH3k+xiFY#A5iqSU686 z4@>8nT>Ht`Vwe9=Fk})C4RS^_A-kqq{$q!Qy?y%?wk^TSoszVJ3RQXhCi{7nuCEP> ziUDEd7PZ^iuh34H8-0zZjBT$KO$eP|EC}tHtq@Ot8}I-5u_^I~LWd@;8`e_wuTL_j z>FLi!iS|wTl(R`q$A|OPyGmb62a^j3o4lp|^4`D&Z<|lG;-jCX=K>-vzt4_D{CxLq zFZ-?SvIFa52KuDWANo}j+rsAYC`jdO=n`uclUoO5rHt|}Q5=?QPm(uq+A#7p+F-~+ z49ySuht`LC4*^-O$T*!GRm@L9T_k2XU#ujEZZw(v=;Y-|@mLx9Gs;d+BdnT>yDVI^k z(&|*nxSF1)>f5~7zbF2NC37L)*K1n>$L-Ea>XI`d8@(6Hfb9@?T#4F~nPBIMU@X61 z#Tpk+(X`q_6tthw@s^vpQc+g(55BDnM*Q2Jmbvjr{Mq!8+wYq%F~ay_+};K6GUX+E3c z)g#)|*tk7x*p(A9UAVI-Ygw zTRRbEQKvvU=ZDzNQhBIp1noCOXHEC)oo+-93Z+b^U5~2mz&rJzNR`s)=rci)fG8789xJ3nm(h8?BGF1_pR>nmk zX%h32lg~w}=`{Abh9cW49q0HLMI>~IQ4UyEoX!f=Ja&>P;$wUx@;rpZ4?rn8fQ4ip zG&;iATAXxyKXzK5t0t=_p*}}JRp`j{*>1yhHCCQ~a*R*s$iDx3t91$U7ARefNez+r zx?END1Lgz{Z=$=sMr#p}1QLyAJhF^hpy_?l$TnHLdI0)H zv=qd}DTNi3##n*3N+v81>6h}-q3s?Tc)rcB{xCH3sNJx^ssQ!b{-JAcKg(oqMs~9+dv$a0)lJarNRXXU;x7}oSOm0fEKv} zO6Lrw+ETuW?<7fpwg1OMB0dGyulwiuVeZc`&Ph8yf%iYvKiF&<$4TexB7$O&cbya+_*iy<()o}+(Lqw{aUu}(gLyGnk;M}$z>CYBY`W^BYu z=}Q_T@@BdS@-&ab;i&LQT$$oCyO+ina%q_TWdzXE7sHNBl4wiI@btW2tIZUiG=@;$d=o(x(kTVt^4LPBle&Rv>bvPZ^y)7TCRjY zzj!|RvlHoz853LNZ^^_URy~#dkBXrc?5G;yL0TbAcM9a|PB$D?#N!C;g7xCmdRE=8 zdu=cQ>w-)oXs&gUj7~hGb&c=xL6EPdQi+q?KyoJ$^sv(DsHmi<$eBl7T)D@{!pdI; zYRcp=nHxHjHb#2S@q!UG1W|vFRe7-<;KncPQhVr7AmTx#;y{%vO0uN zrhBS5jF9Q2H$ccjENf8ttZG$^18B?q9Y;r}ucpogGqJ@3EcBxt*__}ZhT$&Fz}@P( z7si59kl~)Yt+(^vkWwj@OW%?neXv7YLXpBV5X3mfwWZMjqkft9dgzt;FYADA!}*NX zy-YvIrLX`KcVNucn3YN@IEr6WxeTCtDWHeTb8?`!-RXNQV`bO2s)BNrqFc$!;9Ofi z{eJY_$vVtsf!vqDi#}+y^`x-1yPBrp)ZF*-cF%NXmMxP~>U^9t6H>*>u+YhT2K1&k zgHANBlH95>d&eW%fN=*MI)RslZLfkhpPK}zWloGGYB)9*=eoZtzQ>{anCo8K?R@nO zxQW5c>y=N%I2*mFc78u6TmKdywZzv#0 znQ;vt&IgV&(HJt%J-a}mYmFznb(;qf zcdx(@?OfJk%eKxU1-Qu*qUH=)wh`a+aP6G6(pGR4`;y;Sv1RiU9x#5q>073! zuLgLv&@|=>+B7_Rt~zox!C(p3xD;aD`4 zFVNj~^ja>tiz?6;qV7HHH73DI{%4OK1E$=h`qbCKjNN>1^)QIi}GIC3J}Bvh7k!nw|M2;7R}5*dW1unY;~ zSLGjR6hB3MCm$z&wGlR?`aQ_Hfkuo7{)AM*5saT_?n~6GG1B=2y4r4usFcp2LnWKD z4cKOW#Eg()f@>ZE=1}D=LhnM78tntv#vAjf@{18y3|j`VB!kenLxsDG36G_OYd&6t zfWF}$X^_hxo&grx!HpxPrL+l7_CJaWC@pW_7;0(NKrYJmuJ>#{z2RUc0{AlKpXoKJ zsCuyf80sQP$wd4>u5b8~IxyhYzb2cI04nkv4HA6_rDbG5n{#}faMRUFTrT70HcHyU zlGA{LCtulYj=7RN^Rt>=^k zX40Od>d6idL;QMzz~fhocB>m585)&)G5n1so&&C#=zz$2BXvhPT7WUiHzj*>(gRzcxYcId^z*^CC4P90XoldM`!}ru!EK+f(iX^Rcv$SF0E(#^_ zQiv76ERBrnM`ltP{1T_DGjm? zi?yeYafEp=$qJykcs11dJBdx@AJc~NbSHhFmSuDhkh03iiY>aIX#A3)L+H-0$XEY0 z&l=o><7N7K&zVA5Q6%o8L9i78l(vfiD!uz7Gl;qi5&5!UMMxd9LPYKRD-I2F&h>&! zmK0+{@fd{*3^PuE@;g!_0@d|!tn@*E2a)9T z4`NqJp$FfH0pUL8xOK!Ei3v!i>$3}7v6VP_v~h-XTPRXlMdUZf36|IjeF+4JICN_r z)^-FRM6nY8lnUcI&-rxEef4X==KWh@rgVR9*ieDT2H>Q2*4%}gT;H}kf4W4+_PGSZ z!RxmUs$`uHhO82NO8TKD;UQzmQ7~7M*7%rcRCV~DMehBxNI^-7=(ypSLU09tY^ZEz zd9DY7JG?0G*`#p`Q>#gw$@N<@$|qKRt4t+i4QVkRhOGJQhU4U4ENGpP$-zac!aPu`mW!2^2E(=-Qjw zJ)0`!YxPQQtW zQkN8baZjNoOx2|hJ*P{TR#MkXZi1!t-dykNLpcM%4i()mZ_^XXj)Hzhj+T3Bv~@i4 zq_Vo~FFtD0URq8-)%woM)I(xJkrAC-L?(M+H6F)!aMWu4=$%TMf;?NERvzxqyu4>b z(utuQ^xc+$KaDmmS?i?rT$gh7oTvj{Pdr_Vbv3_7sfo<9UBV^dT79?L??)j_M^;YC z&wa4LZs>@L{o=@$coT6=+J98~`GoWg@_ifk@{GG$R6}+rhB8}PU_A2W{mIF3BLV&Z zJNzUmH=C;?vG*GzMW{uvdZ)#BWB$SuHhm8vt7&SzI+1c#z2f+)k%G)ZZ+X?d5y#at zB6`b2e)Uo-1)0PlhY)Zy;fd=e z&v?BR{9inWjlWEw>d+J( zyUlE`Z9;Yij4nu>sGr9?t8z+EIPW54>B&BuDM?Gcrp4&C9-c&V*DjrSm9IS@ z@+jDLtgf{-(hNR5VywmpiJQKfzwgR2spXiA^x)h&e4+J@ebG_PYc9K6ku5&)1#gFU zbop1(_-n})#X!Ybx(QfeN)` zUw<6(%gfo{t`*;p`_0`XS^PzUwwy1GU_l%)W+pKxE&2%=_qN;sx+6b%uFT`_dYQG(l#nM+8CxwI z_6l5cl$%H=1Tu812y~}?Uz%E{n08V%FsV{69XLCeyd*VLtWEH!qK7{EhzE01)5N`{ zJz0(Wh`+yH*XrwYe4*WMIbSc8-#HEwoo`7yvCXE|TrR20SFCBuY4Z+!5vvW&E33m@ zqs3Ywci1tr_8G)GVFY8qs^4cfs`D^lC&|l)S`rO%d@t z%TBV^NtYGp*$VTikKHN|P@14r(%n~yW5qAB?OIDLO+H;hwglu{zR^%TUt-IV4ONfd zdGl5OZvG=Kr@S-j*2DmX?>LWb2+ezIdy2>Ao9Wn5s?&iUlb-K?EUFQ7K7yXfMz}dn zs#>*wuu>Q#^qgc5;yP>`*S{o7cO%&?(`$A&DQ9)J36M_4Z|CF0a)J>=QWj|dVQ7mzcql1RK_win8);`l^EOSrMm+W0XNjO0qP&Wh%&lpj7$XS7I?RP27^sa)%n$A}&JAvCL5Bb@g~ zogi-Pi2mUTx~+r*^9Q)CR1^Qhx!@tJqSGxho5NM^EWd@MO0l*<7fXklGu1C4!nero zuXru@Bppjn~1m}-L5=eSPe0yPZ_=~An zg*|Uyk!3lRw>f)9ZsKtg9uGORS+PBg7`kqq`N}3^95=;`G6_7W?CXJ`w3@w~o1Zj> zX3ua9x;~kDKV_n2WDiMfJp9Sf(GAlHZK;L0^{8g?H*laH4L>Ue~6q+c2!T z_BWI~b~5+b6r(7zH9Y!HN;Uh(ry)umYnG%5Jg6+;9kUW^oJZdkJe{bO^t*s?gx7g{ zDi#^@xz^zs5*?j$MMVv%lGcEDv1`O21eh-~f~}~ez6QN1Pf_rm+yg?@TJ+bW0%Vkf zn!F&4SG!8KbWJd-{C$^$r*R4{PlKi)|3+*`57%L8B8*Gp9$mfkY1)yyYDo(X%ucLO`XJCcfE?KO%GP>KoL~2@CZ)HO>Scz zioVRAM@?ELz1QM;S8g=cfk)(Mr`u_(p;7o7)zN!mo}8|@{uIXe)uKfrfZV7@-Kw9a z@8uWAvI3r2h%=w>ctIVA_HPW)lPc_PF!B3ST+;Qu7}8XB?l}B+)<;3PpJob#>?P>T z2p(q{kKc1P)~hrSES(o$2{iviKc4+sv2H#)sk;cAFtVw$^#kXzxlWa?HT+t1hXKA^ zel1AgZEPTlmytTe8(hITu{M~~W3GVr;-%-CoKany2FHsN+Xf|JlNs9~UK7=N_w5=P zui-oBzKk(D_n@%4p5h4%n!j3N(j8xRo-vWRHCJij8Wub8 zDMgr@ZkY%3TScNV9)uFFzfP!S^>H>=QnoLIs=Gp(G|N zE#mx=VZ20^r)rAVdfZ9oJpBTe2uKfSg$SoBofd>cp;){4;@c<8-%JsHamjH80T*xl zI=mlk@iv`?o>B6HQj-7J$nCY9w3&~pRzo~i6GLNT)vo)?MY>gT-(^u9w^{dH1%}c0 zxub3-S3-<)$uDVtfH|!Xy^JzF`n&}K&5YOBo4RM~{GKisO2chJ_M728Ngh3 zVK_MVqeuuT>0~T(qcvpVPnHwvB%^}i7?9AH_mykZ-KRmIoz1Bl``JcMoBBO}g%g{G z!&somH4OeUMZ9`c$X&G}BFV&L+iJ-uCb)d0Mby+xlXuhK&D+e*3=IvT(RPdN1lqYB zAC|YOW|f$SBv*owyL!mo@k@ySJXyEN4J?q0DG-e=&tw8CG@fSHsYLO8BsM4KMKAgh z!s$%OW*oWTbha$=1Ix=Me~7XiFNYj&PnWyF!GdlFW*@%BRv$l=PFxLyoBZyU)H!({ z7((}w<>ng=?#B~13*?lQ*#ayrcVj=M=y}~ElxOqAd`^NY@)6-Pawha5jRK-Zp6fW2 zs|KrvaNn{WNKPQ)<|U+{Unz=7JX>RBnR$7#bQdiF_+8!JfTkSJ7zs9|Xr_Yi?+A3N zERR2gZD3;Kwfhd~^McgbwX5IRbZy(J)hq#Z5)T)>O?PK z%*)@C`W)u=3W5lWvpgEZV-#vpIRa=sHT zsE)8AAL!9EuEo=K-`rhqjx!MX_|5U>bv6h@KGo!9pm-+wjPrP#GVi-%lmmjr{g+)O zZLJXUY!^OC(KsIz5HMw2V4Xk?l6g9PMKFl*nX8D38pRkOMMC3KQrKk0PON9#!8%5{0AFHz%9 z#3FQ%D5*ndKlq?QF3D9sd!s*;*g3`|!MH&0_udS9GhxrFumM$%b~dE=X}L}bI@WH1 z0CaIURSqdIy;?5s+I|PvJyZE%U?G7bpL7Q*tLcPxrPzA-F_=fe?%-a2@ z!ANUro(*8K04GQc7HIgnJR*-YJb^To7A5T-!)!k^ruz@K~J1p-~W z-35Ik{!ir@qqeY=SBBr!l!dt=ozc+2Y~kyReNMoaaa)We^V=`~%iO-J{y2~!6->Yl3FzN>Bs*fN3rKgRg_ga&y}W#I_k~P2Ma-Rq+n<=f(>$Uf zp?Th$%)ftiz9Vl8{s{H}2gY-i4ZINnNJo1;(c~_-`n{zYJ-xj za^w2y!iISWl&)|AL&`GI9d7dPsX*bHYeG>Ko`yYFO?B439t|9u9fz~0&EvxsTOuGa zs8A3xlQ{Oc?;!po0|7MHrt2+lUpFN*rk8W?rvaNs$+bgAg^iw|VXqOJ<;8aR(YyV9 zo5l}cu|SYt8i*9prh0?ywv*Vx0%Q%ZX)T_93McxzP*)#{H7I%gAjTYaMCrw|H#w>l ze{ynh7t>4 zlIyV@SI5!437GeB1Or~2_l1n7VnaU{B$O-j>mFucx|XPZ1BuT&ANTj!p{ z1F0}yQ*BKVvk;oUmYIkYNk|+Jq(P%XRuciU)b6OsFbvT1-T7QeO&+;H=dp7HbkdOV z?=A1Kh!&53T*IeDJ6%uqH8$?XSlt6L1ck$oeiCE1$>stUNioynK(TGRYG!JJu_sqD zze84}E~8^nyUJZ(=;O)BOoO6KIOXi=?3KoE%S!rr^#;Am~O(RyB4W`xph<;U000Y{tD=dDRL+YLuI-6mH%X`PTUJdh8H8eJYG z?zBAx<&~p0Jvj)<272W3taVzr53jGTdrqKD!!25kWqUs;mB_0vc{iF0tc9#EdXI-+ z7a3-8p@2ZjN)n+lWomGB2(++ye^iy|yVG>mi?p~JJh-;+IIv(%aO$~!JLEiH4im(} zn;JiCDsDQ!CS|>x+rB;=v|)W$`p+Eq3v{t~na>6`HxyGnfyRskHrYz~9E1HdQ@!Jj z#}aYM&!#;tS&~>AHZPY7EO|jR+0oo`_Wf zg`0F%g4gEe#Rd0cC7sd|8$&-%;91woCOtFZ2{-4^!hc5Ca}3K$;*3Ssy8T{E*WEVa zpIQvm!3vNYk_?S9P2w{fVyoPhOHEyRXF0l2hZQ!N4S#a!a0prV zPxG|R2+C$_LE8f9fk!*N%X3^5PIhj(*5|wJXa$Yz@W;d&a`KbvxS4W!B$Iq&Hn~Ob z2PuXO!)yeWZJ^lr_nZa~!g)bHw;n>5GUvtmX3Jo2l@~XLy0>$6W8w>2dW;RYYXt2* zo?E!9#qJz2NS9mmHo_|GET-JxW+t8ap3gTUD)@{9Gj}>fiWKb>NA~ele(9_9pgn0R&49YMJVRGe{0$aBIvxH$%;~Z zI1aEHY_qG8kY*WN$+IXAeU?%*_$@hHMY$CmnulK}$U<$Xm{Im<^Zj@)CCKhMn(?`? zGqIwtFF!fxo&-We3^00xp}HSID$oC0F<`wU(B+K*cICtpf=v33(cLyWJW6iEvGzR) zO7i3OKzjcN-WPL*M%eh|m%k!Z@gGpw?tJ^|jQ`ZK?-r0t)Cyuxx%Pdl!xnPb!3>|` zHH+`Qz@(($H*06W@eS|~^>jH|kdPMIYtLNp4V%iP-98VZFcT(1sfmVbzP9wC+F=PUX7_75O&=te90O3X{V{(*pn#{PZ* zv{gw_0YmC@bmw!)wS)y2M0TXpww zh?0~#XxX=50^zt>WdIx~R_Ij7xgYs=hhvXzuriTCIk3k!xyqHnQoZVToGm6#Ty?5= zA|`gcbaYuwk`K&^Leta+$kl?#@;vAxl+VfTm^sIUB8hh{RF_Sa{dp-o!;qJK`f)YA z`p()?aLsRI$o%45SpF}Z;`Y5k9l;EN{#xIh=>sz<<#8!zg}j3_DcOk?2C=#VGsNYO zVg`H;LL#AiXLX^QD=Dyx;;ZPa|{fV-d(f`!t>^`{nejUUWt)Wv;?W0ucx zL5AGr9QfY%g@=+$JWJj@Ld@Z|pbm0yTke5~Yx%^8DHZO}@yXmgCPJF% zOsp)-E$vx97dzy*E|056s=sAiUAMVJ8jnEzC+XtEo22H`_}OyS+%iJk%3p-vF|nE& zhDr*mMT1q22JBJ|9aw6@BA1?unX2w-OoVT1GZrAnLff8I8Cxe9X+m{n9Cof&!^o-Y zOx@Vf1<1Iw1J^vY#yF?bZ&{B$*?Lk&{Sutivp6yC*qiKfGUqv=q^lc-LY9rgtsv%( zm=*HGTV}oQ3)bf+Ut9e=&rdv=`>vP$khCXOJ!NpbdrS(n0HqVPKkTm#5Q(VGn=lCxvksrw@xLv-be=1Tk| z+*(HPZBmPLe0ow1p|BZ5Un{P`D%N+hohQ&@(Rp*7id(Ucx)Gz%8Upn4BMfQ zJ;pgFDN}^%tO9gcAPets7t(P%4e|%g5C!Vp?}xoh25$&BsKp+mpG;@#E2db)jC`W% zv3dbXi1Br{C-gK*YUXk~T-4wwO2|_fm7*TE`|t>gSZNgcoMcxh{>mXki!YH8`oZMLSzA3nbwQLYYzm{buKNJ;U=fJ{H`ZPo8b zV)V`gREpCs-3N&ak`rO@2AQqs_LJQf;mneHyY88AQ7DO8R9;cl_#2)XDIK?bwA2e- zN5{E+ocxr8x<^%63GAN}-(NW_50sXv?eJsa9|v&HeKX8iH0!;qBr_?r2{AV= zfg0&b=a6qJ;#mjHol9wlTjRgTxlxtxM@`!R zRjQ?KRVC-cho4yPP1CIxX7gyMi()o^_1(+#MA5Ok^!Faw9@P$JKU-Sw;3UkH!nPB{ zGV*s^XTQto0sy<%IVQ*1${Mh+h$Wp2B6~{wfl0$A;}`sa?jWg9wO-NSF(23fq3Od% z-`PJj@eYgf1#yN6-|NTG;6a~^O30Z~7jbiN@>iJX4>)N0yr1F;N$byUiLpz+)q%k% z1kpO{yCufj0cLs%ANfjE#8RP$F_`;+_*F~nt0WW)no-0`ON5y5(iG!4JrxVRJz>gC z+WY*!?ID4*4ng-_*N0HZbMM!G?5fA(6G%?)J)n!^#^C;+!)hVigktp_Np49=9P5X@ z`JXpkqQn&Dp1rCZf0Ok#IrG{Pwx+ zE?S;VR;>PaCllZiEX>T_HhP>Elr+}bEp-kTXq9MJELV=|yX)x|$WlFNZhgZODfdM> zkt=HGu}#w@ie?u_5q$#G=Az%me)L)h<)z7j*p3Vh(QI(Stoc!Ya6g)2ngjqyMS7ke zP1iYhEjHQAHh#v&mm?$Nx06KAjg=YQz=+yN*}(SNt)V=%atFbpj$6e=K%0)36aWr^ zl>co|7e@%Yf4*d3+KXcUlj!aVp*8W=BRi&c)l20__oLFrZXmw49k4EUu6!J})<*!_ z$oCzEqs%|Xb+e@|HE@A)@fu}x;>4MNMRM`HW?ekCiJw^u-4d((wf7Kcz7PsW#>U1z z#@Dw_`$a7D10QttTNHg#FalDc{ZHLP0=5WP)~B;Gw>2uDa$avXkn!a{ac`Qa_e{Mj zkT0ijn)U)nT$=aQX&wN$rV5P%FxfZ3KB4{YgSA0OZ(N6Wv+o^3Y_^7j$lE`dO6to2 zK-1sff2k`@ezWLZjosn;FaXNAZUHATN^|!MPU=VF&hn?bx`5#`veE_Vqt5~ltF)2w`N5^{fY6<$>qbfc+W|iU`~qc(NLiL7fUrME5*UPT5`h0W47{Y?GHjFh z)I5tA1uB#W8>7nE zXM)?+3&nNYkqOtS?%VLY5ziy|B2*&GB77p^BT66A@hJq3sXzs9Vjdvk+H4wVygJ(e z!u!gmOEA|!<_;6K=;gtn=$3nZ>xiE<7dZy#YP`&-t3>{OVL_n!X2hK>r$$ zb!BYAO$M3YTaW__rBij10u3+@k>hU|hyS^CQ`#KpGXjAgs~&+Xvcv?X68E)=q{15) z4x0ABK+wgV_haG3sfJn1^3~_JEDL8xE+0ezyk+=j7x;YsS2aadQz3N`RQ6!Ua9YTL z8@O`y+aYG8r5N3Mv{pg?E~_Zbbs_Y#q72B#+an11Ff9)FZhIeT_zizf>H$5X^O7OC z`BdXa6nJ4Dpk$`-ug+}!C!P7X&xByela(xJRTDD{448}Jst`?g=x`-o_<5lih&t0d zPo6*n=nhud8-Ld9jd2N_V3*Z8kqd+Zxu|yx1ys?>@HhD98@w#ZL|N9ua3Oy<56~Tb zkorCb<+U8DcSGN9tTH@SCkqgf>^{Qd)&(SKU3?e-5dsq*HE`Xamf@rD)=(K>BdL-) zseSUm6A_?XLV%FP?!^nj0xpVqY@hZ2TLt*ng*jQoo-1ItyfvX7`hZmM&r*f<$z%HD zFR39C7Uu!Zq|3QB$St%$K1zHQ)f@d1^vTC(H(PCt zlLmz2a8CeTy>}Nh{Lk6_f4ps%Gkua9;cMFfFSJsF)QOb;@CbBLAs59NwJ%?Yb_t{e z@cqy3D4=Bus|{*r5`0p`BH`Q^L&8gek)G&60Ns|jz#xJOQQQIzx1?z# z0@|9Uoi%>^mn5A3K$4_PFmkTpnjW~sfc57(Fcm0um+J2kD)Um|>tC7cCZ=lUf0dzfO}Yi4jdZQ#^E zLH`oE|MUtFM8$RJl|Uu1$1K{L<$>)?AW|>m0t%4-Nw3;P1MdJd=72dnVr;2Hy-`m= z`2nK^Tq5tVK>4to|5HMf15VsSY;3RfNx}m_VwJn5F?6PMD{*hL_8y7?oc`}T`Cll~ zzrXs|x!;(K^v=^Kf0c%X7rlJ&hSU2PKKUeUz34-FwsHdu`MKm^>#Gwi^^%?(mwIbV z?pZTJVUCd)di3b@#sVpIXiQA$(he1GHhetZ#uu^HK~EJ@S-qQWWSL{!Y7a8Fc8d%{ z#yDz?cH9NDZZzz_wgz;D8pk}T+pE5Y6>R>dKiJTsMQdK2t<#79x$l3|PT)x-WrJ<^ z;cDicEJxqJvKw`aYHLvIOn=zuqI_uK1^HSl^^Fr(Y5aZVE6rwf-Qr@`-e|gq$hl5 z61J&PfY|@4`cAd=t9#5eC74ouQoy^-t%w(5HSDM7&qbu z0N>tof%n40D4+{&2c8MQ1x7V6BD8Kjzp+cl0YR=mFzb=)C=-Na#@{nlK(JKe2T1;P z`yCf2ZE>@^o9jR%w^wlL?cr@`qt>{-XHqFA=<>?N-=HCGgn)8>r9=l4BzImg(q?>{ zoCD}9zHzY#u;39QBwZpK_m5MJM#;&~xD*x@Rc49R-aM_XE;&x!(^L8*+jft7%L*vy z8@rWAB4Co^j(gNS4{m{WVG27-pdQ;1WuC4_-_T^kbHhetu+88Y`dj| zTrlFxwYlx$e`%)1>+IuuQaThdI$4VA`LOh|3 zMXk(}|M))Tj)UzRuhLole|30R#I~&O2^3}Fay;!k>$*bz z>?V@{syl)nCm$swBs@KZ;aKW1-M^?Cy~ddoT*nQL?%7AIc}~|l{)e)d3ji?rMg0lu z`0STMI{5#)29%BhLKkG3V2z>|T`(eg53pSCn1y&mkuo{C^-RX$azErjWnf0 zyRhN<6g+^_4VGP2!9w)y?G*d9Hw5(%J!=p)^@BtsCix*amEx`Ml8KVi*r8m2%PD76 zM#ONCJLiL=q8#mk$DBAII)I=ay~~;&s2T$=0NDrhF^o$svk4zRmdkt_U#C-9H>py) zgYgNp`OXiixXj`(!u+lo&EIT+WR~^A`nwpZ_wAp7T1xw9Np>zK}8(P#tZMiskm1c04o72m*mb< zwxfE^9o^nQ?-BU+-{u!E7g!9e0DgOyh>T9sG8dU5?7@Rc-_r$-SPn-jiA^(p2C&gGkjutl1T5&d{s?%-+`YN86xZ-Q+B^(dX)$U&Q?H$UmYtmq zWXn#0;3x@AD)iCTWR+1H-p$@%Pj}b4^bLa)E*s0W;w1#oK&ImW*d-vP1fGSg!MZUX z;;CRk+xZ`pHcg(kRElA3jJTkFI&y~?I_v^T#2yfwx-gSN$>$rmI%t5~`{_6uoPW?$ zEP;VA+97UG7)Z{5gp~$8<8^LTLqP2RWiUU12K$Vvhezcrq(|9D0svbx6I}sd0Av|RnpaG_<6nrsazC;J>c{>-H&z1TRo;s|!_SLZahAyF zm>@2giuQ}d;bEXnht>ulim92&IP395-c~;f02{0(c{)tB9eH?otbz4f{Ba}4EJlm< zDolC+oa3x+_EM=g9x(1~9S5vk@j&7}GCJDj*W__(mvE|8qJKGIQSwiV)ZZfp1C{){ zvJa!^cyuOue+&YxEHwFvz)w;VfU&c6{Q$b&jE!+!jyA_dulB;rm7?z~3}njS19|8< z&EyXZMVsCJq#wDa_uFy}odq=H zaLgsqaI({hKev64?($Q4DoXcBAu-+2tfe_K=kJ z5x`hxj560Q9@%@a5UWY&#FGdHSwH!tMg^g*i9s6GN_U(6)ND_8fI*YqyJB5myG_$P zpJY#*?=;y^7zjD8NB>AVkw`9FoEcFvCxo?yQ^r|FSEdx6bpKYOQn!2iB!+P4ujDyv zCv=os0!S6dT$g}?iI=v!?7t~sGN0}1H!U=Qk}%wujChyGWJ1EXofOaGO z#sQCav^`yC&=dptpg{Hf!7CV6l(6A$JofW1xG^6RA|jC-G&S9yqZ4lWBTkp%0IpWmysgf zI;SFZ|&NyT`kSa1?aa z{$%b_h^%1;*29X2QAUx_x%lD65RMg|UD(UAz92YSiZi&nKI~9LeSN}p4g8-TkgSxF KWby0wzW)oOtILl7 literal 0 HcmV?d00001 diff --git a/doc/tutorials/content/index.rst b/doc/tutorials/content/index.rst index 1175e3971d0..9ef736a49e7 100644 --- a/doc/tutorials/content/index.rst +++ b/doc/tutorials/content/index.rst @@ -97,6 +97,21 @@ Basic Usage .. |mi_3| image:: images/pcl_ccmake.png :height: 100px + * :ref:`pcl_vcpkg_windows` + + ====== ====== + |mi_4| Title: **Install PCL using VCPKG** + + Author: *Lars Glud* + + Compatibility: PCL version available on VCPKG and Master, unless VCPKG updates a dependency before PCL is ready for it. + + In this tutorial,it is explained how to install PCL or PCL dependencies. + ====== ====== + + .. |mi_4| image:: images/windows_logo.png + :height: 100px + * :ref:`compiling_pcl_dependencies_windows` ====== ====== diff --git a/doc/tutorials/content/pcl_vcpkg_windows.rst b/doc/tutorials/content/pcl_vcpkg_windows.rst new file mode 100644 index 00000000000..79ea37fbed3 --- /dev/null +++ b/doc/tutorials/content/pcl_vcpkg_windows.rst @@ -0,0 +1,143 @@ +.. _pcl_vcpkg_windows: + +Using PCL on windows with VCPKG and CMake +----------------------------------------- + +This tutorial explains how to acquire Point Cloud Library on +Microsoft Windows platforms using `VCPKG `_. + +For additional information how to use VCPKG, please see their `documentation `_. + +Last updated: 22. December 2021 + +.. image:: images/windows_logo.png + :alt: Microsoft Windows logo + :align: right + +.. contents:: + + +Requirements +================== + +Download VCPKG sources to eg. *c:\\vcpkg* preferably by cloning their repository. + +Navigate to *c:\\vcpkg* in **powershell** and run + + .\\bootstrap-vcpkg.bat + +This will download vcpkg.exe. + + +PCL's dependencies +================== + +PCL's required dependencies available on VCPKG are: + +* Boost +* FLANN +* Eigen3 + +PCL's optional dependencies available on VCPKG are: + +* VTK - for visualization module + + * Feature OpenGL - required + * Feature Qt - optional for QVTK, used in apps + +* GLEW - for simulation module +* Qhull - for convex/concave in surface module +* Qt - for apps that use Qt for GUI +* Google Test - for unit tests +* Google Benchmark - for benchmarks +* OpenNI2 +* Realsense2 +* PNG - for a single openni app +* Pcap - for Velodyne HDL driver + +PCL's optional dependencies not on VCPKG + +* CUDA - only a port that verify its installed (version 10.1). +* GLUT +* OpenNI +* Ensenso +* davidSDK +* DSSDK +* RSSDK + + +Install PCL for usage +===================== + +Running the following command in powershell in the VCPKG directory, +will install PCL with default options as well as default triplet type (ie. x86). + + ./vcpkg install pcl + + +.. note:: + + If there are new features or bugfixes that are not yet part of a release, + you can try to use --head, which downloads the master of PCL. + +You can see the available PCL version and options in VCPKG `here `_. + +To enable specific features, you need to write: + + ./vcpkg install pcl[qt,vtk] + +And all features: + + ./vcpkg install pcl[*] + +If you want to install with a different triplet type, the easiest way is: + + ./vcpkg install pcl --triplet triplet_type + +ie. + + ./vcpkg install pcl --triplet x64-windows + +This will acquire all the dependencies, build them and place the binaries +in vcpkg/installed/triplet_type/bin for release and vcpkg/installed/triplet_type/debug/bin for debug. + + +Using dependencies installed with VCPKG in CMake projects +========================================================= + +Use `CMake `_ to configure projects and remember to pass **vcpkg\\scripts\\buildsystems\\vcpkg.cmake** as toolchain file +to enable CMake to find all the dependencies installed with VCPKG. + +See example below using the cmake window: + +.. list-table:: + + * - .. figure:: images/vcpkg/cmake_configure_1.png + + Fig 1. Cmake configuration + + - .. figure:: images/vcpkg/cmake_configure_2.png + + Fig 2. Cmake configuration with vcpkg tool chain + + +Find PCL using CMake +==================== + +To use PCL in CMake project, take a look at Kunal Tyagi's minimal example `in this repository `_ + + +Install PCL dependencies for contributions +========================================== + +If you want to contribute to PCL, the easiest way to get dependencies +using vcpkg is to run the install command from our `docker file `_ + + ./vcpkg install dependencies_here --triplet triplet_type + +Remember to omit the *--clean-after-build*, as this removes the source code of the dependencies and limit debugging capabilities for those. + +To build PCL, you would have to get the `source `_, preferably clone it using git. + +Use `CMake `_ to configure PCL. + From 3153baa232be3eb0cd4bda71d265f771a2a49c8d Mon Sep 17 00:00:00 2001 From: Joey Rowell <79405074+joerowelll@users.noreply.github.com> Date: Wed, 8 Feb 2023 08:40:12 +0000 Subject: [PATCH 042/288] suggesting zero padding files when writing (#5597) * suggesting zero padding files when writing * updating documentation with correct filenames --- doc/tutorials/content/cluster_extraction.rst | 6 +++--- .../sources/cluster_extraction/cluster_extraction.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/doc/tutorials/content/cluster_extraction.rst b/doc/tutorials/content/cluster_extraction.rst index 1cc459b0619..7b2dbe6fb10 100644 --- a/doc/tutorials/content/cluster_extraction.rst +++ b/doc/tutorials/content/cluster_extraction.rst @@ -171,10 +171,10 @@ You will see something similar to:: PointCloud representing the Cluster: 290 data points. PointCloud representing the Cluster: 120 data points. -You can also look at your outputs cloud_cluster_0.pcd, cloud_cluster_1.pcd, -cloud_cluster_2.pcd, cloud_cluster_3.pcd and cloud_cluster_4.pcd:: +You can also look at your outputs cloud_cluster_0000.pcd, cloud_cluster_0001.pcd, +cloud_cluster_0002.pcd, cloud_cluster_0003.pcd and cloud_cluster_0004.pcd:: - $ ./pcl_viewer cloud_cluster_0.pcd cloud_cluster_1.pcd cloud_cluster_2.pcd cloud_cluster_3.pcd cloud_cluster_4.pcd + $ ./pcl_viewer cloud_cluster_0000.pcd cloud_cluster_0001.pcd cloud_cluster_0002.pcd cloud_cluster_0003.pcd cloud_cluster_0004.pcd You are now able to see the different clusters in one viewer. You should see something similar to this: diff --git a/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp b/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp index c865cefdb3f..d3cdee44b16 100644 --- a/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp +++ b/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp @@ -94,8 +94,8 @@ main () std::cout << "PointCloud representing the Cluster: " << cloud_cluster->size () << " data points." << std::endl; std::stringstream ss; - ss << "cloud_cluster_" << j << ".pcd"; - writer.write (ss.str (), *cloud_cluster, false); //* + ss << std::setw(4) << std::setfill('0') << j; + writer.write ("cloud_cluster_" + ss.str () + ".pcd", *cloud_cluster, false); //* j++; } From 3a8af8e5fe22fe5be9af56acd8e41a30b923523c Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 8 Feb 2023 14:23:27 +0100 Subject: [PATCH 043/288] Tide seems only to developed by the author Geoffrey Biggs and seems unobtainable. (#5595) Its currently not build on the build servers. --- tools/CMakeLists.txt | 9 - tools/pcl_video.cpp | 437 ------------------------------------------- 2 files changed, 446 deletions(-) delete mode 100644 tools/pcl_video.cpp diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index 8a72fdaa2cc..f92258405db 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -333,15 +333,6 @@ target_link_libraries (pcl_transform_point_cloud pcl_common pcl_io pcl_registrat PCL_ADD_EXECUTABLE(pcl_transform_from_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES transform_from_viewpoint.cpp) target_link_libraries (pcl_transform_from_viewpoint pcl_common pcl_io pcl_registration) -find_package(tide QUIET) -if(Tide_FOUND) - include_directories(SYSTEM ${Tide_INCLUDE_DIRS}) - add_definitions(${Tide_DEFINITIONS}) - PCL_ADD_EXECUTABLE(pcl_video COMPONENT ${SUBSYS_NAME} SOURCES pcl_video.cpp) - target_link_libraries(pcl_video pcl_common pcl_io pcl_visualization - ${Tide_LIBRARIES}) -endif() - if(CMAKE_GENERATOR_IS_IDE) set(SUBSYS_TARGET_NAME TOOLS_BUILD) else() diff --git a/tools/pcl_video.cpp b/tools/pcl_video.cpp deleted file mode 100644 index d79d7dbf0a2..00000000000 --- a/tools/pcl_video.cpp +++ /dev/null @@ -1,437 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Geoffrey Biggs - * 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. - * - * \author Geoffrey Biggs - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // for date -#include // for local_time -#include // for time_duration - -using namespace std::chrono_literals; -namespace bpt = boost::posix_time; - - -class Recorder -{ - public: - Recorder(std::string const& filename, std::string const& title) - : filename_(filename), title_(title), - stream_(filename, std::ios::in|std::ios::out|std::ios::trunc), - count_(0) - { - } - - void Callback(pcl::PointCloud::ConstPtr const& cloud) - { - // When creating a block, the track number must be specified. Currently, - // all blocks belong to track 1 (because this program only records one - // track). A timecode must also be given. It is an offset from the - // cluster's timecode measured in the segment's timecode scale. - bpt::ptime blk_start(bpt::microsec_clock::local_time()); - bpt::time_duration blk_offset = blk_start - cltr_start_; - tide::BlockElement::Ptr block(new tide::SimpleBlock(1, - blk_offset.total_microseconds() / 10000)); - // Here the frame data itself is added to the block - pcl::PCLPointCloud2 blob; - pcl::toPCLPointCloud2(*cloud, blob); - tide::Block::FramePtr frame_ptr(new tide::Block::Frame(blob.data.begin(), - blob.data.end())); - block->push_back(frame_ptr); - cluster_->push_back(block); - // Benchmarking - if (++count_ == 30) - { - double now = pcl::getTime(); - std::cerr << "Average framerate: " << - static_cast(count_) / (now - last_) << "Hz\n"; - count_ = 0; - last_ = now; - } - // Check if the cluster has enough data in it. - // What "enough" is depends on your own needs. Generally, a cluster - // shouldn't be allowed to get too big in data size or too long in time, or - // it has an adverse affect on seeking through the file. We will aim for 1 - // second of data per cluster. - bpt::time_duration cluster_len( - bpt::microsec_clock::local_time() - cltr_start_); - if (cluster_len.total_seconds() >= 1) - { - // Finalise the cluster - cluster_->finalise(stream_); - // Create a new cluster - cltr_start_ = bpt::microsec_clock::local_time(); - bpt::time_duration cltr_offset = cltr_start_ - seg_start_; - cluster_.reset(new tide::FileCluster( - cltr_offset.total_microseconds() / 10000)); - cluster_->write(stream_); - } - } - - int Run() - { - // Write the EBML PCLHeader. This specifies that the file is an EBML - // file, and is a Tide document. - tide::EBMLElement ebml_el; - ebml_el.write(stream_); - - // Open a new segment in the file. This will write some initial meta-data - // and place some padding at the start of the file for final meta-data to - // be written after tracks, clusters, etc. have been written. - tide::Segment segment; - segment.write(stream_); - // Set up the segment information so it can be used while writing tracks - // and clusters. - // A UID is not required, but is highly recommended. - boost::uuids::random_generator gen; - boost::uuids::uuid uuid = gen(); - std::vector uuid_data(uuid.size()); - std::copy(uuid.cbegin(), uuid.cend(), uuid_data.begin()); - segment.info.uid(uuid_data); - // The filename can be nice to know. - segment.info.filename(filename_); - // The segment's timecode scale is possibly the most important value in the - // segment meta-data data. Without it, timely playback of frames is not - // possible. It has a sensible default (defined in the Tide specification), - // but here we set it to ten milliseconds for demonstrative purposes. - segment.info.timecode_scale(10000000); - // The segment's date should be set. It is the somewhat-awkward value of - // the number of seconds since the start of the millennium. Boost::Date_Time - // to the rescue! - bpt::ptime basis(boost::gregorian::date(2001, 1, 1)); - seg_start_ = boost::posix_time::microsec_clock::local_time(); - bpt::time_duration td = seg_start_ - basis; - segment.info.date(td.total_microseconds() * 1000); - // Let's give the segment an inspirational title. - segment.info.title(title_); - // It sometimes helps to know what created a Tide file. - segment.info.muxing_app("libtide-0.1"); - segment.info.writing_app("pcl_video"); - - // Set up the tracks meta-data and write it to the file. - tide::Tracks tracks; - // Each track is represented in the Tracks information by a TrackEntry. - // This specifies such things as the track number, the track's UID and the - // codec used. - tide::TrackEntry::Ptr track(new tide::TrackEntry(1, 1, "pointcloud2")); - track->name("3D video"); - track->codec_name("pcl::PCLPointCloud2"); - // Adding each level 1 element (only the first occurrence, in the case of - // clusters) to the index makes opening the file later much faster. - segment.index.insert(std::make_pair(tracks.id(), - segment.to_segment_offset(stream_.tellp()))); - // Now we can write the Tracks element. - tracks.insert(track); - tracks.write(stream_); - // The file is now ready for writing the data. The data itself is stored in - // clusters. Each cluster contains a number of blocks, with each block - // containing a single frame of data. Different cluster implementations are - // (will be) available using different optimisations. Here, we use the - // implementation that stores all its blocks in memory before writing them - // all to the file at once. As with the segment, clusters must be opened - // for writing before blocks are added. Once the cluster is complete, it is - // finalised. How many blocks each cluster contains is relatively flexible: - // the only limitation is on the range of block timecodes that can be - // stored. Each timecode is a signed 16-bit integer, and usually blocks - // have timecodes that are positive, limiting the range to 32767. The unit - // of this value is the segment's timecode scale. The default timecode - // scale therefore gives approximately 65 seconds of total range, with 32 - // seconds being usable. - // The first cluster will appear at this point in the file, so it is - // recorded in the segment's index for faster file reading. - segment.index.insert(std::make_pair(tide::ids::Cluster, - segment.to_segment_offset(stream_.tellp()))); - - // Set up a callback to get clouds from a grabber and write them to the - // file. - pcl::Grabber* interface(new pcl::OpenNIGrabber()); - std::function::ConstPtr&)> f ( - [this] (const pcl::PointCloud::ConstPtr&) { Callback (cloud); } - ); - interface->registerCallback(f); - // Start the first cluster - cltr_start_ = bpt::microsec_clock::local_time(); - bpt::time_duration cltr_offset = cltr_start_ - seg_start_; - cluster_.reset(new tide::FileCluster( - cltr_offset.total_microseconds() / 10000)); - cluster_->write(stream_); - last_ = pcl::getTime(); - interface->start(); - - std::cout << "Recording frames. Press any key to stop.\n"; - getchar(); - - interface->stop(); - // Close the last open cluster - if (cluster_) - { - cluster_->finalise(stream_); - } - - // Now that the data has been written, the last thing to do is to finalise - // the segment. - segment.finalise(stream_); - // And finally, close the file. - stream_.close(); - - return 0; - } - - private: - std::string filename_; - std::string title_; - std::fstream stream_; - tide::FileCluster::Ptr cluster_; - bpt::ptime seg_start_; - bpt::ptime cltr_start_; - unsigned int count_; - double last_; -}; - - -class Player -{ - public: - Player(std::string const& filename) - : filename_(filename), viewer_("PCL Video Player: " + filename) - { - //viewer_.setBackgroundColor(0, 0, 0); - //viewer_.initCameraParameters(); - } - - int Run() - { - // Open the file and check for the EBML header. This confirms that the file - // is an EBML file, and is a Tide document. - std::ifstream stream(filename_, std::ios::in); - tide::ids::ReadResult id = tide::ids::read(stream); - if (id.first != tide::ids::EBML) - { - std::cerr << "File does not begin with an EBML header.\n"; - return 1; - } - tide::EBMLElement ebml_el; - ebml_el.read(stream); - if (ebml_el.doc_type() != tide::TideDocType) - { - std::cerr << "Specified EBML file is not a Tide document.\n"; - return 1; - } - if (ebml_el.read_version() > tide::TideEBMLVersion) - { - std::cerr << "This Tide document requires read version " << - ebml_el.read_version() << ".\n"; - return 1; - } - if (ebml_el.doc_read_version() > tide::TideVersionMajor) - { - std::cerr << "This Tide document requires doc read version " << - ebml_el.read_version() << ".\n"; - return 1; - } - std::cerr << "Found EBML header\n"; - - // Open the file's segment. This will read some meta-data about the segment - // and read (or build, if necessary) an index of the level 1 elements. With - // this index, we will be able to quickly jump to important elements such - // as the Tracks and the first Cluster. - id = tide::ids::read(stream); - if (id.first != tide::ids::Segment) - { - std::cerr << "Segment element not found\n"; - return 1; - } - tide::Segment segment; - segment.read(stream); - // The segment's date is stored as the number of nanoseconds since the - // start of the millennium. Boost::Date_Time is invaluable here. - bpt::ptime basis(boost::gregorian::date(2001, 1, 1)); - bpt::time_duration sd(bpt::microseconds(segment.info.date() / 1000)); - bpt::ptime seg_start(basis + sd); - - // The segment is now open and we can start reading its child elements. To - // begin with, we get the tracks element (their may be more than one, if - // the document was created by merging other documents) but generally only - // one will exist). - // We can guarantee that there is at least one in the index because - // otherwise the call to segment.read() would have thrown an error. - std::streampos tracks_pos(segment.index.find(tide::ids::Tracks)->second); - stream.seekg(segment.to_stream_offset(tracks_pos)); - // To be sure, we can check it really is a Tracks element, but this is - // usually not necessary. - id = tide::ids::read(stream); - if (id.first != tide::ids::Tracks) - { - std::cerr << "Tracks element not at indicated position.\n"; - return 1; - } - // Read the tracks - tide::Tracks tracks; - tracks.read(stream); - // Now we can introspect the tracks available in the file. - if (tracks.empty()) - { - std::cerr << "No tracks found.\n"; - return 1; - } - // Let's check that the file contains the codec we expect for the first - // track. - if (tracks[1]->codec_id() != "pointcloud2") - { - std::cerr << "Track #1 has wrong codec type " << - tracks[1]->codec_id() << '\n'; - return 1; - } - - bpt::ptime pb_start(bpt::microsec_clock::local_time()); - - // Now we can start reading the clusters. Get an iterator to the clusters - // in the segment. - // In this case, we are using a file-based cluster implementation, which - // reads blocks from the file on demand. This is usually a better - // option tham the memory-based cluster when the size of the stored - // data is large. - for (tide::Segment::FileBlockIterator block(segment.blocks_begin_file(stream)); - block != segment.blocks_end_file(stream); ++block) - { - bpt::time_duration blk_offset(bpt::microseconds(( - (block.cluster()->timecode() + block->timecode()) * - segment.info.timecode_scale() / 1000))); - bpt::time_duration played_time(bpt::microsec_clock::local_time() - - pb_start); - // If the current playback time is ahead of this block, skip it - if (played_time > blk_offset) - { - std::cerr << "Skipping block at " << blk_offset << - " because current playback time is " << played_time << '\n'; - continue; - } - // Some blocks may actually contain multiple frames in a lace. - // In this case, we are reading blocks that do not use lacing, - // so there is only one frame per block. This is the general - // case; lacing is typically only used when the frame size is - // very small to reduce overhead. - tide::BlockElement::FramePtr frame_data(*block->begin()); - // Copy the frame data into a serialised cloud structure - pcl::PCLPointCloud2 blob; - blob.height = 480; - blob.width = 640; - pcl::PCLPointField ptype; - ptype.name = "x"; - ptype.offset = 0; - ptype.datatype = 7; - ptype.count = 1; - blob.fields.push_back(ptype); - ptype.name = "y"; - ptype.offset = 4; - ptype.datatype = 7; - ptype.count = 1; - blob.fields.push_back(ptype); - ptype.name = "z"; - ptype.offset = 8; - ptype.datatype = 7; - ptype.count = 1; - blob.fields.push_back(ptype); - blob.is_bigendian = false; - blob.point_step = 16; - blob.row_step = 10240; - blob.is_dense = false; - blob.data.assign(frame_data->begin(), frame_data->end()); - pcl::PointCloud::Ptr cloud(new pcl::PointCloud); - pcl::fromPCLPointCloud2(blob, *cloud); - // Sleep until the block's display time. The played_time is - // updated to account for the time spent preparing the data. - played_time = bpt::microsec_clock::local_time() - pb_start; - bpt::time_duration sleep_time(blk_offset - played_time); - std::cerr << "Will sleep " << sleep_time << " until displaying block\n"; - std::this_thread::sleep_for(sleep_time); - viewer_.showCloud(cloud); - //viewer_.removePointCloud("1"); - //viewer_.addPointCloud(cloud, "1"); - //viewer_.spinOnce(); - //if (viewer_.wasStopped()) - //{ - //break; - //} - } - - return 0; - } - - private: - std::string filename_; - //pcl::visualization::PCLVisualizer viewer_; - pcl::visualization::CloudViewer viewer_; -}; - - -int main(int argc, char** argv) -{ - std::string filename; - if (pcl::console::parse_argument(argc, argv, "-f", filename) < 0) - { - std::cerr << "Usage: " << argv[0] << " -f filename [-p] [-t title]\n"; - return 1; - } - std::string title("PCL 3D video"); - pcl::console::parse_argument(argc, argv, "-t", title); - if (pcl::console::find_switch(argc, argv, "-p")) - { - Player player(filename); - return player.Run(); - } - else - { - Recorder recorder(filename, title); - return recorder.Run(); - } -} - From f0d8a18d63d775d9e812059e871a6af5a1cd788e Mon Sep 17 00:00:00 2001 From: Patrick Scheckenbach <124401292+ptrckschcknbch@users.noreply.github.com> Date: Wed, 8 Feb 2023 21:02:24 +0100 Subject: [PATCH 044/288] Fix register macros to match struct definitions Fix the sequence order in POINT_CLOUD_REGISTER macros to match structs --- common/include/pcl/impl/point_types.hpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index a3aee983201..28bcc121a24 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -1894,10 +1894,10 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::_PointXYZRGBNormal, (float, x, x) (float, y, y) (float, z, z) - (float, rgb, rgb) (float, normal_x, normal_x) (float, normal_y, normal_y) (float, normal_z, normal_z) + (float, rgb, rgb) (float, curvature, curvature) ) POINT_CLOUD_REGISTER_POINT_WRAPPER(pcl::PointXYZRGBNormal, pcl::_PointXYZRGBNormal) @@ -1905,20 +1905,20 @@ POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZINormal, (float, x, x) (float, y, y) (float, z, z) - (float, intensity, intensity) (float, normal_x, normal_x) (float, normal_y, normal_y) (float, normal_z, normal_z) + (float, intensity, intensity) (float, curvature, curvature) ) POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointXYZLNormal, (float, x, x) (float, y, y) (float, z, z) - (std::uint32_t, label, label) (float, normal_x, normal_x) (float, normal_y, normal_y) (float, normal_z, normal_z) + (std::uint32_t, label, label) (float, curvature, curvature) ) POINT_CLOUD_REGISTER_POINT_STRUCT (pcl::PointWithRange, From b438c9b8114d774ce402dd0134d214ae9148b091 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 11 Feb 2023 12:04:51 +0100 Subject: [PATCH 045/288] Add overload to fromPCLPointCloud2 to avoid copying data This is especially interesting for perception_pcl (see https://github.com/ros-perception/perception_pcl/pull/368) --- common/include/pcl/conversions.h | 39 ++++++++++++++++++++++---------- 1 file changed, 27 insertions(+), 12 deletions(-) diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 7e9fdf40b5d..652a1b41b67 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -151,21 +151,17 @@ namespace pcl } /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. - * \param[in] msg the PCLPointCloud2 binary blob + * \param[in] msg the PCLPointCloud2 binary blob (note that the binary point data in msg.data will not be used!) * \param[out] cloud the resultant pcl::PointCloud * \param[in] field_map a MsgFieldMap object + * \param[in] msg_data pointer to binary blob data, used instead of msg.data * - * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud) directly or create you - * own MsgFieldMap using: - * - * \code - * MsgFieldMap field_map; - * createMapping (msg.fields, field_map); - * \endcode + * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud) instead, except if you have a binary blob of + * point data that you do not want to copy into a pcl::PCLPointCloud2 in order to use fromPCLPointCloud2. */ template void fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud, - const MsgFieldMap& field_map) + const MsgFieldMap& field_map, const std::uint8_t* msg_data) { // Copy info fields cloud.header = msg.header; @@ -187,11 +183,10 @@ namespace pcl field_map[0].size == sizeof(PointT)) { const auto cloud_row_step = (sizeof (PointT) * cloud.width); - const std::uint8_t* msg_data = &msg.data[0]; // Should usually be able to copy all rows at once if (msg.row_step == cloud_row_step) { - std::copy(msg.data.cbegin(), msg.data.cend(), cloud_data); + memcpy (cloud_data, msg_data, msg.width * msg.height * sizeof(PointT)); } else { @@ -205,7 +200,7 @@ namespace pcl // If not, memcpy each group of contiguous fields separately for (uindex_t row = 0; row < msg.height; ++row) { - const std::uint8_t* row_data = &msg.data[row * msg.row_step]; + const std::uint8_t* row_data = msg_data + row * msg.row_step; for (uindex_t col = 0; col < msg.width; ++col) { const std::uint8_t* msg_data = row_data + col * msg.point_step; @@ -220,6 +215,26 @@ namespace pcl } } + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. + * \param[in] msg the PCLPointCloud2 binary blob + * \param[out] cloud the resultant pcl::PointCloud + * \param[in] field_map a MsgFieldMap object + * + * \note Use fromPCLPointCloud2 (PCLPointCloud2, PointCloud) directly or create you + * own MsgFieldMap using: + * + * \code + * MsgFieldMap field_map; + * createMapping (msg.fields, field_map); + * \endcode + */ + template void + fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud& cloud, + const MsgFieldMap& field_map) + { + fromPCLPointCloud2 (msg, cloud, field_map, msg.data.data()); + } + /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object. * \param[in] msg the PCLPointCloud2 binary blob * \param[out] cloud the resultant pcl::PointCloud From aa864db6386e73931b443ca6f8216f84a042d01f Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Sat, 11 Feb 2023 03:26:36 -0800 Subject: [PATCH 046/288] Added modernize-return-braced-init-list to clang-tidy checks (#5593) * Added modernize-return-braced-init-list clang-tidy Added modernize-return-braced-init-list clang-tidy check Fixed issues flagged by clang-tidy Fixed clang-tidy complaints from CI Worked around clang bug with explicit constructor Fixed unrelated unused typedef error Fixed formatting issue * Reverted formatting changes per review * Restored braced-init-list return * *Really* revert formatting this time * Commented NOLINT instances more clearly --- .clang-tidy | 1 + common/include/pcl/common/impl/eigen.hpp | 3 +- .../pcl/range_image/impl/range_image.hpp | 4 +- .../include/pcl/filters/normal_refinement.h | 6 +- filters/include/pcl/filters/voxel_grid.h | 8 +-- .../filters/voxel_grid_occlusion_estimation.h | 6 +- geometry/include/pcl/geometry/mesh_base.h | 14 ++--- io/include/pcl/io/dinast_grabber.h | 2 +- io/include/pcl/io/real_sense_2_grabber.h | 3 +- io/src/dinast_grabber.cpp | 2 +- io/src/hdl_grabber.cpp | 2 +- io/src/oni_grabber.cpp | 2 +- io/src/openni2_grabber.cpp | 2 +- io/src/openni_grabber.cpp | 2 +- io/src/ply_io.cpp | 14 ++--- io/src/robot_eye_grabber.cpp | 2 +- io/src/tim_grabber.cpp | 2 +- io/src/vlp_grabber.cpp | 2 +- io/tools/ply/ply2obj.cpp | 20 +++---- io/tools/ply/ply2ply.cpp | 5 +- io/tools/ply/ply2raw.cpp | 22 +++----- .../pcl/outofcore/visualization/camera.h | 4 ++ .../face_detector_data_provider.cpp | 2 +- .../include/pcl/registration/impl/lum.hpp | 4 +- simulation/include/pcl/simulation/camera.h | 2 +- surface/src/on_nurbs/sequential_fitter.cpp | 2 +- test/filters/test_convolution.cpp | 4 +- test/geometry/test_mesh_common_functions.h | 55 +++++++++---------- test/io/test_octree_compression.cpp | 14 ++--- .../include/pcl/tracking/impl/tracking.hpp | 10 ++-- .../pcl/visualization/area_picking_event.h | 2 +- visualization/src/common/common.cpp | 2 +- 32 files changed, 104 insertions(+), 121 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index fb4b590a1b4..80625eda8a4 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -7,6 +7,7 @@ Checks: > modernize-deprecated-headers, modernize-redundant-void-arg, modernize-replace-random-shuffle, + modernize-return-braced-init-list, modernize-use-auto, modernize-use-equals-default, modernize-use-equals-delete, diff --git a/common/include/pcl/common/impl/eigen.hpp b/common/include/pcl/common/impl/eigen.hpp index 4ff30cd5cbd..031a8ee0b7c 100644 --- a/common/include/pcl/common/impl/eigen.hpp +++ b/common/include/pcl/common/impl/eigen.hpp @@ -285,8 +285,7 @@ getLargest3x3Eigenvector (const Matrix scaledMatrix) Index index; const Scalar length = len.maxCoeff (&index); // <- first evaluation - return EigenVector {crossProduct.row (index) / length, - length}; + return {crossProduct.row (index) / length, length}; } } // namespace detail diff --git a/common/include/pcl/range_image/impl/range_image.hpp b/common/include/pcl/range_image/impl/range_image.hpp index 866cc2ce96d..01e396e290e 100644 --- a/common/include/pcl/range_image/impl/range_image.hpp +++ b/common/include/pcl/range_image/impl/range_image.hpp @@ -682,7 +682,7 @@ RangeImage::getAcutenessValue (int x1, int y1, int x2, int y2) const const Eigen::Vector3f RangeImage::getSensorPos () const { - return Eigen::Vector3f (to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3)); + return {to_world_system_ (0,3), to_world_system_ (1,3), to_world_system_ (2,3)}; } ///////////////////////////////////////////////////////////////////////// @@ -801,7 +801,7 @@ RangeImage::getMaxAngleSize (const Eigen::Affine3f& viewer_pose, const Eigen::Ve Eigen::Vector3f RangeImage::getEigenVector3f (const PointWithRange& point) { - return Eigen::Vector3f (point.x, point.y, point.z); + return {point.x, point.y, point.z}; } ///////////////////////////////////////////////////////////////////////// diff --git a/filters/include/pcl/filters/normal_refinement.h b/filters/include/pcl/filters/normal_refinement.h index 144ec0ad9ca..7de5be0300c 100644 --- a/filters/include/pcl/filters/normal_refinement.h +++ b/filters/include/pcl/filters/normal_refinement.h @@ -64,7 +64,11 @@ namespace pcl PCL_ERROR("[pcl::assignNormalWeights] inequal size of neighbor indices and distances!\n"); // TODO: For now we use uniform weights - return (std::vector (k_indices.size (), 1.0f)); + // Disable check for braced-initialization, + // since the compiler doesn't seem to recognize that + // {k_indices.size (), 1.0f} is selecting the vector(size_type count, const T&) constructor + // NOLINTNEXTLINE(modernize-return-braced-init-list) + return std::vector (k_indices.size (), 1.0f); } /** \brief Refine an indexed point based on its neighbors, this function only writes to the normal_* fields diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 186fccebc65..1f06d46d4cd 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -362,9 +362,9 @@ namespace pcl inline Eigen::Vector3i getGridCoordinates (float x, float y, float z) const { - return (Eigen::Vector3i (static_cast (std::floor (x * inverse_leaf_size_[0])), + return {static_cast (std::floor (x * inverse_leaf_size_[0])), static_cast (std::floor (y * inverse_leaf_size_[1])), - static_cast (std::floor (z * inverse_leaf_size_[2])))); + static_cast (std::floor (z * inverse_leaf_size_[2]))}; } /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates. @@ -710,9 +710,9 @@ namespace pcl inline Eigen::Vector3i getGridCoordinates (float x, float y, float z) const { - return (Eigen::Vector3i (static_cast (std::floor (x * inverse_leaf_size_[0])), + return {static_cast (std::floor (x * inverse_leaf_size_[0])), static_cast (std::floor (y * inverse_leaf_size_[1])), - static_cast (std::floor (z * inverse_leaf_size_[2])))); + static_cast (std::floor (z * inverse_leaf_size_[2]))}; } /** \brief Returns the index in the downsampled cloud corresponding to a given set of coordinates. diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index 4285fb2bfc7..cac545941e9 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -227,9 +227,9 @@ namespace pcl inline Eigen::Vector3i getGridCoordinatesRound (float x, float y, float z) { - return Eigen::Vector3i (static_cast (round (x * inverse_leaf_size_[0])), - static_cast (round (y * inverse_leaf_size_[1])), - static_cast (round (z * inverse_leaf_size_[2]))); + return {static_cast (round (x * inverse_leaf_size_[0])), + static_cast (round (y * inverse_leaf_size_[1])), + static_cast (round (z * inverse_leaf_size_[2]))}; } // initialization flag diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index f2ed1a83e05..991ac56470e 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -1091,7 +1091,7 @@ class MeshBase { &vertex_data <= &vertex_data_cloud_.back()); return (VertexIndex(std::distance(&vertex_data_cloud_.front(), &vertex_data))); } - return (VertexIndex()); + return {}; } /** \brief Get the index associated to the given half-edge data. */ @@ -1104,7 +1104,7 @@ class MeshBase { return (HalfEdgeIndex( std::distance(&half_edge_data_cloud_.front(), &half_edge_data))); } - return (HalfEdgeIndex()); + return {}; } /** \brief Get the index associated to the given edge data. */ @@ -1116,7 +1116,7 @@ class MeshBase { &edge_data <= &edge_data_cloud_.back()); return (EdgeIndex(std::distance(&edge_data_cloud_.front(), &edge_data))); } - return (EdgeIndex()); + return {}; } /** \brief Get the index associated to the given face data. */ @@ -1128,7 +1128,7 @@ class MeshBase { &face_data <= &face_data_cloud_.back()); return (FaceIndex(std::distance(&face_data_cloud_.front(), &face_data))); } - return (FaceIndex()); + return {}; } protected: @@ -1162,7 +1162,7 @@ class MeshBase { { const int n = static_cast(vertices.size()); if (n < 3) - return (FaceIndex()); + return {}; // Check for topological errors inner_he_.resize(n); @@ -1175,7 +1175,7 @@ class MeshBase { inner_he_[i], is_new_[i], IsManifold())) { - return (FaceIndex()); + return {}; } } for (int i = 0; i < n; ++i) { @@ -1188,7 +1188,7 @@ class MeshBase { make_adjacent_[i], free_he_[i], IsManifold())) { - return (FaceIndex()); + return {}; } } diff --git a/io/include/pcl/io/dinast_grabber.h b/io/include/pcl/io/dinast_grabber.h index 67cbdd9a9d9..766f8ecc39f 100644 --- a/io/include/pcl/io/dinast_grabber.h +++ b/io/include/pcl/io/dinast_grabber.h @@ -81,7 +81,7 @@ namespace pcl */ std::string getName () const override - { return (std::string ("DinastGrabber")); } + { return {"DinastGrabber"}; } /** \brief Start the data acquisition process. */ diff --git a/io/include/pcl/io/real_sense_2_grabber.h b/io/include/pcl/io/real_sense_2_grabber.h index 61248101468..646633adadd 100644 --- a/io/include/pcl/io/real_sense_2_grabber.h +++ b/io/include/pcl/io/real_sense_2_grabber.h @@ -101,7 +101,8 @@ namespace pcl /** \brief defined grabber name*/ std::string - getName () const override { return std::string ( "RealSense2Grabber" ); } + getName () const override { + return {"RealSense2Grabber"}; } //define callback signature typedefs using signal_librealsense_PointXYZ = void( const pcl::PointCloud::ConstPtr& ); diff --git a/io/src/dinast_grabber.cpp b/io/src/dinast_grabber.cpp index 6ca3c951aa5..8071257f3bf 100644 --- a/io/src/dinast_grabber.cpp +++ b/io/src/dinast_grabber.cpp @@ -204,7 +204,7 @@ pcl::DinastGrabber::getDeviceVersion () PCL_THROW_EXCEPTION (pcl::IOException, "[pcl::DinastGrabber::getDeviceVersion] Error trying to get device version"); //data[21] = 0; - return (std::string (reinterpret_cast (data))); + return {reinterpret_cast(data)}; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/hdl_grabber.cpp b/io/src/hdl_grabber.cpp index d6234ea980d..72dd213598a 100644 --- a/io/src/hdl_grabber.cpp +++ b/io/src/hdl_grabber.cpp @@ -564,7 +564,7 @@ pcl::HDLGrabber::isRunning () const std::string pcl::HDLGrabber::getName () const { - return (std::string ("Velodyne High Definition Laser (HDL) Grabber")); + return {"Velodyne High Definition Laser (HDL) Grabber"}; } ///////////////////////////////////////////////////////////////////////////// diff --git a/io/src/oni_grabber.cpp b/io/src/oni_grabber.cpp index 096985861c6..1d18540f847 100644 --- a/io/src/oni_grabber.cpp +++ b/io/src/oni_grabber.cpp @@ -243,7 +243,7 @@ ONIGrabber::isRunning() const std::string ONIGrabber::getName () const { - return (std::string("ONIGrabber")); + return {"ONIGrabber"}; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index de0ed7d95f8..25954dfdd7e 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -298,7 +298,7 @@ pcl::io::OpenNI2Grabber::signalsChanged () std::string pcl::io::OpenNI2Grabber::getName () const { - return (std::string ("OpenNI2Grabber")); + return {"OpenNI2Grabber"}; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index bc8f3b7fcd1..81e9aecfe41 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -305,7 +305,7 @@ pcl::OpenNIGrabber::signalsChanged () std::string pcl::OpenNIGrabber::getName () const { - return std::string ("OpenNIGrabber"); + return {"OpenNIGrabber"}; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index c56483ec12f..4df171ab587 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -70,16 +70,12 @@ pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std: cloud_->point_step = 0; cloud_->row_step = 0; vertex_count_ = 0; - return (std::tuple, std::function > ( - [this] { vertexBeginCallback (); }, - [this] { vertexEndCallback (); })); + return {[this] { vertexBeginCallback(); }, [this] { vertexEndCallback(); }}; } if ((element_name == "face") && polygons_) { polygons_->reserve (count); - return (std::tuple, std::function > ( - [this] { faceBeginCallback (); }, - [this] { faceEndCallback (); })); + return {[this] { faceBeginCallback(); }, [this] { faceEndCallback(); }}; } if (element_name == "camera") { @@ -89,9 +85,7 @@ pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std: if (element_name == "range_grid") { range_grid_->reserve (count); - return (std::tuple, std::function > ( - [this] { rangeGridBeginCallback (); }, - [this] { rangeGridEndCallback (); })); + return {[this] { rangeGridBeginCallback(); }, [this] { rangeGridEndCallback(); }}; } return {}; } @@ -100,7 +94,7 @@ bool pcl::PLYReader::endHeaderCallback () { cloud_->data.resize (static_cast(cloud_->point_step) * cloud_->width * cloud_->height); - return (true); + return true; } template void diff --git a/io/src/robot_eye_grabber.cpp b/io/src/robot_eye_grabber.cpp index e9ef154ba2f..2db6da17906 100644 --- a/io/src/robot_eye_grabber.cpp +++ b/io/src/robot_eye_grabber.cpp @@ -74,7 +74,7 @@ pcl::RobotEyeGrabber::~RobotEyeGrabber () noexcept std::string pcl::RobotEyeGrabber::getName () const { - return (std::string ("Ocular Robotics RobotEye Grabber")); + return {"Ocular Robotics RobotEye Grabber"}; } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/tim_grabber.cpp b/io/src/tim_grabber.cpp index 3dc1c0b7742..a97b9e374da 100644 --- a/io/src/tim_grabber.cpp +++ b/io/src/tim_grabber.cpp @@ -215,7 +215,7 @@ pcl::TimGrabber::isRunning () const std::string pcl::TimGrabber::getName () const { - return (std::string ("Sick Tim Grabber")); + return {"Sick Tim Grabber"}; } /////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/vlp_grabber.cpp b/io/src/vlp_grabber.cpp index b3163eac1d6..b35087b74b9 100644 --- a/io/src/vlp_grabber.cpp +++ b/io/src/vlp_grabber.cpp @@ -215,7 +215,7 @@ pcl::VLPGrabber::toPointClouds (HDLDataPacket *dataPacket) std::string pcl::VLPGrabber::getName () const { - return (std::string ("Velodyne LiDAR (VLP) Grabber")); + return {"Velodyne LiDAR (VLP) Grabber"}; } ///////////////////////////////////////////////////////////////////////////// diff --git a/io/tools/ply/ply2obj.cpp b/io/tools/ply/ply2obj.cpp index b248e322708..f85b3db4280 100644 --- a/io/tools/ply/ply2obj.cpp +++ b/io/tools/ply/ply2obj.cpp @@ -160,17 +160,11 @@ ply_to_obj_converter::element_definition_callback (const std::string& element_na { if (element_name == "vertex") { - return std::tuple, std::function > ( - [this] { vertex_begin (); }, - [this] { vertex_end (); } - ); + return {[this] { vertex_begin(); }, [this] { vertex_end(); }}; } if (element_name == "face") { - return std::tuple, std::function > ( - [this] { face_begin (); }, - [this] { face_end (); } - ); + return {[this] { face_begin(); }, [this] { face_end(); }}; } return {}; } @@ -196,11 +190,11 @@ template <> std::tuple, std::function< ply_to_obj_converter::list_property_definition_callback (const std::string& element_name, const std::string& property_name) { if ((element_name == "face") && (property_name == "vertex_indices")) { - return std::tuple, std::function, std::function > ( - [this] (pcl::io::ply::uint8 p){ face_vertex_indices_begin (p); }, - [this] (pcl::io::ply::int32 vertex_index) { face_vertex_indices_element (vertex_index); }, - [this] { face_vertex_indices_end (); } - ); + return {[this](pcl::io::ply::uint8 p) { face_vertex_indices_begin(p); }, + [this](pcl::io::ply::int32 vertex_index) { + face_vertex_indices_element(vertex_index); + }, + [this] { face_vertex_indices_end(); }}; } return {}; } diff --git a/io/tools/ply/ply2ply.cpp b/io/tools/ply/ply2ply.cpp index c3137042deb..b82c742d7ac 100644 --- a/io/tools/ply/ply2ply.cpp +++ b/io/tools/ply/ply2ply.cpp @@ -214,10 +214,7 @@ ply_to_ply_converter::element_end_callback() std::tuple, std::function > ply_to_ply_converter::element_definition_callback(const std::string& element_name, std::size_t count) { (*ostream_) << "element " << element_name << " " << count << "\n"; - return std::tuple, std::function >( - [this] { element_begin_callback (); }, - [this] { element_end_callback (); } - ); + return {[this] { element_begin_callback(); }, [this] { element_end_callback(); }}; } template diff --git a/io/tools/ply/ply2raw.cpp b/io/tools/ply/ply2raw.cpp index 118aa8ce80c..9e1b70829c5 100644 --- a/io/tools/ply/ply2raw.cpp +++ b/io/tools/ply/ply2raw.cpp @@ -172,16 +172,10 @@ std::tuple, std::function > ply_to_raw_converter::element_definition_callback (const std::string& element_name, std::size_t) { if (element_name == "vertex") { - return std::tuple, std::function > ( - [this] { vertex_begin (); }, - [this] { vertex_end (); } - ); + return {[this] { vertex_begin(); }, [this] { vertex_end(); }}; } if (element_name == "face") { - return std::tuple, std::function > ( - [this] { face_begin (); }, - [this] { face_end (); } - ); + return {[this] { face_begin(); }, [this] { face_end(); }}; } return {}; } @@ -210,13 +204,11 @@ ply_to_raw_converter::list_property_definition_callback (const std::string& elem { if ((element_name == "face") && (property_name == "vertex_indices")) { - return std::tuple, - std::function, - std::function > ( - [this] (pcl::io::ply::uint8 p){ face_vertex_indices_begin (p); }, - [this] (pcl::io::ply::int32 vertex_index) { face_vertex_indices_element (vertex_index); }, - [this] { face_vertex_indices_end (); } - ); + return {[this](pcl::io::ply::uint8 p) { face_vertex_indices_begin(p); }, + [this](pcl::io::ply::int32 vertex_index) { + face_vertex_indices_element(vertex_index); + }, + [this] { face_vertex_indices_end(); }}; } return {}; } diff --git a/outofcore/include/pcl/outofcore/visualization/camera.h b/outofcore/include/pcl/outofcore/visualization/camera.h index e2d57b13829..cf2d84c837b 100644 --- a/outofcore/include/pcl/outofcore/visualization/camera.h +++ b/outofcore/include/pcl/outofcore/visualization/camera.h @@ -97,6 +97,10 @@ class Camera : public Object Eigen::Matrix4d getViewProjectionMatrix () { + // Disable check for braced-initialization, + // since the compiler complains that the constructor selected + // with {projection_matrix_ * model_view_matrix_} is explicit + // NOLINTNEXTLINE(modernize-return-braced-init-list) return Eigen::Matrix4d (projection_matrix_ * model_view_matrix_); } diff --git a/recognition/src/face_detection/face_detector_data_provider.cpp b/recognition/src/face_detection/face_detector_data_provider.cpp index 95cedbdc3d2..558c7f10773 100644 --- a/recognition/src/face_detection/face_detector_data_provider.cpp +++ b/recognition/src/face_detection/face_detector_data_provider.cpp @@ -254,7 +254,7 @@ void pcl::face_detection::FaceDetectorDataProviderwidth; - const float *data = reinterpret_cast (&(*cloud)[0]); // NOLINT(readability-container-data-pointer) + const float *data = reinterpret_cast (cloud->data()); integral_image_depth->setInput (data + 2, cloud->width, cloud->height, element_stride, row_stride); //Compute normals and normal integral images diff --git a/registration/include/pcl/registration/impl/lum.hpp b/registration/include/pcl/registration/impl/lum.hpp index 5bc532d802f..faa1d6f575d 100644 --- a/registration/include/pcl/registration/impl/lum.hpp +++ b/registration/include/pcl/registration/impl/lum.hpp @@ -203,7 +203,7 @@ LUM::getCorrespondences(const Vertex& source_vertex, if (source_vertex >= getNumVertices() || target_vertex >= getNumVertices()) { PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get " "a set of correspondences between non-existing graph vertices.\n"); - return (pcl::CorrespondencesPtr()); + return {}; } Edge e; bool present; @@ -211,7 +211,7 @@ LUM::getCorrespondences(const Vertex& source_vertex, if (!present) { PCL_ERROR("[pcl::registration::LUM::getCorrespondences] You are attempting to get " "a set of correspondences from a non-existing graph edge.\n"); - return (pcl::CorrespondencesPtr()); + return {}; } return ((*slam_graph_)[e].corrs_); } diff --git a/simulation/include/pcl/simulation/camera.h b/simulation/include/pcl/simulation/camera.h index 9c0ef990c5d..1785e471435 100644 --- a/simulation/include/pcl/simulation/camera.h +++ b/simulation/include/pcl/simulation/camera.h @@ -140,7 +140,7 @@ class PCL_EXPORTS Camera { Eigen::Vector3d getYPR() const { - return Eigen::Vector3d(yaw_, pitch_, roll_); + return {yaw_, pitch_, roll_}; } private: diff --git a/surface/src/on_nurbs/sequential_fitter.cpp b/surface/src/on_nurbs/sequential_fitter.cpp index c9c617ec60b..10433490aef 100644 --- a/surface/src/on_nurbs/sequential_fitter.cpp +++ b/surface/src/on_nurbs/sequential_fitter.cpp @@ -177,7 +177,7 @@ SequentialFitter::project (const Eigen::Vector3d &pt) pr (0) = -pr (0); pr (1) = -pr (1); } - return Eigen::Vector2d (pr (0), pr (1)); + return {pr(0), pr(1)}; } bool diff --git a/test/filters/test_convolution.cpp b/test/filters/test_convolution.cpp index 9029e6642e7..f0d1ece311b 100644 --- a/test/filters/test_convolution.cpp +++ b/test/filters/test_convolution.cpp @@ -68,11 +68,11 @@ RGB interpolate_color(float lower_bound, float upper_bound, float value) auto interpolate = [](std::uint8_t lower, std::uint8_t upper, float step_size, float value) { return (lower == upper) ? lower : static_cast(static_cast(lower) + ((static_cast(upper) - static_cast(lower)) / step_size) * value); }; - return RGB( + return { interpolate(colormap[lower_index].r, colormap[lower_index + 1].r, step_size, value), interpolate(colormap[lower_index].g, colormap[lower_index + 1].g, step_size, value), interpolate(colormap[lower_index].b, colormap[lower_index + 1].b, step_size, value) - ); + }; } TEST (Convolution, convolveRowsXYZI) diff --git a/test/geometry/test_mesh_common_functions.h b/test/geometry/test_mesh_common_functions.h index 6f7291f9ad9..5f3d42f5f2b 100644 --- a/test/geometry/test_mesh_common_functions.h +++ b/test/geometry/test_mesh_common_functions.h @@ -65,7 +65,7 @@ hasFaces (const MeshT& mesh, const std::vector & { std::cerr << "Incorrect number of faces: " << mesh.sizeFaces () << " != " << faces.size () << "\n"; } - return (false); + return false; } VertexIndices vi; @@ -84,7 +84,7 @@ hasFaces (const MeshT& mesh, const std::vector & if (++counter > max_number_polygon_vertices) { if (verbose) std::cerr << "... Infinite loop aborted.\n"; - return (false); + return false; } vi.push_back (circ.getTargetIndex ()); } while (++circ != circ_end); @@ -92,7 +92,7 @@ hasFaces (const MeshT& mesh, const std::vector & if (vi.size () != faces [i].size ()) { std::cerr << "Wrong size!\n"; - return (false); + return false; } if (verbose) std::cerr << "\texpected: "; for (std::size_t j = 0; j < vi.size (); ++j) @@ -100,12 +100,12 @@ hasFaces (const MeshT& mesh, const std::vector & if (verbose) std::cerr << std::setw (2) << faces [i][j] << " "; if (vi [j] != faces [i][j]) { - return (false); + return false; } } if (verbose) std::cerr << "\n"; } - return (true); + return true; } //////////////////////////////////////////////////////////////////////////////// @@ -126,7 +126,7 @@ hasFaces (const MeshT& mesh, const std::vector > &faces, cons { std::cerr << "Incorrect number of faces: " << mesh.sizeFaces () << " != " << faces.size () << "\n"; } - return (false); + return false; } const VertexDataCloud& vdc = mesh.getVertexDataCloud (); @@ -146,7 +146,7 @@ hasFaces (const MeshT& mesh, const std::vector > &faces, cons if (++counter > max_number_polygon_vertices) { if (verbose) std::cerr << "... Infinite loop aborted.\n"; - return (false); + return false; } vv.push_back (vdc [circ.getTargetIndex ().get ()]); } while (++circ != circ_end); @@ -154,7 +154,7 @@ hasFaces (const MeshT& mesh, const std::vector > &faces, cons if (vv.size () != faces [i].size ()) { std::cerr << "Wrong size!\n"; - return (false); + return false; } if (verbose) std::cerr << "\texpected: "; for (std::size_t j=0; j > &faces, cons if (vv [j] != faces [i][j]) { if (verbose) std::cerr << "\n"; - return (false); + return false; } } if (verbose) std::cerr << "\n"; } - return (true); + return true; } //////////////////////////////////////////////////////////////////////////////// @@ -187,7 +187,7 @@ getBoundaryVertices (const MeshT& mesh, const typename MeshT::VertexIndex& first if (verbose) std::cerr << "Vertex " << first << "with outgoing half_edge " << mesh.getOriginatingVertexIndex (boundary_he) << "-" << mesh.getTerminatingVertexIndex (boundary_he) << " is not on the boundary!\n"; - return (VertexIndices ()); + return {}; } VAFC circ = mesh.getVertexAroundFaceCirculator (boundary_he); @@ -203,12 +203,12 @@ getBoundaryVertices (const MeshT& mesh, const typename MeshT::VertexIndex& first if (++counter > max_number_boundary_vertices) { if (verbose) std::cerr << "... Infinite loop aborted.\n"; - return (VertexIndices ()); + return {}; } boundary_vertices.push_back (circ.getTargetIndex ()); } while (++circ != circ_end); if (verbose) std::cerr << "\n"; - return (boundary_vertices); + return boundary_vertices; } //////////////////////////////////////////////////////////////////////////////// @@ -227,7 +227,7 @@ getBoundaryVertices (const MeshT& mesh, const int first, const bool verbose = fa if (verbose) std::cerr << "Vertex " << first << "with outgoing half_edge " << mesh.getOriginatingVertexIndex (boundary_he) << "-" << mesh.getTerminatingVertexIndex (boundary_he) << " is not on the boundary!\n"; - return (std::vector ()); + return {}; } VAFC circ = mesh.getVertexAroundFaceCirculator (boundary_he); @@ -243,12 +243,12 @@ getBoundaryVertices (const MeshT& mesh, const int first, const bool verbose = fa if (++counter > max_number_boundary_vertices) { if (verbose) std::cerr << "... Infinite loop aborted.\n"; - return (std::vector ()); + return {}; } boundary_vertices.push_back (mesh.getVertexDataCloud () [circ.getTargetIndex ().get ()]); } while (++circ != circ_end); if (verbose) std::cerr << "\n"; - return (boundary_vertices); + return boundary_vertices; } //////////////////////////////////////////////////////////////////////////////// @@ -264,7 +264,7 @@ isCircularPermutation (const ContainerT& expected, const ContainerT& actual, con if (n != actual.size ()) { if (verbose) std::cerr << "expected.size () != actual.size (): " << n << " != " << actual.size () << "\n"; - return (false); + return false; } for (unsigned int i=0; i &expected, const std::v if (n != actual.size ()) { if (verbose) std::cerr << "expected.size () != actual.size (): " << n << " != " << actual.size () << "\n"; - return (false); + return false; } for (unsigned int i=0; i &expected, const std::v if (verbose) std::cerr << "\n"; if (all_equal) { - return (true); + return true; } } - return (false); + return false; } //////////////////////////////////////////////////////////////////////////////// @@ -333,12 +333,11 @@ findHalfEdge (const MeshT& mesh, const typename MeshT::VertexIndex& idx_v_0, const typename MeshT::VertexIndex& idx_v_1) { - using HalfEdgeIndex = typename MeshT::HalfEdgeIndex; using VAVC = typename MeshT::VertexAroundVertexCirculator; if (mesh.isIsolated (idx_v_0) || mesh.isIsolated (idx_v_1)) { - return (HalfEdgeIndex ()); + return {}; } VAVC circ = mesh.getVertexAroundVertexCirculator (idx_v_0); @@ -352,7 +351,7 @@ findHalfEdge (const MeshT& mesh, } } while (++circ != circ_end); - return (HalfEdgeIndex ()); + return {}; } //////////////////////////////////////////////////////////////////////////////// @@ -364,9 +363,9 @@ checkHalfEdge (const MeshT& mesh, const typename MeshT::VertexIndex ind_v_a, const typename MeshT::VertexIndex ind_v_b) { - if (mesh.getOriginatingVertexIndex (ind_he_ab) != ind_v_a) return (false); - if (mesh.getTerminatingVertexIndex (ind_he_ab) != ind_v_b) return (false); - return (true); + if (mesh.getOriginatingVertexIndex (ind_he_ab) != ind_v_a) return false; + if (mesh.getTerminatingVertexIndex (ind_he_ab) != ind_v_b) return false; + return true; } //////////////////////////////////////////////////////////////////////////////// diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index a73f4583a7a..6cf9f2f2342 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -53,19 +53,19 @@ char* pcd_file; 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), + return {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)); + 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), + return {static_cast (MAX_XYZ * rand() / RAND_MAX), static_cast (MAX_XYZ * rand() / RAND_MAX), - static_cast (MAX_XYZ * rand() / RAND_MAX)); + static_cast (MAX_XYZ * rand() / RAND_MAX)}; } template inline diff --git a/tracking/include/pcl/tracking/impl/tracking.hpp b/tracking/include/pcl/tracking/impl/tracking.hpp index 626b2cff911..5ef653a121d 100644 --- a/tracking/include/pcl/tracking/impl/tracking.hpp +++ b/tracking/include/pcl/tracking/impl/tracking.hpp @@ -292,7 +292,7 @@ struct EIGEN_ALIGN16 ParticleXYZR : public _ParticleXYZR { float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; getTranslationAndEulerAngles( trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw); - return (pcl::tracking::ParticleXYZR(trans_x, trans_y, trans_z, 0, trans_pitch, 0)); + return {trans_x, trans_y, trans_z, 0, trans_pitch, 0}; } // a[i] @@ -458,8 +458,7 @@ struct EIGEN_ALIGN16 ParticleXYRPY : public _ParticleXYRPY { float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; getTranslationAndEulerAngles( trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw); - return (pcl::tracking::ParticleXYRPY( - trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw)); + return {trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw}; } // a[i] @@ -625,8 +624,7 @@ struct EIGEN_ALIGN16 ParticleXYRP : public _ParticleXYRP { float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; getTranslationAndEulerAngles( trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw); - return ( - pcl::tracking::ParticleXYRP(trans_x, 0, trans_z, 0, trans_pitch, trans_yaw)); + return {trans_x, 0, trans_z, 0, trans_pitch, trans_yaw}; } // a[i] @@ -792,7 +790,7 @@ struct EIGEN_ALIGN16 ParticleXYR : public _ParticleXYR { float trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw; getTranslationAndEulerAngles( trans, trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw); - return (pcl::tracking::ParticleXYR(trans_x, 0, trans_z, 0, trans_pitch, 0)); + return {trans_x, 0, trans_z, 0, trans_pitch, 0}; } // a[i] diff --git a/visualization/include/pcl/visualization/area_picking_event.h b/visualization/include/pcl/visualization/area_picking_event.h index 7753b96d8d2..26cb217612f 100644 --- a/visualization/include/pcl/visualization/area_picking_event.h +++ b/visualization/include/pcl/visualization/area_picking_event.h @@ -95,7 +95,7 @@ namespace pcl { const auto cloud = cloud_indices_.find (name); if(cloud == cloud_indices_.cend ()) - return Indices (); + return {}; return cloud->second; } diff --git a/visualization/src/common/common.cpp b/visualization/src/common/common.cpp index 807fe6d077e..92932334e44 100644 --- a/visualization/src/common/common.cpp +++ b/visualization/src/common/common.cpp @@ -115,7 +115,7 @@ pcl::visualization::worldToView (const Eigen::Vector4d &world_pt, const Eigen::M // Calculate -world_pt.y () because the screen Y axis is oriented top->down, ie 0 is top-left //int winY = (int) std::floor ( (double) (((1 - world_pt.y ()) / 2.0) * height) + 0.5); // top left - return (Eigen::Vector2i (screen_x, screen_y)); + return {screen_x, screen_y}; } ///////////////////////////////////////////////////////////////////////////////////////////// From 693c7a8e4bde3ef131d2de22f7c1dd5b647dbb94 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 13 Feb 2023 23:40:57 +0100 Subject: [PATCH 047/288] Update VCPKG to 2023.01.09 Release - since ICU links are broken. (#5607) * Update VCPKG to 2023.01.09 Release - since ICU links are broken. --- .ci/azure-pipelines/env.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index b5cde4c881b..4fc44c80a7b 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -119,7 +119,7 @@ jobs: PLATFORM: x86 TAG: winx86 GENERATOR: "'Visual Studio 16 2019' -A Win32" - VCPKGCOMMIT: acc3bcf76b84ae5041c86ab55fe138ae7b8255c7 + VCPKGCOMMIT: fd766eba2b4cf59c7123d46189be373e2cee959d Winx64: PLATFORM: x64 TAG: winx64 From 64ac46130855a8581d74015a41ac3d64be3f6b05 Mon Sep 17 00:00:00 2001 From: Patrick Scheckenbach <124401292+ptrckschcknbch@users.noreply.github.com> Date: Tue, 14 Feb 2023 09:49:40 +0100 Subject: [PATCH 048/288] Add writeBinary to ostream for PCDWriter (#5598) * Add writeBinary to ostream for PCDWriter Add method writeBinary to serialize point clouds in memory uncompressed. * Revert "Add writeBinary to ostream for PCDWriter" This reverts commit 55f3f80b57b0804b1d8881d3c7521d27ccc6b200. * Add independent writeBinary to ostream function Add method writeBinary to serialize point clouds in memory uncompressed. * Add unit test for writeBinary to ostream * Fix register macros to match struct definitions Fix the sequence order in POINT_CLOUD_REGISTER macros to match structs * Revert "Fix register macros to match struct definitions" This reverts commit b522e74139184e957bdf1acfe5ca746b14471ebb. * Sort fields in generateHeaderBinary Sort cloud.fields by their offset value to generate correct fake fields --- io/include/pcl/io/pcd_io.h | 11 ++++++ io/src/pcd_io.cpp | 53 ++++++++++++++++++++++------- test/io/test_io.cpp | 68 ++++++++++++++++++++++++++++++++++++++ 3 files changed, 120 insertions(+), 12 deletions(-) diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index c10c525e111..cc6cb2a8768 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -402,6 +402,17 @@ namespace pcl const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ()); + /** \brief Save point cloud data to a std::ostream containing n-D points, in BINARY format + * \param[out] os the stream into which to write the data + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor acquisition origin + * \param[in] orientation the sensor acquisition orientation + */ + int + writeBinary (std::ostream &os, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin = Eigen::Vector4f::Zero (), + const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity ()); + /** \brief Save point cloud data to a PCD file containing n-D points, in BINARY_COMPRESSED format * \param[in] file_name the output file name * \param[in] cloud the point cloud data message diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 49075bcebb7..04eedaa2abb 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -930,9 +930,15 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, "\nVERSION 0.7" "\nFIELDS"; + auto fields = cloud.fields; + std::sort(fields.begin(), fields.end(), [](const auto& field_a, const auto& field_b) + { + return field_a.offset < field_b.offset; + }); + // Compute the total size of the fields unsigned int fsize = 0; - for (const auto &field : cloud.fields) + for (const auto &field : fields) fsize += field.count * getFieldSize (field.datatype); // The size of the fields cannot be larger than point_step @@ -945,20 +951,20 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, std::stringstream field_names, field_types, field_sizes, field_counts; // Check if the size of the fields is smaller than the size of the point step std::size_t toffset = 0; - for (std::size_t i = 0; i < cloud.fields.size (); ++i) + for (std::size_t i = 0; i < fields.size (); ++i) { // If field offsets do not match, then we need to create fake fields - if (toffset != cloud.fields[i].offset) + if (toffset != fields[i].offset) { // If we're at the last "valid" field int fake_offset = (i == 0) ? // Use the current_field offset - (cloud.fields[i].offset) + (fields[i].offset) : // Else, do cur_field.offset - prev_field.offset + sizeof (prev_field) - (cloud.fields[i].offset - - (cloud.fields[i-1].offset + - cloud.fields[i-1].count * getFieldSize (cloud.fields[i-1].datatype))); + (fields[i].offset - + (fields[i-1].offset + + fields[i-1].count * getFieldSize (fields[i-1].datatype))); toffset += fake_offset; @@ -969,11 +975,11 @@ pcl::PCDWriter::generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, } // Add the regular dimension - toffset += cloud.fields[i].count * getFieldSize (cloud.fields[i].datatype); - field_names << " " << cloud.fields[i].name; - field_sizes << " " << pcl::getFieldSize (cloud.fields[i].datatype); - field_types << " " << pcl::getFieldType (cloud.fields[i].datatype); - int count = std::abs (static_cast (cloud.fields[i].count)); + toffset += fields[i].count * getFieldSize (fields[i].datatype); + field_names << " " << fields[i].name; + field_sizes << " " << pcl::getFieldSize (fields[i].datatype); + field_types << " " << pcl::getFieldType (fields[i].datatype); + int count = std::abs (static_cast (fields[i].count)); if (count == 0) count = 1; // check for 0 counts (coming from older converter code) field_counts << " " << count; } @@ -1173,6 +1179,29 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo return (0); } +/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +int +pcl::PCDWriter::writeBinary (std::ostream &os, const pcl::PCLPointCloud2 &cloud, + const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation) +{ + if (cloud.data.empty ()) + { + PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!\n"); + } + if (cloud.fields.empty()) + { + PCL_ERROR ("[pcl::PCDWriter::writeBinary] Input point cloud has no field data!\n"); + return (-1); + } + + os.imbue (std::locale::classic ()); + os << generateHeaderBinary (cloud, origin, orientation) << "DATA binary\n"; + std::copy (cloud.data.cbegin(), cloud.data.cend(), std::ostream_iterator (os)); + os.flush (); + + return (os ? 0 : -1); +} + /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// int pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &cloud, diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index a534c29e677..97716de54aa 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -1379,6 +1379,74 @@ TEST (PCL, LZFExtended) remove ("test_pcl_io_compressed.pcd"); } +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +TEST (PCL, WriteBinaryToOStream) +{ + PointCloud cloud; + cloud.width = 640; + cloud.height = 480; + cloud.resize (cloud.width * cloud.height); + cloud.is_dense = true; + + srand (static_cast (time (nullptr))); + const auto nr_p = cloud.size (); + // Randomly create a new point cloud + for (std::size_t i = 0; i < nr_p; ++i) + { + cloud[i].x = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].y = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].z = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].normal_x = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].normal_y = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].normal_z = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].rgb = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + } + + pcl::PCLPointCloud2 blob; + pcl::toPCLPointCloud2 (cloud, blob); + + std::ostringstream oss; + PCDWriter writer; + int res = writer.writeBinary (oss, blob); + EXPECT_EQ (res, 0); + std::string pcd_str = oss.str (); + + Eigen::Vector4f origin; + Eigen::Quaternionf orientation; + int pcd_version = -1; + int data_type = -1; + unsigned int data_idx = 0; + std::istringstream iss (pcd_str, std::ios::binary); + PCDReader reader; + pcl::PCLPointCloud2 blob2; + res = reader.readHeader (iss, blob2, origin, orientation, pcd_version, data_type, data_idx); + EXPECT_EQ (res, 0); + EXPECT_EQ (blob2.width, blob.width); + EXPECT_EQ (blob2.height, blob.height); + EXPECT_EQ (data_type, 1); // since it was written by writeBinary (), it should be uncompressed. + + const auto *data = reinterpret_cast (pcd_str.data ()); + res = reader.readBodyBinary (data, blob2, pcd_version, data_type == 2, data_idx); + PointCloud cloud2; + pcl::fromPCLPointCloud2 (blob2, cloud2); + EXPECT_EQ (res, 0); + EXPECT_EQ (cloud2.width, blob.width); + EXPECT_EQ (cloud2.height, blob.height); + EXPECT_EQ (cloud2.is_dense, cloud.is_dense); + EXPECT_EQ (cloud2.size (), cloud.size ()); + + for (std::size_t i = 0; i < cloud2.size (); ++i) + { + EXPECT_EQ (cloud2[i].x, cloud[i].x); + EXPECT_EQ (cloud2[i].y, cloud[i].y); + EXPECT_EQ (cloud2[i].z, cloud[i].z); + EXPECT_EQ (cloud2[i].normal_x, cloud[i].normal_x); + EXPECT_EQ (cloud2[i].normal_y, cloud[i].normal_y); + EXPECT_EQ (cloud2[i].normal_z, cloud[i].normal_z); + EXPECT_EQ (cloud2[i].rgb, cloud[i].rgb); + } +} + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, LZFInMem) { From ad56383c14b749bdec80fad1ca8c570c3899a296 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 20 Feb 2023 12:59:45 +0100 Subject: [PATCH 049/288] Remove last usage of date_time and replace it with std::chrono (#5596) * Remove last usage of date_time and replace it with std::chrono * Added new header with getTimestamp method. Added unit test to ensure it returns as expected, like boost format. Changed tools to use the new function. * Fix us printout. * Use frametime and not current time. * Minor doc correction. * Renaming. * Remove posix_time in additional files. Add parsing of string to time_point. Return timestamp in local timezone instead of UTC. rename from timestamp_generator to timestamp, since it can also parse now. * Add duration parse to microseconds, to get correct difference. * Doxygen Faster find using a char instead of string, per clang-tidy. * Remove last occurrences of date-time and only call pcl::getTimestamp once in openni_save_image.cpp. * Fix if check for position of dot in iso timestamp string. * Address reviews: getTime returns time in seconds, don't multiply with 1000 in kinfu. Lowercase timestamp test in test/io/CMakeLists.txt Call getTimestamp once in openni_image. --- .dev/docker/env/Dockerfile | 2 +- .dev/docker/release/Dockerfile | 2 +- .dev/docker/ubuntu-variety/Dockerfile | 2 +- apps/src/openni_grab_frame.cpp | 4 +- apps/src/openni_grab_images.cpp | 6 +- apps/src/openni_klt.cpp | 7 +- cmake/pcl_find_boost.cmake | 2 +- cmake/pcl_pclconfig.cmake | 2 +- common/include/pcl/common/boost.h | 1 - doc/tutorials/content/building_pcl.rst | 50 ++++----- doc/tutorials/content/dinast_grabber.rst | 106 +++++++++--------- doc/tutorials/content/openni_grabber.rst | 11 +- doc/tutorials/content/pcl_visualizer.rst | 2 +- gpu/kinfu/tools/kinfu_app.cpp | 23 ++-- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 23 ++-- io/CMakeLists.txt | 1 + io/include/pcl/io/boost.h | 1 - io/include/pcl/io/timestamp.h | 77 +++++++++++++ io/src/image_grabber.cpp | 7 +- io/tools/CMakeLists.txt | 2 +- io/tools/openni_pcd_recorder.cpp | 9 +- test/io/CMakeLists.txt | 4 + test/io/test_timestamp.cpp | 64 +++++++++++ tools/CMakeLists.txt | 4 +- tools/openni_image.cpp | 22 ++-- tools/openni_save_image.cpp | 10 +- .../include/pcl/visualization/boost.h | 1 - 27 files changed, 297 insertions(+), 148 deletions(-) create mode 100644 io/include/pcl/io/timestamp.h create mode 100644 test/io/test_timestamp.cpp diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index e2cabbd76c6..67a6e9d81b6 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -30,7 +30,7 @@ RUN apt-get update \ clang-tidy \ libbenchmark-dev \ libblas-dev \ - libboost-date-time-dev \ + libboost-serialization-dev \ libboost-filesystem-dev \ libboost-iostreams-dev \ libflann-dev \ diff --git a/.dev/docker/release/Dockerfile b/.dev/docker/release/Dockerfile index 8b156a982c6..65b04c89936 100644 --- a/.dev/docker/release/Dockerfile +++ b/.dev/docker/release/Dockerfile @@ -15,7 +15,7 @@ RUN sed -i 's/^deb \(.*\)$/deb \1\ndeb-src \1/' /etc/apt/sources.list \ dpkg-dev \ git \ g++ \ - libboost-date-time-dev \ + libboost-serialization-dev \ libboost-filesystem-dev \ libboost-iostreams-dev \ libeigen3-dev \ diff --git a/.dev/docker/ubuntu-variety/Dockerfile b/.dev/docker/ubuntu-variety/Dockerfile index 6eb149f903a..a84bb558d20 100644 --- a/.dev/docker/ubuntu-variety/Dockerfile +++ b/.dev/docker/ubuntu-variety/Dockerfile @@ -15,7 +15,7 @@ ENV DEBIAN_FRONTEND=noninteractive RUN apt update RUN apt install -y git cmake ${COMPILER_PACKAGE} RUN apt install -y libeigen3-dev libflann-dev -RUN apt install -y libboost-filesystem-dev libboost-date-time-dev libboost-iostreams-dev +RUN apt install -y libboost-filesystem-dev libboost-serialization-dev libboost-iostreams-dev RUN apt install -y libgtest-dev libbenchmark-dev RUN apt install -y qtbase5-dev libvtk${VTK_VERSION}-dev libvtk${VTK_VERSION}-qt-dev diff --git a/apps/src/openni_grab_frame.cpp b/apps/src/openni_grab_frame.cpp index f61ff619405..fbdc4d42ebf 100644 --- a/apps/src/openni_grab_frame.cpp +++ b/apps/src/openni_grab_frame.cpp @@ -40,6 +40,7 @@ #include #include #include +#include #include #include #include @@ -157,8 +158,7 @@ class OpenNIGrabFrame { saveCloud() { FPS_CALC("I/O"); - const std::string time = boost::posix_time::to_iso_string( - boost::posix_time::microsec_clock::local_time()); + const std::string time = pcl::getTimestamp(); const std::string filepath = dir_name_ + '/' + file_name_ + '_' + time + ".pcd"; if (format_ & 1) { diff --git a/apps/src/openni_grab_images.cpp b/apps/src/openni_grab_images.cpp index 3d1dc8ba9e3..7a864567129 100644 --- a/apps/src/openni_grab_images.cpp +++ b/apps/src/openni_grab_images.cpp @@ -117,8 +117,7 @@ class OpenNIGrabFrame { void saveImages() { - std::string time = boost::posix_time::to_iso_string( - boost::posix_time::microsec_clock::local_time()); + const std::string time = pcl::getTimestamp(); openni_wrapper::Image::Ptr image; openni_wrapper::DepthImage::Ptr depth_image; @@ -204,8 +203,7 @@ class OpenNIGrabFrame { // wait until user quits program with Ctrl-C, but no busy-waiting -> sleep (1); while (!image_viewer_.wasStopped() && !quit_) { - std::string time = boost::posix_time::to_iso_string( - boost::posix_time::microsec_clock::local_time()); + const std::string time = pcl::getTimestamp(); openni_wrapper::Image::Ptr image; openni_wrapper::DepthImage::Ptr depth_image; diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index 41b5f81c067..164426ba396 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -39,12 +39,11 @@ #include #include #include +#include #include #include #include -#include // for to_iso_string, local_time - #include #define SHOW_FPS 1 @@ -175,9 +174,7 @@ class OpenNIViewer { if ((event.getKeyCode() == 's') || (event.getKeyCode() == 'S')) { std::lock_guard lock(cloud_mutex_); frame.str("frame-"); - frame << boost::posix_time::to_iso_string( - boost::posix_time::microsec_clock::local_time()) - << ".pcd"; + frame << pcl::getTimestamp() << ".pcd"; writer.writeBinaryCompressed(frame.str(), *cloud_); PCL_INFO("Written cloud %s.\n", frame.str().c_str()); } diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index 2efcf3cbecf..7b7783861b7 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -26,7 +26,7 @@ if(Boost_SERIALIZATION_FOUND) endif() # Required boost modules -set(BOOST_REQUIRED_MODULES filesystem date_time iostreams system) +set(BOOST_REQUIRED_MODULES filesystem iostreams system) find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) if(Boost_FOUND) diff --git a/cmake/pcl_pclconfig.cmake b/cmake/pcl_pclconfig.cmake index 40e5ad80ba6..84a29ae0794 100644 --- a/cmake/pcl_pclconfig.cmake +++ b/cmake/pcl_pclconfig.cmake @@ -78,7 +78,7 @@ foreach(_ss ${PCL_SUBSYSTEMS_MODULES}) endforeach() #Boost modules -set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem date_time iostreams") +set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem iostreams") if(Boost_SERIALIZATION_FOUND) string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " serialization") endif() diff --git a/common/include/pcl/common/boost.h b/common/include/pcl/common/boost.h index 232d1df5f3b..068e48999fd 100644 --- a/common/include/pcl/common/boost.h +++ b/common/include/pcl/common/boost.h @@ -47,7 +47,6 @@ PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly." // Marking all Boost headers as system headers to remove warnings #include #include -#include #include #include #include diff --git a/doc/tutorials/content/building_pcl.rst b/doc/tutorials/content/building_pcl.rst index 95f2e3bb16d..187b4b0760c 100644 --- a/doc/tutorials/content/building_pcl.rst +++ b/doc/tutorials/content/building_pcl.rst @@ -198,31 +198,31 @@ then a sample value is given for reference. * Boost -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| cache variable | meaning | sample value | -+==================================+===============================================================+==========================================+ -| Boost_DATE_TIME_LIBRARY | full path to boost_date-time.[so,lib,a] | /usr/local/lib/libboost_date_time.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_DATE_TIME_LIBRARY_DEBUG | full path to boost_date-time.[so,lib,a] (debug version) | /usr/local/lib/libboost_date_time-gd.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_DATE_TIME_LIBRARY_RELEASE | full path to boost_date-time.[so,lib,a] (release version) | /usr/local/lib/libboost_date_time.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_FILESYSTEM_LIBRARY | full path to boost_filesystem.[so,lib,a] | /usr/local/lib/libboost_filesystem.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_FILESYSTEM_LIBRARY_DEBUG | full path to boost_filesystem.[so,lib,a] (debug version) | /usr/local/lib/libboost_filesystem-gd.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_FILESYSTEM_LIBRARY_RELEASE | full path to boost_filesystem.[so,lib,a] (release version) | /usr/local/lib/libboost_filesystem.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_INCLUDE_DIR | path to boost headers directory | /usr/local/include | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_LIBRARY_DIRS | path to boost libraries directory | /usr/local/lib | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_SYSTEM_LIBRARY | full path to boost_system.[so,lib,a] | /usr/local/lib/libboost_system.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_SYSTEM_LIBRARY_DEBUG | full path to boost_system.[so,lib,a] (debug version) | /usr/local/lib/libboost_system-gd.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ -| Boost_SYSTEM_LIBRARY_RELEASE | full path to boost_system.[so,lib,a] (release version) | /usr/local/lib/libboost_system.so | -+----------------------------------+---------------------------------------------------------------+------------------------------------------+ ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| cache variable | meaning | sample value | ++=====================================+===============================================================+=============================================+ +| Boost_SERIALIZATION_LIBRARY | full path to boost_serialization.[so,lib,a] | /usr/local/lib/libboost_serialization.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_SERIALIZATION_LIBRARY_DEBUG | full path to boost_serialization.[so,lib,a] (debug version) | /usr/local/lib/libboost_serialization-gd.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_SERIALIZATION_LIBRARY_RELEASE | full path to boost_serialization.[so,lib,a] (release version) | /usr/local/lib/libboost_serialization.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_FILESYSTEM_LIBRARY | full path to boost_filesystem.[so,lib,a] | /usr/local/lib/libboost_filesystem.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_FILESYSTEM_LIBRARY_DEBUG | full path to boost_filesystem.[so,lib,a] (debug version) | /usr/local/lib/libboost_filesystem-gd.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_FILESYSTEM_LIBRARY_RELEASE | full path to boost_filesystem.[so,lib,a] (release version) | /usr/local/lib/libboost_filesystem.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_INCLUDE_DIR | path to boost headers directory | /usr/local/include | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_LIBRARY_DIRS | path to boost libraries directory | /usr/local/lib | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_SYSTEM_LIBRARY | full path to boost_system.[so,lib,a] | /usr/local/lib/libboost_system.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_SYSTEM_LIBRARY_DEBUG | full path to boost_system.[so,lib,a] (debug version) | /usr/local/lib/libboost_system-gd.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ +| Boost_SYSTEM_LIBRARY_RELEASE | full path to boost_system.[so,lib,a] (release version) | /usr/local/lib/libboost_system.so | ++-------------------------------------+---------------------------------------------------------------+---------------------------------------------+ * CMinpack diff --git a/doc/tutorials/content/dinast_grabber.rst b/doc/tutorials/content/dinast_grabber.rst index 5f3c0c4fcce..d83c1e47879 100644 --- a/doc/tutorials/content/dinast_grabber.rst +++ b/doc/tutorials/content/dinast_grabber.rst @@ -41,69 +41,73 @@ The code from *apps/src/dinast_grabber_example.cpp* will be used for this tutori :linenos: #include - #include #include #include + #include + + #include + #include + + using namespace std::chrono_literals; template - class DinastProcessor - { - public: - - typedef pcl::PointCloud Cloud; - typedef typename Cloud::ConstPtr CloudConstPtr; - - DinastProcessor(pcl::Grabber& grabber) : interface(grabber), viewer("Dinast Cloud Viewer") {} - - void - cloud_cb_ (CloudConstPtr cloud_cb) - { - static unsigned count = 0; - static double last = pcl::getTime (); - if (++count == 30) - { - double now = pcl::getTime (); - std::cout << "Average framerate: " << double(count)/double(now - last) << " Hz" << std::endl; - count = 0; - last = now; - } - if (!viewer.wasStopped()) - viewer.showCloud(cloud_cb); + class DinastProcessor { + public: + using Cloud = pcl::PointCloud; + using CloudConstPtr = typename Cloud::ConstPtr; + + DinastProcessor(pcl::Grabber& grabber) + : interface(grabber), viewer("Dinast Cloud Viewer") + {} + + void + cloud_cb_(CloudConstPtr cloud_cb) + { + static unsigned count = 0; + static double last = pcl::getTime(); + if (++count == 30) { + double now = pcl::getTime(); + std::cout << "Average framerate: " << double(count) / double(now - last) << " Hz" + << std::endl; + count = 0; + last = now; } - - int - run () - { - - std::function f = - [this] (const CloudConstPtr& cloud) { cloud_cb_ (cloud); }; - - boost::signals2::connection c = interface.registerCallback (f); + if (!viewer.wasStopped()) + viewer.showCloud(cloud_cb); + } - interface.start (); - - while (!viewer.wasStopped()) - { - boost::this_thread::sleep (boost::posix_time::seconds (1)); - } - - interface.stop (); - - return(0); + int + run() + { + + std::function f = [this](const CloudConstPtr& cloud) { + cloud_cb_(cloud); + }; + + boost::signals2::connection c = interface.registerCallback(f); + + interface.start(); + + while (!viewer.wasStopped()) { + std::this_thread::sleep_for(1s); } - - pcl::Grabber& interface; - pcl::visualization::CloudViewer viewer; - + + interface.stop(); + + return 0; + } + + pcl::Grabber& interface; + pcl::visualization::CloudViewer viewer; }; int - main () + main() { pcl::DinastGrabber grabber; - DinastProcessor v (grabber); - v.run (); - return (0); + DinastProcessor v(grabber); + v.run(); + return 0; } The explanation diff --git a/doc/tutorials/content/openni_grabber.rst b/doc/tutorials/content/openni_grabber.rst index 885f1247b03..56fdb84e7c0 100644 --- a/doc/tutorials/content/openni_grabber.rst +++ b/doc/tutorials/content/openni_grabber.rst @@ -36,13 +36,20 @@ the OpenNI Grabber. -So let's look at the code. From *visualization/tools/openni_viewer_simple.cpp* +So let's look at the code. From *tools/openni_viewer_simple.cpp* .. code-block:: cpp :linenos: #include #include + + + #include + #include + + using namespace std::chrono_literals; + class SimpleOpenNIViewer { @@ -68,7 +75,7 @@ So let's look at the code. From *visualization/tools/openni_viewer_simple.cpp* while (!viewer.wasStopped()) { - boost::this_thread::sleep (boost::posix_time::seconds (1)); + std::this_thread::sleep_for(1s); } interface->stop (); diff --git a/doc/tutorials/content/pcl_visualizer.rst b/doc/tutorials/content/pcl_visualizer.rst index 1cedca26ac7..af0a39d55af 100644 --- a/doc/tutorials/content/pcl_visualizer.rst +++ b/doc/tutorials/content/pcl_visualizer.rst @@ -145,7 +145,7 @@ found at the bottom of the sample: while (!viewer->wasStopped ()) { viewer->spinOnce (100); - boost::this_thread::sleep (boost::posix_time::microseconds (100000)); + std::this_thread::sleep_for(100ms); } ... diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 04f91172f08..af65de9337f 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -44,7 +44,6 @@ #include #include -#include // for microsec_clock::local_time #include #include @@ -201,24 +200,24 @@ std::vector getPcdFilesInDir(const std::string& directory) struct SampledScopeTime : public StopWatch { enum { EACH = 33 }; - SampledScopeTime(int& time_ms) : time_ms_(time_ms) {} + SampledScopeTime(double& time_s) : time_s_(time_s) {} ~SampledScopeTime() { static int i_ = 0; - static boost::posix_time::ptime starttime_ = boost::posix_time::microsec_clock::local_time(); - time_ms_ += getTime (); + static double starttime_ = pcl::getTime(); + time_s_ += getTime (); if (i_ % EACH == 0 && i_) { - boost::posix_time::ptime endtime_ = boost::posix_time::microsec_clock::local_time(); - std::cout << "Average frame time = " << time_ms_ / EACH << "ms ( " << 1000.f * EACH / time_ms_ << "fps )" - << "( real: " << 1000.f * EACH / (endtime_-starttime_).total_milliseconds() << "fps )" << std::endl; - time_ms_ = 0; + const auto endtime_ = pcl::getTime(); + std::cout << "Average frame time = " << time_s_ / EACH << "ms ( " << EACH / time_s_ << "fps )" + << "( real: " < depth_; PtrStepSz rgb24_; - int time_ms_; + double time_s_; int icp_, viz_; CameraPoseProcessor::Ptr pose_processor_; diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index d2b8c71279f..f923dd0559f 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -56,7 +56,6 @@ Work in progress: patch by Marco (AUG,19th 2012) #include #include -#include // for microsec_clock::local_time #include #include @@ -151,24 +150,24 @@ std::vector getPcdFilesInDir(const std::string& directory) struct SampledScopeTime : public StopWatch { enum { EACH = 33 }; - SampledScopeTime(int& time_ms) : time_ms_(time_ms) {} + SampledScopeTime(double& time_s) : time_s_(time_s) {} ~SampledScopeTime() { static int i_ = 0; - static boost::posix_time::ptime starttime_ = boost::posix_time::microsec_clock::local_time(); - time_ms_ += getTime (); + static double starttime_ = pcl::getTime(); + time_s_ += getTime (); if (i_ % EACH == 0 && i_) { - boost::posix_time::ptime endtime_ = boost::posix_time::microsec_clock::local_time(); - std::cout << "Average frame time = " << time_ms_ / EACH << "ms ( " << 1000.f * EACH / time_ms_ << "fps )" - << "( real: " << 1000.f * EACH / (endtime_-starttime_).total_milliseconds() << "fps )" << std::endl; - time_ms_ = 0; + const auto endtime_ = pcl::getTime(); + std::cout << "Average frame time = " << time_s_ / EACH << "ms ( " << EACH / time_s_ << "fps )" + << "( real: " << EACH / (endtime_-starttime_) << "fps )" << std::endl; + time_s_ = 0; starttime_ = endtime_; } ++i_; } private: - int& time_ms_; + double& time_s_; }; /////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -701,7 +700,7 @@ struct KinFuLSApp enum { PCD_BIN = 1, PCD_ASCII = 2, PLY = 3, MESH_PLY = 7, MESH_VTK = 8 }; KinFuLSApp(pcl::Grabber& source, float vsz, float shiftDistance, int snapshotRate) : exit_ (false), scan_ (false), scan_mesh_(false), scan_volume_ (false), independent_camera_ (false), - registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), was_lost_(false), time_ms_ (0) + registration_ (false), integrate_colors_ (false), pcd_source_ (false), focal_length_(-1.f), capture_ (source), was_lost_(false), time_s_ (0) { //Init Kinfu Tracker Eigen::Vector3f volume_size = Vector3f::Constant (vsz/*meters*/); @@ -829,7 +828,7 @@ struct KinFuLSApp image_view_.colors_device_.upload (rgb24.data, rgb24.step, rgb24.rows, rgb24.cols); { - SampledScopeTime fps(time_ms_); + SampledScopeTime fps(time_s_); //run kinfu algorithm if (integrate_colors_) @@ -1198,7 +1197,7 @@ struct KinFuLSApp bool was_lost_; - int time_ms_; + double time_s_; ///////////////////////////////////////////////////////////////////////////////////////////////////////////////////// static void diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index 55baf49e1aa..d63c3864f2d 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -269,6 +269,7 @@ set(incs "include/pcl/${SUBSYS_NAME}/io.h" "include/pcl/${SUBSYS_NAME}/grabber.h" "include/pcl/${SUBSYS_NAME}/file_grabber.h" + "include/pcl/${SUBSYS_NAME}/timestamp.h" "include/pcl/${SUBSYS_NAME}/pcd_grabber.h" "include/pcl/${SUBSYS_NAME}/pcd_io.h" "include/pcl/${SUBSYS_NAME}/vtk_io.h" diff --git a/io/include/pcl/io/boost.h b/io/include/pcl/io/boost.h index be19192f2f6..a0867796df8 100644 --- a/io/include/pcl/io/boost.h +++ b/io/include/pcl/io/boost.h @@ -52,7 +52,6 @@ PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly." #include #include #include -#include #include #include #include diff --git a/io/include/pcl/io/timestamp.h b/io/include/pcl/io/timestamp.h new file mode 100644 index 00000000000..ca987a95c41 --- /dev/null +++ b/io/include/pcl/io/timestamp.h @@ -0,0 +1,77 @@ +/* + * SPDX-License-Identifier: BSD-3-Clause + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2023-, Open Perception + * + * All rights reserved + */ + +#include + +#include +#include +#include +#include + +namespace pcl { +/** + * @brief Returns a timestamp in local time as string formatted like boosts to_iso_string see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string + * Example: 19750101T235959.123456 + * @param time std::chrono::timepoint to convert, defaults to now + * @return std::string containing the timestamp +*/ +PCL_EXPORTS inline std::string +getTimestamp(const std::chrono::time_point& time = + std::chrono::system_clock::now()) +{ + const auto us = + std::chrono::duration_cast(time.time_since_epoch()); + + const auto s = std::chrono::duration_cast(us); + std::time_t tt = s.count(); + std::size_t fractional_seconds = us.count() % 1000000; + + std::tm tm = *std::localtime(&tt); // local time + std::stringstream ss; + ss << std::put_time(&tm, "%Y%m%dT%H%M%S"); + + if (fractional_seconds > 0) { + ss << "." << std::setw(6) << std::setfill('0') << fractional_seconds; + } + + return ss.str(); +} + +/** + * @brief Parses a iso timestring (see https://www.boost.org/doc/libs/1_81_0/doc/html/date_time/posix_time.html#ptime_to_string) and returns a timepoint + * @param timestamp as string formatted like boost iso date + * @return std::chrono::time_point with system_clock +*/ +PCL_EXPORTS inline std::chrono::time_point +parseTimestamp(std::string timestamp) +{ + std::istringstream ss; + + std::tm tm = {}; + + std::size_t fractional_seconds = 0; + + ss.str(timestamp); + ss >> std::get_time(&tm, "%Y%m%dT%H%M%S"); + + auto timepoint = std::chrono::system_clock::from_time_t(std::mktime(&tm)); + + const auto pos = timestamp.find('.'); + + if (pos != std::string::npos) { + const auto frac_text = timestamp.substr(pos+1); + ss.str(frac_text); + ss >> fractional_seconds; + timepoint += std::chrono::microseconds(fractional_seconds); + } + + return timepoint; +} + +} // namespace pcl diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 99529fb3aa9..99511ec719c 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -36,6 +36,7 @@ */ // Looking for PCL_BUILT_WITH_VTK #include +#include #include #include #include @@ -43,7 +44,6 @@ #include #include // for exists, basename, is_directory, ... #include // for to_upper_copy -#include // for posix_time #ifdef PCL_BUILT_WITH_VTK #include @@ -435,10 +435,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getTimestampFromFilepath ( if (result > 0) { // Convert to std::uint64_t, microseconds since 1970-01-01 - boost::posix_time::ptime cur_date = boost::posix_time::from_iso_string (timestamp_str); - boost::posix_time::ptime zero_date ( - boost::gregorian::date (1970,boost::gregorian::Jan,1)); - timestamp = (cur_date - zero_date).total_microseconds (); + timestamp = std::chrono::duration(pcl::parseTimestamp(timestamp_str).time_since_epoch()).count(); return (true); } return (false); diff --git a/io/tools/CMakeLists.txt b/io/tools/CMakeLists.txt index 818da1d99c8..651bb00daa5 100644 --- a/io/tools/CMakeLists.txt +++ b/io/tools/CMakeLists.txt @@ -9,7 +9,7 @@ if(WITH_OPENNI) PCL_ADD_EXECUTABLE(pcl_openni_pcd_recorder COMPONENT ${SUBSYS_NAME} SOURCES openni_pcd_recorder.cpp) - target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io Boost::date_time) + target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io) endif() PCL_ADD_EXECUTABLE(pcl_pcd_convert_NaN_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_convert_NaN_nan.cpp) diff --git a/io/tools/openni_pcd_recorder.cpp b/io/tools/openni_pcd_recorder.cpp index 06ff97f7be6..0f3bfed73de 100644 --- a/io/tools/openni_pcd_recorder.cpp +++ b/io/tools/openni_pcd_recorder.cpp @@ -36,13 +36,14 @@ #include #include #include +#include #include -#include // for to_iso_string, local_time #include #include #include #include //fps calculations +#include #include #include #include @@ -282,10 +283,8 @@ class Consumer void writeToDisk (const typename PointCloud::ConstPtr& cloud) { - std::stringstream ss; - std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ()); - ss << "frame-" << time << ".pcd"; - writer_.writeBinaryCompressed (ss.str (), *cloud); + const std::string file_name = "frame-" + pcl::getTimestamp() + ".pcd"; + writer_.writeBinaryCompressed(file_name, *cloud); FPS_CALC ("cloud write.", buf_); } diff --git a/test/io/CMakeLists.txt b/test/io/CMakeLists.txt index 82fe839e492..6a57a682662 100644 --- a/test/io/CMakeLists.txt +++ b/test/io/CMakeLists.txt @@ -12,6 +12,10 @@ if(NOT build) return() endif() +PCL_ADD_TEST(timestamp test_timestamp + FILES test_timestamp.cpp + LINK_WITH pcl_gtest pcl_io) + PCL_ADD_TEST(io_io test_io FILES test_io.cpp LINK_WITH pcl_gtest pcl_io) diff --git a/test/io/test_timestamp.cpp b/test/io/test_timestamp.cpp new file mode 100644 index 00000000000..a9f318217f7 --- /dev/null +++ b/test/io/test_timestamp.cpp @@ -0,0 +1,64 @@ +#include +#include + +std::string +getTimeOffset() +{ + // local offset + auto offset_hour = std::localtime(new time_t(0))->tm_hour; + std::ostringstream ss; + ss << std::setfill('0') << std::setw(2) << offset_hour; + + return ss.str(); +} + +TEST(PCL, TestTimestampGeneratorZeroFraction) +{ + const std::chrono::time_point time; + + const auto timestamp = pcl::getTimestamp(time); + + EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000"); +} + +TEST(PCL, TestTimestampGeneratorWithFraction) +{ + const std::chrono::microseconds dur(123456); + const std::chrono::time_point dt(dur); + + const auto timestamp = pcl::getTimestamp(dt); + + EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.123456"); +} + +TEST(PCL, TestTimestampGeneratorWithSmallFraction) +{ + const std::chrono::microseconds dur(123); + const std::chrono::time_point dt(dur); + + const auto timestamp = pcl::getTimestamp(dt); + + EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.000123"); +} + +TEST(PCL, TestParseTimestamp) +{ + const std::chrono::time_point timepoint(std::chrono::system_clock::now()); + + const auto timestamp = pcl::getTimestamp(timepoint); + + const auto parsedTimepoint = pcl::parseTimestamp(timestamp); + + const auto diff = std::chrono::duration(timepoint - parsedTimepoint).count(); + + EXPECT_LT(diff, 1e-3); +} + +/* ---[ */ +int +main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return (RUN_ALL_TESTS()); +} +/* ]--- */ diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index f92258405db..755960466f2 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -276,7 +276,7 @@ else() if(WITH_OPENNI) PCL_ADD_EXECUTABLE(pcl_openni_save_image COMPONENT ${SUBSYS_NAME} SOURCES openni_save_image.cpp) - target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization Boost::date_time) + target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization) PCL_ADD_EXECUTABLE(pcl_pcd_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_grabber_viewer.cpp BUNDLE) target_link_libraries(pcl_pcd_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) @@ -297,7 +297,7 @@ else() target_link_libraries(pcl_openni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) PCL_ADD_EXECUTABLE(pcl_openni_image COMPONENT ${SUBSYS_NAME} SOURCES openni_image.cpp BUNDLE) - target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization Boost::date_time) + target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization) endif() if(WITH_OPENNI2) diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index d0855613704..84a1d7c3281 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -37,22 +37,23 @@ #include #include //fps calculations -#include #include +#include +#include +#include #include #include -#include #include #include #include -#include // for ptime, to_iso_string, ... +#include #include #include +#include #include #include -#include using namespace std::chrono_literals; using namespace pcl; @@ -145,7 +146,7 @@ struct Frame const openni_wrapper::DepthImage::Ptr &_depth_image, const io::CameraParameters &_parameters_rgb, const io::CameraParameters &_parameters_depth, - const boost::posix_time::ptime &_time) + const std::chrono::time_point& _time) : image (_image) , depth_image (_depth_image) , parameters_rgb (_parameters_rgb) @@ -158,7 +159,7 @@ struct Frame io::CameraParameters parameters_rgb, parameters_depth; - boost::posix_time::ptime time; + std::chrono::time_point time; }; ////////////////////////////////////////////////////////////////////////////////////////// @@ -265,8 +266,9 @@ class Writer FPS_CALC_WRITER ("data write ", buf_); nr_frames_total++; - - std::string time_string = boost::posix_time::to_iso_string (frame->time); + + const std::string time_string = getTimestamp(frame->time); + // Save RGB data const std::string rgb_filename = "frame_" + time_string + "_rgb.pclzf"; switch (frame->image->getEncoding ()) @@ -293,6 +295,7 @@ class Writer // Save depth data const std::string depth_filename = "frame_" + time_string + "_depth.pclzf"; + io::LZFDepth16ImageWriter ld; //io::LZFShift11ImageWriter ld; ld.write (reinterpret_cast (&frame->depth_image->getDepthMetaData ().Data ()[0]), frame->depth_image->getWidth (), frame->depth_image->getHeight (), depth_filename); @@ -371,7 +374,8 @@ class Driver const openni_wrapper::DepthImage::Ptr &depth_image, float) { - boost::posix_time::ptime time = boost::posix_time::microsec_clock::local_time (); + const auto time = std::chrono::system_clock::now(); + FPS_CALC_DRIVER ("driver ", buf_write_, buf_vis_); // Extract camera parameters diff --git a/tools/openni_save_image.cpp b/tools/openni_save_image.cpp index 54a86287f13..1787c977d3c 100644 --- a/tools/openni_save_image.cpp +++ b/tools/openni_save_image.cpp @@ -36,6 +36,7 @@ */ #include //fps calculations +#include #include #include #include @@ -46,10 +47,10 @@ #include #include +#include #include #include #include -#include // for to_iso_string, local_time #define SHOW_FPS 1 @@ -125,7 +126,8 @@ class SimpleOpenNIViewer { std::lock_guard lock (image_mutex_); - std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ()); + const auto timestamp = pcl::getTimestamp(); + if (image_) { FPS_CALC ("writer callback"); @@ -151,7 +153,7 @@ class SimpleOpenNIViewer data = reinterpret_cast (rgb_data); } - const std::string filename = "frame_" + time + "_rgb.tiff"; + const std::string filename = "frame_" + timestamp + "_rgb.tiff"; importer_->SetImportVoidPointer (const_cast(data), 1); importer_->Update (); flipper_->SetInputConnection (importer_->GetOutputPort ()); @@ -166,7 +168,7 @@ class SimpleOpenNIViewer openni_wrapper::DepthImage::Ptr depth_image; depth_image.swap (depth_image_); - const std::string filename = "frame_" + time + "_depth.tiff"; + const std::string filename = "frame_" + timestamp + "_depth.tiff"; depth_importer_->SetWholeExtent (0, depth_image->getWidth () - 1, 0, depth_image->getHeight () - 1, 0, 0); depth_importer_->SetDataExtentToWholeExtent (); diff --git a/visualization/include/pcl/visualization/boost.h b/visualization/include/pcl/visualization/boost.h index 8efff445ec3..a1978ca68ee 100644 --- a/visualization/include/pcl/visualization/boost.h +++ b/visualization/include/pcl/visualization/boost.h @@ -51,5 +51,4 @@ PCL_DEPRECATED_HEADER(1, 16, "Please include the needed boost headers directly." #include #include #include -#include #include From 83d3ba506615522d7bbf4ae959d8540fac74874e Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 21 Feb 2023 11:17:26 +0100 Subject: [PATCH 050/288] Changes to tools (#5605) * Move IO tools to tools folder. * Made all dependencies optional and build tools if requirements are met. * Fix opnni_viewer_simple * Satisfy clang-tidy * Make io hard-dependency. * Link pcl_common to pcl_io_ply. * Fix includes from pcl_common. * Remove check for pcl_io target. Move tools under if target pcl_recognition. Move tools under other if, having nested if instead of multiple conditions in ifs. * More reorganizing due to dependencies. * Fixup remove boost. * Fix missing TARGET keyword Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- common/CMakeLists.txt | 6 +- io/CMakeLists.txt | 6 +- io/tools/CMakeLists.txt | 28 -- io/tools/ply/CMakeLists.txt | 11 - tools/CMakeLists.txt | 461 ++++++++++-------- .../convert_pcd_ascii_binary.cpp | 0 {io/tools => tools}/converter.cpp | 0 {io/tools => tools}/hdl_grabber_example.cpp | 0 .../openni_grabber_depth_example.cpp | 0 .../openni_grabber_example.cpp | 0 {io/tools => tools}/openni_pcd_recorder.cpp | 0 tools/openni_viewer_simple.cpp | 30 +- {io/tools => tools}/pcd_convert_NaN_nan.cpp | 0 {io/tools => tools}/pcd_introduce_nan.cpp | 0 {io/tools/ply => tools}/ply2obj.cpp | 0 {io/tools/ply => tools}/ply2ply.cpp | 0 {io/tools/ply => tools}/ply2raw.cpp | 0 {io/tools/ply => tools}/plyheader.cpp | 0 18 files changed, 288 insertions(+), 254 deletions(-) delete mode 100644 io/tools/CMakeLists.txt delete mode 100644 io/tools/ply/CMakeLists.txt rename {io/tools => tools}/convert_pcd_ascii_binary.cpp (100%) rename {io/tools => tools}/converter.cpp (100%) rename {io/tools => tools}/hdl_grabber_example.cpp (100%) rename {io/tools => tools}/openni_grabber_depth_example.cpp (100%) rename {io/tools => tools}/openni_grabber_example.cpp (100%) rename {io/tools => tools}/openni_pcd_recorder.cpp (100%) rename {io/tools => tools}/pcd_convert_NaN_nan.cpp (100%) rename {io/tools => tools}/pcd_introduce_nan.cpp (100%) rename {io/tools/ply => tools}/ply2obj.cpp (100%) rename {io/tools/ply => tools}/ply2ply.cpp (100%) rename {io/tools/ply => tools}/ply2raw.cpp (100%) rename {io/tools/ply => tools}/plyheader.cpp (100%) diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index 9c7067332d6..12d69ed5ccf 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -172,9 +172,13 @@ set(kissfft_srcs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${kissfft_srcs} ${incs} ${common_incs} ${impl_incs} ${tools_incs} ${kissfft_incs} ${common_incs_impl} ${range_image_incs} ${range_image_incs_impl}) +target_include_directories(${LIB_NAME} PUBLIC + $ + $ +) + target_link_libraries(${LIB_NAME} Boost::boost) if(MSVC AND NOT (MSVC_VERSION LESS 1915)) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index d63c3864f2d..dcba298032d 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -211,7 +211,7 @@ if(MINGW) endif() PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/ply" ${PLY_INCLUDES}) target_include_directories(pcl_io_ply PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") -target_link_libraries(pcl_io_ply Boost::boost) +target_link_libraries(pcl_io_ply pcl_common Boost::boost) set(srcs src/debayer.cpp @@ -440,7 +440,3 @@ PCL_ADD_INCLUDES("${SUBSYS_NAME}" compression ${compression_incs}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/openni_camera" ${OPENNI_INCLUDES}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/openni2" ${OPENNI2_INCLUDES}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs}) - -if(BUILD_tools) - add_subdirectory(tools) -endif() diff --git a/io/tools/CMakeLists.txt b/io/tools/CMakeLists.txt deleted file mode 100644 index 651bb00daa5..00000000000 --- a/io/tools/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -set(SUBSYS_NAME tools) - -if(WITH_OPENNI) - PCL_ADD_EXECUTABLE(pcl_openni_grabber_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_example.cpp) - target_link_libraries(pcl_openni_grabber_example pcl_common pcl_io) - - PCL_ADD_EXECUTABLE(pcl_openni_grabber_depth_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_depth_example.cpp) - target_link_libraries(pcl_openni_grabber_depth_example pcl_common pcl_io) - - - PCL_ADD_EXECUTABLE(pcl_openni_pcd_recorder COMPONENT ${SUBSYS_NAME} SOURCES openni_pcd_recorder.cpp) - target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io) -endif() - -PCL_ADD_EXECUTABLE(pcl_pcd_convert_NaN_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_convert_NaN_nan.cpp) -PCL_ADD_EXECUTABLE(pcl_pcd_introduce_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_introduce_nan.cpp) -PCL_ADD_EXECUTABLE(pcl_convert_pcd_ascii_binary COMPONENT ${SUBSYS_NAME} SOURCES convert_pcd_ascii_binary.cpp) -if(VTK_FOUND) - PCL_ADD_EXECUTABLE(pcl_converter COMPONENT ${SUBSYS_NAME} SOURCES converter.cpp) - target_link_libraries(pcl_converter pcl_common pcl_io) -endif() -PCL_ADD_EXECUTABLE(pcl_hdl_grabber COMPONENT ${SUBSYS_NAME} SOURCES hdl_grabber_example.cpp) -target_link_libraries(pcl_convert_pcd_ascii_binary pcl_common pcl_io) -target_link_libraries(pcl_hdl_grabber pcl_common pcl_io) -target_link_libraries(pcl_pcd_introduce_nan pcl_common pcl_io) - -#libply inherited tools -add_subdirectory(ply) diff --git a/io/tools/ply/CMakeLists.txt b/io/tools/ply/CMakeLists.txt deleted file mode 100644 index 16d054cda02..00000000000 --- a/io/tools/ply/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -PCL_ADD_EXECUTABLE(pcl_ply2obj COMPONENT ${SUBSYS_NAME} SOURCES ply2obj.cpp) -target_link_libraries(pcl_ply2obj pcl_io_ply) - -PCL_ADD_EXECUTABLE(pcl_ply2ply COMPONENT ${SUBSYS_NAME} SOURCES ply2ply.cpp) -target_link_libraries(pcl_ply2ply pcl_io_ply) - -PCL_ADD_EXECUTABLE(pcl_ply2raw COMPONENT ${SUBSYS_NAME} SOURCES ply2raw.cpp) -target_link_libraries(pcl_ply2raw pcl_io_ply) - -PCL_ADD_EXECUTABLE(pcl_plyheader COMPONENT ${SUBSYS_NAME} SOURCES plyheader.cpp) -target_link_libraries(pcl_plyheader pcl_io_ply) diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index 755960466f2..a4151e9c2d4 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -1,11 +1,11 @@ set(SUBSYS_NAME tools) set(SUBSYS_DESC "Useful PCL-based command line tools") -set(SUBSYS_DEPS common io filters sample_consensus segmentation search kdtree features surface octree registration recognition geometry keypoints ml) -set(SUBSYS_OPT_DEPS vtk visualization) +set(SUBSYS_DEPS io) +set(SUBSYS_OPT_DEPS filters sample_consensus segmentation search kdtree features surface octree registration recognition geometry keypoints ml visualization vtk) set(DEFAULT ON) set(REASON "") -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON}) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS}) if(NOT build) @@ -15,26 +15,7 @@ endif() # to be filled with all targets the tools subsystem set(PCL_TOOLS_ALL_TARGETS) -PCL_ADD_EXECUTABLE(pcl_sac_segmentation_plane COMPONENT ${SUBSYS_NAME} SOURCES sac_segmentation_plane.cpp) -target_link_libraries(pcl_sac_segmentation_plane pcl_common pcl_io pcl_sample_consensus pcl_segmentation) - -PCL_ADD_EXECUTABLE(pcl_plane_projection COMPONENT ${SUBSYS_NAME} SOURCES plane_projection.cpp) -target_link_libraries (pcl_plane_projection pcl_common pcl_io pcl_sample_consensus) - -PCL_ADD_EXECUTABLE(pcl_normal_estimation COMPONENT ${SUBSYS_NAME} SOURCES normal_estimation.cpp) -target_link_libraries (pcl_normal_estimation pcl_common pcl_io pcl_features pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_uniform_sampling COMPONENT ${SUBSYS_NAME} SOURCES uniform_sampling.cpp) -target_link_libraries (pcl_uniform_sampling pcl_common pcl_io pcl_filters pcl_keypoints pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_boundary_estimation COMPONENT ${SUBSYS_NAME} SOURCES boundary_estimation.cpp) -target_link_libraries (pcl_boundary_estimation pcl_common pcl_io pcl_features pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_cluster_extraction COMPONENT ${SUBSYS_NAME} SOURCES cluster_extraction.cpp) -target_link_libraries (pcl_cluster_extraction pcl_common pcl_io pcl_segmentation pcl_filters pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_fpfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES fpfh_estimation.cpp) -target_link_libraries (pcl_fpfh_estimation pcl_common pcl_io pcl_features pcl_kdtree) +PCL_ADD_EXECUTABLE(pcl_pcd_convert_NaN_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_convert_NaN_nan.cpp) PCL_ADD_EXECUTABLE(pcl_pcd2ply COMPONENT ${SUBSYS_NAME} SOURCES pcd2ply.cpp) target_link_libraries (pcl_pcd2ply pcl_common pcl_io) @@ -51,132 +32,45 @@ target_link_libraries (pcl_pclzf2pcd pcl_common pcl_io) PCL_ADD_EXECUTABLE(pcl_pcd2vtk COMPONENT ${SUBSYS_NAME} SOURCES pcd2vtk.cpp) target_link_libraries (pcl_pcd2vtk pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_vfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES vfh_estimation.cpp) -target_link_libraries (pcl_vfh_estimation pcl_common pcl_io pcl_features pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_spin_estimation COMPONENT ${SUBSYS_NAME} SOURCES spin_estimation.cpp) -target_link_libraries (pcl_spin_estimation pcl_common pcl_io pcl_features pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_voxel_grid COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid.cpp) -target_link_libraries (pcl_voxel_grid pcl_common pcl_io pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_passthrough_filter COMPONENT ${SUBSYS_NAME} SOURCES passthrough_filter.cpp) -target_link_libraries (pcl_passthrough_filter pcl_common pcl_io pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_radius_filter COMPONENT ${SUBSYS_NAME} SOURCES radius_filter.cpp) -target_link_libraries (pcl_radius_filter pcl_common pcl_io pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_extract_feature COMPONENT ${SUBSYS_NAME} SOURCES extract_feature.cpp) -target_link_libraries (pcl_extract_feature pcl_common pcl_io pcl_features pcl_kdtree) - -PCL_ADD_EXECUTABLE(pcl_compute_cloud_error COMPONENT ${SUBSYS_NAME} SOURCES compute_cloud_error.cpp) -target_link_libraries (pcl_compute_cloud_error pcl_common pcl_io pcl_kdtree pcl_search) - -PCL_ADD_EXECUTABLE(pcl_train_unary_classifier COMPONENT ${SUBSYS_NAME} SOURCES train_unary_classifier.cpp) -target_link_libraries (pcl_train_unary_classifier pcl_common pcl_io pcl_segmentation) - -PCL_ADD_EXECUTABLE(pcl_unary_classifier_segment COMPONENT ${SUBSYS_NAME} SOURCES unary_classifier_segment.cpp) -target_link_libraries (pcl_unary_classifier_segment pcl_common pcl_io pcl_segmentation) - -PCL_ADD_EXECUTABLE(pcl_crf_segmentation COMPONENT ${SUBSYS_NAME} SOURCES crf_segmentation.cpp) -target_link_libraries (pcl_crf_segmentation pcl_common pcl_io pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_add_gaussian_noise COMPONENT ${SUBSYS_NAME} SOURCES add_gaussian_noise.cpp) target_link_libraries (pcl_add_gaussian_noise pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_outlier_removal COMPONENT ${SUBSYS_NAME} SOURCES outlier_removal.cpp) -target_link_libraries (pcl_outlier_removal pcl_common pcl_io pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_mls_smoothing COMPONENT ${SUBSYS_NAME} SOURCES mls_smoothing.cpp) -target_link_libraries (pcl_mls_smoothing pcl_common pcl_io pcl_surface pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_marching_cubes_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES marching_cubes_reconstruction.cpp) -target_link_libraries (pcl_marching_cubes_reconstruction pcl_common pcl_io pcl_surface) - -PCL_ADD_EXECUTABLE(pcl_gp3_surface COMPONENT ${SUBSYS_NAME} SOURCES gp3_surface.cpp) -target_link_libraries (pcl_gp3_surface pcl_common pcl_io pcl_surface) - -PCL_ADD_EXECUTABLE(pcl_icp COMPONENT ${SUBSYS_NAME} SOURCES icp.cpp) -target_link_libraries(pcl_icp pcl_common pcl_io pcl_registration) - -PCL_ADD_EXECUTABLE(pcl_icp2d COMPONENT ${SUBSYS_NAME} SOURCES icp2d.cpp) -target_link_libraries(pcl_icp2d pcl_common pcl_io pcl_registration) - -PCL_ADD_EXECUTABLE(pcl_elch COMPONENT ${SUBSYS_NAME} SOURCES elch.cpp) -target_link_libraries(pcl_elch pcl_common pcl_io pcl_registration) - -PCL_ADD_EXECUTABLE(pcl_lum COMPONENT ${SUBSYS_NAME} SOURCES lum.cpp) -target_link_libraries(pcl_lum pcl_common pcl_io pcl_registration) - -PCL_ADD_EXECUTABLE(pcl_ndt2d COMPONENT ${SUBSYS_NAME} SOURCES ndt2d.cpp) -target_link_libraries(pcl_ndt2d pcl_common pcl_io pcl_registration) - -PCL_ADD_EXECUTABLE(pcl_ndt3d COMPONENT ${SUBSYS_NAME} SOURCES ndt3d.cpp) -target_link_libraries(pcl_ndt3d pcl_common pcl_io pcl_registration) - PCL_ADD_EXECUTABLE(pcl_pcd_change_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES pcd_change_viewpoint.cpp) target_link_libraries(pcl_pcd_change_viewpoint pcl_common pcl_io) PCL_ADD_EXECUTABLE(pcl_concatenate_points_pcd COMPONENT ${SUBSYS_NAME} SOURCES concatenate_points_pcd.cpp) target_link_libraries(pcl_concatenate_points_pcd pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_poisson_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES poisson_reconstruction.cpp) -target_link_libraries(pcl_poisson_reconstruction pcl_common pcl_io pcl_surface) - -PCL_ADD_EXECUTABLE(pcl_train_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES train_linemod_template.cpp) -target_link_libraries(pcl_train_linemod_template pcl_common pcl_io pcl_segmentation pcl_recognition) - -PCL_ADD_EXECUTABLE(pcl_match_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES match_linemod_template.cpp) -target_link_libraries(pcl_match_linemod_template pcl_common pcl_io pcl_recognition) - -PCL_ADD_EXECUTABLE(pcl_linemod_detection COMPONENT ${SUBSYS_NAME} SOURCES linemod_detection.cpp) -target_link_libraries(pcl_linemod_detection pcl_common pcl_io pcl_recognition) - -PCL_ADD_EXECUTABLE(pcl_fast_bilateral_filter COMPONENT ${SUBSYS_NAME} SOURCES fast_bilateral_filter.cpp) -target_link_libraries(pcl_fast_bilateral_filter pcl_common pcl_io pcl_filters) - PCL_ADD_EXECUTABLE(pcl_demean_cloud COMPONENT ${SUBSYS_NAME} SOURCES demean_cloud.cpp) target_link_libraries(pcl_demean_cloud pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_compute_hausdorff COMPONENT ${SUBSYS_NAME} SOURCES compute_hausdorff.cpp) -target_link_libraries(pcl_compute_hausdorff pcl_common pcl_io pcl_search) - -PCL_ADD_EXECUTABLE(pcl_morph COMPONENT ${SUBSYS_NAME} SOURCES morph.cpp) -target_link_libraries(pcl_morph pcl_common pcl_io pcl_filters) - -PCL_ADD_EXECUTABLE(pcl_progressive_morphological_filter COMPONENT ${SUBSYS_NAME} SOURCES progressive_morphological_filter.cpp) -target_link_libraries(pcl_progressive_morphological_filter pcl_common pcl_io pcl_filters pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_generate COMPONENT ${SUBSYS_NAME} SOURCES generate.cpp) target_link_libraries(pcl_generate pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_local_max COMPONENT ${SUBSYS_NAME} SOURCES local_max.cpp) -target_link_libraries(pcl_local_max pcl_common pcl_io pcl_filters) +PCL_ADD_EXECUTABLE(pcl_convert_pcd_ascii_binary COMPONENT ${SUBSYS_NAME} SOURCES convert_pcd_ascii_binary.cpp) +target_link_libraries(pcl_convert_pcd_ascii_binary pcl_common pcl_io) + +PCL_ADD_EXECUTABLE(pcl_pcd_introduce_nan COMPONENT ${SUBSYS_NAME} SOURCES pcd_introduce_nan.cpp) +target_link_libraries(pcl_pcd_introduce_nan pcl_common pcl_io) -PCL_ADD_EXECUTABLE(pcl_grid_min COMPONENT ${SUBSYS_NAME} SOURCES grid_min.cpp) -target_link_libraries(pcl_grid_min pcl_common pcl_io pcl_filters) +PCL_ADD_EXECUTABLE(pcl_hdl_grabber COMPONENT ${SUBSYS_NAME} SOURCES hdl_grabber_example.cpp) +target_link_libraries(pcl_hdl_grabber pcl_common pcl_io) if(WITH_OPENNI) PCL_ADD_EXECUTABLE(pcl_oni2pcd COMPONENT ${SUBSYS_NAME} SOURCES oni2pcd.cpp) target_link_libraries(pcl_oni2pcd pcl_common pcl_io) -endif() + + PCL_ADD_EXECUTABLE(pcl_openni_grabber_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_example.cpp) + target_link_libraries(pcl_openni_grabber_example pcl_common pcl_io) -if(QHULL_FOUND) - PCL_ADD_EXECUTABLE(pcl_crop_to_hull COMPONENT ${SUBSYS_NAME} SOURCES crop_to_hull.cpp) - target_link_libraries(pcl_crop_to_hull pcl_common pcl_io pcl_filters pcl_surface) + PCL_ADD_EXECUTABLE(pcl_openni_grabber_depth_example COMPONENT ${SUBSYS_NAME} SOURCES openni_grabber_depth_example.cpp) + target_link_libraries(pcl_openni_grabber_depth_example pcl_common pcl_io) - PCL_ADD_EXECUTABLE(pcl_compute_hull COMPONENT ${SUBSYS_NAME} SOURCES compute_hull.cpp) - target_link_libraries(pcl_compute_hull pcl_common pcl_io pcl_surface) + PCL_ADD_EXECUTABLE(pcl_openni_pcd_recorder COMPONENT ${SUBSYS_NAME} SOURCES openni_pcd_recorder.cpp) + target_link_libraries(pcl_openni_pcd_recorder pcl_common pcl_io) endif() -if(NOT VTK_FOUND) - set(DEFAULT FALSE) - set(REASON "VTK was not found.") -else() - set(DEFAULT TRUE) - set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - +if(VTK_FOUND) PCL_ADD_EXECUTABLE(pcl_png2pcd COMPONENT ${SUBSYS_NAME} SOURCES png2pcd.cpp) target_link_libraries(pcl_png2pcd pcl_common pcl_io) @@ -219,119 +113,292 @@ else() target_link_libraries(pcl_vtk2pcd vtkFiltersCore) endif() - if(BUILD_visualization) - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_model_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_model_opps.cpp) - target_link_libraries(pcl_obj_rec_ransac_model_opps pcl_common pcl_visualization pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_converter COMPONENT ${SUBSYS_NAME} SOURCES converter.cpp) + target_link_libraries(pcl_converter pcl_common pcl_io) +endif() - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_hash_table COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_hash_table.cpp) - target_link_libraries(pcl_obj_rec_ransac_hash_table pcl_common pcl_visualization pcl_io pcl_recognition) +if(TARGET pcl_io_ply) + PCL_ADD_EXECUTABLE(pcl_ply2obj COMPONENT ${SUBSYS_NAME} SOURCES ply2obj.cpp) + target_link_libraries(pcl_ply2obj pcl_io_ply) - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_scene_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_scene_opps.cpp) - target_link_libraries(pcl_obj_rec_ransac_scene_opps pcl_common pcl_visualization pcl_io pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_ply2ply COMPONENT ${SUBSYS_NAME} SOURCES ply2ply.cpp) + target_link_libraries(pcl_ply2ply pcl_io_ply) - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_accepted_hypotheses COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_accepted_hypotheses.cpp) - target_link_libraries(pcl_obj_rec_ransac_accepted_hypotheses pcl_common pcl_visualization pcl_io pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_ply2raw COMPONENT ${SUBSYS_NAME} SOURCES ply2raw.cpp) + target_link_libraries(pcl_ply2raw pcl_io_ply) - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree.cpp) - target_link_libraries(pcl_obj_rec_ransac_orr_octree pcl_common pcl_visualization pcl_io pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_plyheader COMPONENT ${SUBSYS_NAME} SOURCES plyheader.cpp) + target_link_libraries(pcl_plyheader pcl_io_ply) +endif() - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree_zprojection COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree_zprojection.cpp) - target_link_libraries(pcl_obj_rec_ransac_orr_octree_zprojection pcl_common pcl_visualization pcl_io pcl_recognition) +if(TARGET pcl_sample_consensus) + PCL_ADD_EXECUTABLE(pcl_plane_projection COMPONENT ${SUBSYS_NAME} SOURCES plane_projection.cpp) + target_link_libraries (pcl_plane_projection pcl_common pcl_io pcl_sample_consensus) +endif() + +if(TARGET pcl_search) + PCL_ADD_EXECUTABLE(pcl_compute_hausdorff COMPONENT ${SUBSYS_NAME} SOURCES compute_hausdorff.cpp) + target_link_libraries(pcl_compute_hausdorff pcl_common pcl_io pcl_search) + + PCL_ADD_EXECUTABLE(pcl_compute_cloud_error COMPONENT ${SUBSYS_NAME} SOURCES compute_cloud_error.cpp) + target_link_libraries (pcl_compute_cloud_error pcl_common pcl_io pcl_kdtree pcl_search) - PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_result COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_result.cpp) - target_link_libraries(pcl_obj_rec_ransac_result pcl_common pcl_visualization pcl_io pcl_segmentation pcl_recognition) + if(TARGET pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_viewer.cpp BUNDLE) + target_link_libraries(pcl_viewer pcl_common pcl_io pcl_kdtree pcl_search pcl_visualization ) + endif() +endif() + +if(TARGET pcl_filters) + PCL_ADD_EXECUTABLE(pcl_voxel_grid COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid.cpp) + target_link_libraries (pcl_voxel_grid pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_passthrough_filter COMPONENT ${SUBSYS_NAME} SOURCES passthrough_filter.cpp) + target_link_libraries (pcl_passthrough_filter pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_radius_filter COMPONENT ${SUBSYS_NAME} SOURCES radius_filter.cpp) + target_link_libraries (pcl_radius_filter pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_outlier_removal COMPONENT ${SUBSYS_NAME} SOURCES outlier_removal.cpp) + target_link_libraries (pcl_outlier_removal pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_fast_bilateral_filter COMPONENT ${SUBSYS_NAME} SOURCES fast_bilateral_filter.cpp) + target_link_libraries(pcl_fast_bilateral_filter pcl_common pcl_io pcl_filters) - PCL_ADD_EXECUTABLE(pcl_registration_visualizer COMPONENT ${SUBSYS_NAME} SOURCES registration_visualizer.cpp) - target_link_libraries(pcl_registration_visualizer pcl_common pcl_io pcl_kdtree pcl_filters pcl_registration pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_morph COMPONENT ${SUBSYS_NAME} SOURCES morph.cpp) + target_link_libraries(pcl_morph pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_local_max COMPONENT ${SUBSYS_NAME} SOURCES local_max.cpp) + target_link_libraries(pcl_local_max pcl_common pcl_io pcl_filters) + + PCL_ADD_EXECUTABLE(pcl_grid_min COMPONENT ${SUBSYS_NAME} SOURCES grid_min.cpp) + target_link_libraries(pcl_grid_min pcl_common pcl_io pcl_filters) + + if(TARGET pcl_segmentation) + PCL_ADD_EXECUTABLE(pcl_cluster_extraction COMPONENT ${SUBSYS_NAME} SOURCES cluster_extraction.cpp) + target_link_libraries (pcl_cluster_extraction pcl_common pcl_io pcl_kdtree pcl_filters pcl_segmentation) + + PCL_ADD_EXECUTABLE(pcl_progressive_morphological_filter COMPONENT ${SUBSYS_NAME} SOURCES progressive_morphological_filter.cpp) + target_link_libraries(pcl_progressive_morphological_filter pcl_common pcl_io pcl_filters pcl_segmentation) + endif() + + if(TARGET pcl_surface) + PCL_ADD_EXECUTABLE(pcl_mls_smoothing COMPONENT ${SUBSYS_NAME} SOURCES mls_smoothing.cpp) + target_link_libraries (pcl_mls_smoothing pcl_common pcl_io pcl_surface pcl_filters) + + endif() + if(TARGET pcl_keypoints) + PCL_ADD_EXECUTABLE(pcl_uniform_sampling COMPONENT ${SUBSYS_NAME} SOURCES uniform_sampling.cpp) + target_link_libraries (pcl_uniform_sampling pcl_common pcl_io pcl_kdtree pcl_filters pcl_keypoints) + endif() + + if(TARGET pcl_registration) + if(TARGET pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_registration_visualizer COMPONENT ${SUBSYS_NAME} SOURCES registration_visualizer.cpp) + target_link_libraries(pcl_registration_visualizer pcl_common pcl_io pcl_kdtree pcl_filters pcl_registration pcl_visualization) + endif() + endif() + + if(TARGET pcl_visualization) PCL_ADD_EXECUTABLE(pcl_octree_viewer COMPONENT ${SUBSYS_NAME} SOURCES octree_viewer.cpp) - target_link_libraries(pcl_octree_viewer pcl_common pcl_io pcl_octree pcl_visualization pcl_kdtree pcl_filters) + target_link_libraries(pcl_octree_viewer pcl_common pcl_io pcl_octree pcl_kdtree pcl_filters pcl_visualization) PCL_ADD_EXECUTABLE(pcl_mesh2pcd COMPONENT ${SUBSYS_NAME} SOURCES mesh2pcd.cpp) - target_link_libraries(pcl_mesh2pcd pcl_common pcl_io pcl_visualization pcl_filters) + target_link_libraries(pcl_mesh2pcd pcl_common pcl_io pcl_filters pcl_visualization) PCL_ADD_EXECUTABLE(pcl_mesh_sampling COMPONENT ${SUBSYS_NAME} SOURCES mesh_sampling.cpp) - target_link_libraries(pcl_mesh_sampling pcl_common pcl_io pcl_visualization pcl_filters) + target_link_libraries(pcl_mesh_sampling pcl_common pcl_io pcl_filters pcl_visualization) PCL_ADD_EXECUTABLE(pcl_virtual_scanner COMPONENT ${SUBSYS_NAME} SOURCES virtual_scanner.cpp) target_link_libraries(pcl_virtual_scanner pcl_common pcl_io pcl_filters pcl_visualization) PCL_ADD_EXECUTABLE(pcl_voxel_grid_occlusion_estimation COMPONENT ${SUBSYS_NAME} SOURCES voxel_grid_occlusion_estimation.cpp) target_link_libraries (pcl_voxel_grid_occlusion_estimation pcl_common pcl_io pcl_filters pcl_visualization) + endif() +endif() - PCL_ADD_EXECUTABLE(pcl_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_viewer.cpp BUNDLE) - target_link_libraries(pcl_viewer pcl_common pcl_io pcl_kdtree pcl_visualization pcl_search) +if(TARGET pcl_segmentation) + PCL_ADD_EXECUTABLE(pcl_sac_segmentation_plane COMPONENT ${SUBSYS_NAME} SOURCES sac_segmentation_plane.cpp) + target_link_libraries(pcl_sac_segmentation_plane pcl_common pcl_io pcl_sample_consensus pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_pcd_image_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_viewer.cpp BUNDLE) - target_link_libraries(pcl_pcd_image_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_train_unary_classifier COMPONENT ${SUBSYS_NAME} SOURCES train_unary_classifier.cpp) + target_link_libraries (pcl_train_unary_classifier pcl_common pcl_io pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_timed_trigger_test COMPONENT ${SUBSYS_NAME} SOURCES timed_trigger_test.cpp) - target_link_libraries(pcl_timed_trigger_test pcl_io pcl_common pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_unary_classifier_segment COMPONENT ${SUBSYS_NAME} SOURCES unary_classifier_segment.cpp) + target_link_libraries (pcl_unary_classifier_segment pcl_common pcl_io pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_hdl_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES hdl_viewer_simple.cpp) - target_link_libraries(pcl_hdl_viewer_simple pcl_io pcl_common pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_crf_segmentation COMPONENT ${SUBSYS_NAME} SOURCES crf_segmentation.cpp) + target_link_libraries (pcl_crf_segmentation pcl_common pcl_io pcl_segmentation) - PCL_ADD_EXECUTABLE(pcl_vlp_viewer COMPONENT ${SUBSYS_NAME} SOURCES vlp_viewer.cpp) - target_link_libraries(pcl_vlp_viewer pcl_io pcl_common pcl_visualization) + if(TARGET pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_train_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES train_linemod_template.cpp) + target_link_libraries(pcl_train_linemod_template pcl_common pcl_io pcl_segmentation pcl_recognition) - if(WITH_OPENNI) - PCL_ADD_EXECUTABLE(pcl_openni_save_image COMPONENT ${SUBSYS_NAME} SOURCES openni_save_image.cpp) - target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization) + if(TARGET pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_result COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_result.cpp) + target_link_libraries(pcl_obj_rec_ransac_result pcl_common pcl_io pcl_segmentation pcl_recognition pcl_visualization) + endif() + endif() +endif() - PCL_ADD_EXECUTABLE(pcl_pcd_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_grabber_viewer.cpp BUNDLE) - target_link_libraries(pcl_pcd_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) +if(TARGET pcl_features) + PCL_ADD_EXECUTABLE(pcl_normal_estimation COMPONENT ${SUBSYS_NAME} SOURCES normal_estimation.cpp) + target_link_libraries (pcl_normal_estimation pcl_common pcl_io pcl_kdtree pcl_features) - PCL_ADD_EXECUTABLE(pcl_image_grabber_saver COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_saver.cpp BUNDLE) - target_link_libraries(pcl_image_grabber_saver pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_boundary_estimation COMPONENT ${SUBSYS_NAME} SOURCES boundary_estimation.cpp) + target_link_libraries (pcl_boundary_estimation pcl_common pcl_io pcl_kdtree pcl_features) - PCL_ADD_EXECUTABLE(pcl_image_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_viewer.cpp BUNDLE) - target_link_libraries(pcl_image_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_fpfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES fpfh_estimation.cpp) + target_link_libraries (pcl_fpfh_estimation pcl_common pcl_io pcl_kdtree pcl_features) - #PCL_ADD_EXECUTABLE(pcl_openni_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer_simple.cpp) - #target_link_libraries(pcl_openni_viewer_simple pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_vfh_estimation COMPONENT ${SUBSYS_NAME} SOURCES vfh_estimation.cpp) + target_link_libraries (pcl_vfh_estimation pcl_common pcl_io pcl_kdtree pcl_features) - PCL_ADD_EXECUTABLE(pcl_oni_viewer COMPONENT ${SUBSYS_NAME} SOURCES oni_viewer_simple.cpp BUNDLE) - target_link_libraries(pcl_oni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_spin_estimation COMPONENT ${SUBSYS_NAME} SOURCES spin_estimation.cpp) + target_link_libraries (pcl_spin_estimation pcl_common pcl_io pcl_kdtree pcl_features) - PCL_ADD_EXECUTABLE(pcl_openni_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer.cpp BUNDLE) - target_link_libraries(pcl_openni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_extract_feature COMPONENT ${SUBSYS_NAME} SOURCES extract_feature.cpp) + target_link_libraries (pcl_extract_feature pcl_common pcl_io pcl_kdtree pcl_features) +endif() - PCL_ADD_EXECUTABLE(pcl_openni_image COMPONENT ${SUBSYS_NAME} SOURCES openni_image.cpp BUNDLE) - target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization) - endif() +if(TARGET pcl_surface) + PCL_ADD_EXECUTABLE(pcl_marching_cubes_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES marching_cubes_reconstruction.cpp) + target_link_libraries (pcl_marching_cubes_reconstruction pcl_common pcl_io pcl_surface) - if(WITH_OPENNI2) - PCL_ADD_EXECUTABLE(pcl_openni2_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni2_viewer.cpp BUNDLE) - target_link_libraries(pcl_openni2_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) - endif() + PCL_ADD_EXECUTABLE(pcl_gp3_surface COMPONENT ${SUBSYS_NAME} SOURCES gp3_surface.cpp) + target_link_libraries (pcl_gp3_surface pcl_common pcl_io pcl_surface) - if(WITH_ENSENSO) - PCL_ADD_EXECUTABLE(pcl_ensenso_viewer COMPONENT ${SUBSYS_NAME} SOURCES ensenso_viewer.cpp BUNDLE) - target_link_libraries(pcl_ensenso_viewer pcl_common pcl_io pcl_visualization) - endif() + PCL_ADD_EXECUTABLE(pcl_poisson_reconstruction COMPONENT ${SUBSYS_NAME} SOURCES poisson_reconstruction.cpp) + target_link_libraries(pcl_poisson_reconstruction pcl_common pcl_io pcl_surface) - if(WITH_DAVIDSDK) - PCL_ADD_EXECUTABLE(pcl_davidsdk_viewer COMPONENT ${SUBSYS_NAME} SOURCES davidsdk_viewer.cpp BUNDLE) - target_link_libraries(pcl_davidsdk_viewer pcl_common pcl_io pcl_visualization) - endif() + if(QHULL_FOUND) + PCL_ADD_EXECUTABLE(pcl_crop_to_hull COMPONENT ${SUBSYS_NAME} SOURCES crop_to_hull.cpp) + target_link_libraries(pcl_crop_to_hull pcl_common pcl_io pcl_filters pcl_surface) - if(WITH_DSSDK) - PCL_ADD_EXECUTABLE(pcl_depth_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES depth_sense_viewer.cpp BUNDLE) - target_link_libraries(pcl_depth_sense_viewer pcl_common pcl_io pcl_visualization) - endif() + PCL_ADD_EXECUTABLE(pcl_compute_hull COMPONENT ${SUBSYS_NAME} SOURCES compute_hull.cpp) + target_link_libraries(pcl_compute_hull pcl_common pcl_io pcl_surface) + endif() +endif() - if(WITH_RSSDK) - PCL_ADD_EXECUTABLE(pcl_real_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES real_sense_viewer.cpp BUNDLE) - target_link_libraries(pcl_real_sense_viewer pcl_common pcl_io pcl_visualization) - endif() +if(TARGET pcl_registration) + PCL_ADD_EXECUTABLE(pcl_icp COMPONENT ${SUBSYS_NAME} SOURCES icp.cpp) + target_link_libraries(pcl_icp pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_icp2d COMPONENT ${SUBSYS_NAME} SOURCES icp2d.cpp) + target_link_libraries(pcl_icp2d pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_elch COMPONENT ${SUBSYS_NAME} SOURCES elch.cpp) + target_link_libraries(pcl_elch pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_lum COMPONENT ${SUBSYS_NAME} SOURCES lum.cpp) + target_link_libraries(pcl_lum pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_ndt2d COMPONENT ${SUBSYS_NAME} SOURCES ndt2d.cpp) + target_link_libraries(pcl_ndt2d pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_ndt3d COMPONENT ${SUBSYS_NAME} SOURCES ndt3d.cpp) + target_link_libraries(pcl_ndt3d pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_transform_point_cloud COMPONENT ${SUBSYS_NAME} SOURCES transform_point_cloud.cpp) + target_link_libraries (pcl_transform_point_cloud pcl_common pcl_io pcl_registration) + + PCL_ADD_EXECUTABLE(pcl_transform_from_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES transform_from_viewpoint.cpp) + target_link_libraries (pcl_transform_from_viewpoint pcl_common pcl_io pcl_registration) +endif() + +if(TARGET pcl_recognition) + PCL_ADD_EXECUTABLE(pcl_match_linemod_template COMPONENT ${SUBSYS_NAME} SOURCES match_linemod_template.cpp) + target_link_libraries(pcl_match_linemod_template pcl_common pcl_io pcl_recognition) + + PCL_ADD_EXECUTABLE(pcl_linemod_detection COMPONENT ${SUBSYS_NAME} SOURCES linemod_detection.cpp) + target_link_libraries(pcl_linemod_detection pcl_common pcl_io pcl_recognition) + + if(TARGET pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_model_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_model_opps.cpp) + target_link_libraries(pcl_obj_rec_ransac_model_opps pcl_common pcl_recognition pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_hash_table COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_hash_table.cpp) + target_link_libraries(pcl_obj_rec_ransac_hash_table pcl_common pcl_io pcl_recognition pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_scene_opps COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_scene_opps.cpp) + target_link_libraries(pcl_obj_rec_ransac_scene_opps pcl_common pcl_io pcl_recognition pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_accepted_hypotheses COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_accepted_hypotheses.cpp) + target_link_libraries(pcl_obj_rec_ransac_accepted_hypotheses pcl_common pcl_io pcl_recognition pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree.cpp) + target_link_libraries(pcl_obj_rec_ransac_orr_octree pcl_common pcl_io pcl_recognition pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_obj_rec_ransac_orr_octree_zprojection COMPONENT ${SUBSYS_NAME} SOURCES obj_rec_ransac_orr_octree_zprojection.cpp) + target_link_libraries(pcl_obj_rec_ransac_orr_octree_zprojection pcl_common pcl_io pcl_recognition pcl_visualization) endif() endif() -PCL_ADD_EXECUTABLE(pcl_transform_point_cloud COMPONENT ${SUBSYS_NAME} SOURCES transform_point_cloud.cpp) -target_link_libraries (pcl_transform_point_cloud pcl_common pcl_io pcl_registration) +if(TARGET pcl_visualization) + PCL_ADD_EXECUTABLE(pcl_pcd_image_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_viewer.cpp BUNDLE) + target_link_libraries(pcl_pcd_image_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_timed_trigger_test COMPONENT ${SUBSYS_NAME} SOURCES timed_trigger_test.cpp) + target_link_libraries(pcl_timed_trigger_test pcl_io pcl_common pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_hdl_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES hdl_viewer_simple.cpp) + target_link_libraries(pcl_hdl_viewer_simple pcl_io pcl_common pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_vlp_viewer COMPONENT ${SUBSYS_NAME} SOURCES vlp_viewer.cpp) + target_link_libraries(pcl_vlp_viewer pcl_io pcl_common pcl_visualization) + + if(WITH_OPENNI) + PCL_ADD_EXECUTABLE(pcl_openni_save_image COMPONENT ${SUBSYS_NAME} SOURCES openni_save_image.cpp) + target_link_libraries(pcl_openni_save_image pcl_common pcl_io pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_pcd_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES pcd_grabber_viewer.cpp BUNDLE) + target_link_libraries(pcl_pcd_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_image_grabber_saver COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_saver.cpp BUNDLE) + target_link_libraries(pcl_image_grabber_saver pcl_common pcl_io pcl_kdtree pcl_visualization) -PCL_ADD_EXECUTABLE(pcl_transform_from_viewpoint COMPONENT ${SUBSYS_NAME} SOURCES transform_from_viewpoint.cpp) -target_link_libraries (pcl_transform_from_viewpoint pcl_common pcl_io pcl_registration) + PCL_ADD_EXECUTABLE(pcl_image_grabber_viewer COMPONENT ${SUBSYS_NAME} SOURCES image_grabber_viewer.cpp BUNDLE) + target_link_libraries(pcl_image_grabber_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_openni_viewer_simple COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer_simple.cpp) + target_link_libraries(pcl_openni_viewer_simple pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_oni_viewer COMPONENT ${SUBSYS_NAME} SOURCES oni_viewer_simple.cpp BUNDLE) + target_link_libraries(pcl_oni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_openni_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni_viewer.cpp BUNDLE) + target_link_libraries(pcl_openni_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + + PCL_ADD_EXECUTABLE(pcl_openni_image COMPONENT ${SUBSYS_NAME} SOURCES openni_image.cpp BUNDLE) + target_link_libraries(pcl_openni_image pcl_common pcl_io pcl_kdtree pcl_visualization) + endif() + + if(WITH_OPENNI2) + PCL_ADD_EXECUTABLE(pcl_openni2_viewer COMPONENT ${SUBSYS_NAME} SOURCES openni2_viewer.cpp BUNDLE) + target_link_libraries(pcl_openni2_viewer pcl_common pcl_io pcl_kdtree pcl_visualization) + endif() + + if(WITH_ENSENSO) + PCL_ADD_EXECUTABLE(pcl_ensenso_viewer COMPONENT ${SUBSYS_NAME} SOURCES ensenso_viewer.cpp BUNDLE) + target_link_libraries(pcl_ensenso_viewer pcl_common pcl_io pcl_visualization) + endif() + + if(WITH_DAVIDSDK) + PCL_ADD_EXECUTABLE(pcl_davidsdk_viewer COMPONENT ${SUBSYS_NAME} SOURCES davidsdk_viewer.cpp BUNDLE) + target_link_libraries(pcl_davidsdk_viewer pcl_common pcl_io pcl_visualization) + endif() + + if(WITH_DSSDK) + PCL_ADD_EXECUTABLE(pcl_depth_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES depth_sense_viewer.cpp BUNDLE) + target_link_libraries(pcl_depth_sense_viewer pcl_common pcl_io pcl_visualization) + endif() + + if(WITH_RSSDK) + PCL_ADD_EXECUTABLE(pcl_real_sense_viewer COMPONENT ${SUBSYS_NAME} SOURCES real_sense_viewer.cpp BUNDLE) + target_link_libraries(pcl_real_sense_viewer pcl_common pcl_io pcl_visualization) + endif() +endif() if(CMAKE_GENERATOR_IS_IDE) set(SUBSYS_TARGET_NAME TOOLS_BUILD) diff --git a/io/tools/convert_pcd_ascii_binary.cpp b/tools/convert_pcd_ascii_binary.cpp similarity index 100% rename from io/tools/convert_pcd_ascii_binary.cpp rename to tools/convert_pcd_ascii_binary.cpp diff --git a/io/tools/converter.cpp b/tools/converter.cpp similarity index 100% rename from io/tools/converter.cpp rename to tools/converter.cpp diff --git a/io/tools/hdl_grabber_example.cpp b/tools/hdl_grabber_example.cpp similarity index 100% rename from io/tools/hdl_grabber_example.cpp rename to tools/hdl_grabber_example.cpp diff --git a/io/tools/openni_grabber_depth_example.cpp b/tools/openni_grabber_depth_example.cpp similarity index 100% rename from io/tools/openni_grabber_depth_example.cpp rename to tools/openni_grabber_depth_example.cpp diff --git a/io/tools/openni_grabber_example.cpp b/tools/openni_grabber_example.cpp similarity index 100% rename from io/tools/openni_grabber_example.cpp rename to tools/openni_grabber_example.cpp diff --git a/io/tools/openni_pcd_recorder.cpp b/tools/openni_pcd_recorder.cpp similarity index 100% rename from io/tools/openni_pcd_recorder.cpp rename to tools/openni_pcd_recorder.cpp diff --git a/tools/openni_viewer_simple.cpp b/tools/openni_viewer_simple.cpp index db5dea2e3dc..90190279d29 100644 --- a/tools/openni_viewer_simple.cpp +++ b/tools/openni_viewer_simple.cpp @@ -121,10 +121,10 @@ class SimpleOpenNIViewer void keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie) { - string* message = (string*)cookie; + auto message = static_cast(cookie); std::cout << (*message) << " :: "; if (event.getKeyCode()) - std::cout << "the key \'" << event.getKeyCode() << "\' (" << (int)event.getKeyCode() << ") was"; + std::cout << "the key \'" << event.getKeyCode() << "\' (" << static_cast(event.getKeyCode()) << ") was"; else std::cout << "the special key \'" << event.getKeySym() << "\' was"; if (event.keyDown()) @@ -135,7 +135,7 @@ class SimpleOpenNIViewer void mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie) { - string* message = (string*) cookie; + auto message = static_cast(cookie); if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton) { std::cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << std::endl; @@ -167,8 +167,10 @@ class SimpleOpenNIViewer std::string mouseMsg3D("Mouse coordinates in PCL Visualizer"); std::string keyMsg3D("Key event for PCL Visualizer"); - cloud_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg3D)); - cloud_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg3D)); + cloud_viewer_.registerMouseCallback( + &SimpleOpenNIViewer::mouse_callback, *this, static_cast(&mouseMsg3D)); + cloud_viewer_.registerKeyboardCallback( + &SimpleOpenNIViewer::keyboard_callback, *this, static_cast(&keyMsg3D)); std::function cloud_cb = [this] (const CloudConstPtr& cloud) { cloud_callback (cloud); }; boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb); @@ -177,12 +179,16 @@ class SimpleOpenNIViewer { std::string mouseMsg2D("Mouse coordinates in image viewer"); std::string keyMsg2D("Key event for image viewer"); - image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg2D)); - image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg2D)); + image_viewer_.registerMouseCallback(&SimpleOpenNIViewer::mouse_callback, + *this, + static_cast(&mouseMsg2D)); + image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, + *this, + static_cast(&keyMsg2D)); std::function image_cb = [this] (const openni_wrapper::Image::Ptr& img) { image_callback (img); }; image_connection = grabber_.registerCallback (image_cb); } - unsigned char* rgb_data = 0; + unsigned char* rgb_data = nullptr; unsigned rgb_data_size = 0; grabber_.start (); @@ -271,7 +277,7 @@ usage(char ** argv) int main(int argc, char ** argv) { - std::string device_id(""); + std::string device_id; pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode; pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode; bool xyz = false; @@ -315,7 +321,7 @@ main(int argc, char ** argv) for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) { std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName(deviceIdx) << ", product: " << driver.getProductName(deviceIdx) - << ", connected: " << (int) driver.getBus(deviceIdx) << " @ " << (int) driver.getAddress(deviceIdx) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << std::endl; + << ", connected: " << static_cast(driver.getBus(deviceIdx)) << " @ " << static_cast(driver.getAddress(deviceIdx)) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << std::endl; } } @@ -336,10 +342,10 @@ main(int argc, char ** argv) unsigned mode; if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1) - depth_mode = (pcl::OpenNIGrabber::Mode) mode; + depth_mode = static_cast(mode); if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1) - image_mode = (pcl::OpenNIGrabber::Mode) mode; + image_mode = static_cast(mode); if (pcl::console::find_argument(argc, argv, "-xyz") != -1) xyz = true; diff --git a/io/tools/pcd_convert_NaN_nan.cpp b/tools/pcd_convert_NaN_nan.cpp similarity index 100% rename from io/tools/pcd_convert_NaN_nan.cpp rename to tools/pcd_convert_NaN_nan.cpp diff --git a/io/tools/pcd_introduce_nan.cpp b/tools/pcd_introduce_nan.cpp similarity index 100% rename from io/tools/pcd_introduce_nan.cpp rename to tools/pcd_introduce_nan.cpp diff --git a/io/tools/ply/ply2obj.cpp b/tools/ply2obj.cpp similarity index 100% rename from io/tools/ply/ply2obj.cpp rename to tools/ply2obj.cpp diff --git a/io/tools/ply/ply2ply.cpp b/tools/ply2ply.cpp similarity index 100% rename from io/tools/ply/ply2ply.cpp rename to tools/ply2ply.cpp diff --git a/io/tools/ply/ply2raw.cpp b/tools/ply2raw.cpp similarity index 100% rename from io/tools/ply/ply2raw.cpp rename to tools/ply2raw.cpp diff --git a/io/tools/ply/plyheader.cpp b/tools/plyheader.cpp similarity index 100% rename from io/tools/ply/plyheader.cpp rename to tools/plyheader.cpp From b551ee47b24e90cfb430ee4474f569e1411cd7bc Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Tue, 21 Feb 2023 02:17:59 -0800 Subject: [PATCH 051/288] Added modernize-use-emplace, modernize-loop-convert clang-tidy check (#5610) Fixed some odd misspellings Fixed formatting escapes Ran 'build format' to resolve clang-format issues Debugging odd compile error Fixed more issues from CI Addressed CI issues and review feedback Added missing const Added yet more missing const Reverted another omp parallel for Reverted for third-party code Disabled clang-tidy for third-party code --- .clang-tidy | 3 ++ common/include/pcl/point_types_conversion.h | 8 ++--- .../impl/multiscale_feature_persistence.hpp | 4 +-- features/include/pcl/features/our_cvfh.h | 8 ++--- features/src/narf.cpp | 6 ++-- .../pcl/filters/impl/covariance_sampling.hpp | 4 +-- .../include/pcl/filters/impl/crop_hull.hpp | 4 +-- .../pcl/filters/impl/local_maximum.hpp | 8 ++--- geometry/include/pcl/geometry/mesh_base.h | 29 ++++++++++-------- .../impl/smoothed_surfaces_keypoint.hpp | 12 ++++---- .../pcl/keypoints/impl/trajkovic_2d.hpp | 2 ++ .../pcl/ml/impl/dt/decision_tree_trainer.hpp | 14 +++------ .../pcl/people/impl/head_based_subcluster.hpp | 4 +-- .../pcl/recognition/3rdparty/metslib/model.hh | 8 +++-- .../3rdparty/metslib/tabu-search.hh | 4 ++- .../include/pcl/recognition/impl/hv/hv_go.hpp | 6 ++-- .../recognition/impl/linemod/line_rgbd.hpp | 30 ++++++++----------- .../include/pcl/registration/impl/ndt_2d.hpp | 4 +-- .../impl/sac_model_sphere.hpp | 10 +++---- test/features/test_normal_estimation.cpp | 8 ++--- test/io/test_iterators.cpp | 4 ++- test/io/test_octree_compression.cpp | 4 +-- test/search/test_organized_index.cpp | 8 ++--- test/surface/test_poisson.cpp | 4 +-- tools/fast_bilateral_filter.cpp | 4 ++- tools/normal_estimation.cpp | 4 ++- 26 files changed, 106 insertions(+), 98 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 80625eda8a4..35542031548 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -5,10 +5,13 @@ Checks: > cppcoreguidelines-pro-type-static-cast-downcast, google-readability-casting, modernize-deprecated-headers, + modernize-loop-convert, modernize-redundant-void-arg, modernize-replace-random-shuffle, modernize-return-braced-init-list, + modernize-shrink-to-fit, modernize-use-auto, + modernize-use-emplace, modernize-use-equals-default, modernize-use-equals-delete, modernize-use-nullptr, diff --git a/common/include/pcl/point_types_conversion.h b/common/include/pcl/point_types_conversion.h index a4afdace339..23f8e68d860 100644 --- a/common/include/pcl/point_types_conversion.h +++ b/common/include/pcl/point_types_conversion.h @@ -173,12 +173,12 @@ namespace pcl 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); + for (float & xyz : f) { + if (xyz > 0.008856) { + xyz = std::pow(xyz, 1.0 / 3.0); } else { - f[i] = 7.787 * f[i] + 16.0 / 116.0; + xyz = 7.787 * xyz + 16.0 / 116.0; } } diff --git a/features/include/pcl/features/impl/multiscale_feature_persistence.hpp b/features/include/pcl/features/impl/multiscale_feature_persistence.hpp index 932aad8d5e5..a44ec8b148c 100644 --- a/features/include/pcl/features/impl/multiscale_feature_persistence.hpp +++ b/features/include/pcl/features/impl/multiscale_feature_persistence.hpp @@ -91,10 +91,10 @@ pcl::MultiscaleFeaturePersistence::computeFeaturesAtA features_at_scale_.reserve (scale_values_.size ()); features_at_scale_vectorized_.clear (); features_at_scale_vectorized_.reserve (scale_values_.size ()); - for (std::size_t scale_i = 0; scale_i < scale_values_.size (); ++scale_i) + for (float & scale_value : scale_values_) { FeatureCloudPtr feature_cloud (new FeatureCloud ()); - computeFeatureAtScale (scale_values_[scale_i], feature_cloud); + computeFeatureAtScale (scale_value, feature_cloud); features_at_scale_.push_back(feature_cloud); // Vectorize each feature and insert it into the vectorized feature storage diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index a40503fdb42..f1f42251641 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -190,8 +190,8 @@ namespace pcl inline void getCentroidClusters (std::vector > & centroids) { - for (std::size_t i = 0; i < centroids_dominant_orientations_.size (); ++i) - centroids.push_back (centroids_dominant_orientations_[i]); + for (const auto & centroids_dominant_orientation : centroids_dominant_orientations_) + centroids.push_back (centroids_dominant_orientation); } /** \brief Get the normal centroids used to compute different CVFH descriptors @@ -200,8 +200,8 @@ namespace pcl inline void getCentroidNormalClusters (std::vector > & centroids) { - for (std::size_t i = 0; i < dominant_normals_.size (); ++i) - centroids.push_back (dominant_normals_[i]); + for (const auto & dominant_normal : dominant_normals_) + centroids.push_back (dominant_normal); } /** \brief Sets max. Euclidean distance between points to be added to the cluster diff --git a/features/src/narf.cpp b/features/src/narf.cpp index 556e741eccb..8e07b71270d 100644 --- a/features/src/narf.cpp +++ b/features/src/narf.cpp @@ -376,6 +376,8 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud< schedule(dynamic, 10) \ num_threads(max_no_of_threads) //!!! nizar 20110408 : for OpenMP sake on MSVC this must be kept signed + // Disable lint since this 'for' is part of the pragma + // NOLINTNEXTLINE(modernize-loop-convert) for (std::ptrdiff_t idx = 0; idx < static_cast(interest_points.size ()); ++idx) { const auto& interest_point = interest_points[idx]; @@ -389,7 +391,7 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud< else { if (!rotation_invariant) { -# pragma omp critical +#pragma omp critical { feature_list.push_back(feature); } @@ -409,7 +411,7 @@ Narf::extractForInterestPoints (const RangeImage& range_image, const PointCloud< delete feature2; continue; } -# pragma omp critical +#pragma omp critical { feature_list.push_back(feature2); } diff --git a/filters/include/pcl/filters/impl/covariance_sampling.hpp b/filters/include/pcl/filters/impl/covariance_sampling.hpp index df675d1923f..99d8da8f550 100644 --- a/filters/include/pcl/filters/impl/covariance_sampling.hpp +++ b/filters/include/pcl/filters/impl/covariance_sampling.hpp @@ -75,8 +75,8 @@ pcl::CovarianceSampling::initCompute () } average_norm /= static_cast(scaled_points_.size ()); - for (std::size_t p_i = 0; p_i < scaled_points_.size (); ++p_i) - scaled_points_[p_i] /= static_cast(average_norm); + for (auto & scaled_point : scaled_points_) + scaled_point /= static_cast(average_norm); return (true); } diff --git a/filters/include/pcl/filters/impl/crop_hull.hpp b/filters/include/pcl/filters/impl/crop_hull.hpp index ef34a021bd4..dbe8f5d07bc 100644 --- a/filters/include/pcl/filters/impl/crop_hull.hpp +++ b/filters/include/pcl/filters/impl/crop_hull.hpp @@ -153,10 +153,10 @@ pcl::CropHull::applyFilter3D (Indices &indices) Eigen::Vector3f(0.856514f, 0.508771f, 0.0868081f) }; - for (std::size_t poly = 0; poly < hull_polygons_.size (); poly++) + for (const auto & hull_polygon : hull_polygons_) for (std::size_t ray = 0; ray < 3; ray++) crossings[ray] += rayTriangleIntersect - ((*input_)[(*indices_)[index]], rays[ray], hull_polygons_[poly], *hull_cloud_); + ((*input_)[(*indices_)[index]], rays[ray], hull_polygon, *hull_cloud_); bool crosses = (crossings[0]&1) + (crossings[1]&1) + (crossings[2]&1) > 1; if ((crop_outside_ && crosses) || (!crop_outside_ && !crosses)) diff --git a/filters/include/pcl/filters/impl/local_maximum.hpp b/filters/include/pcl/filters/impl/local_maximum.hpp index 2b770d3efa9..59c821bb362 100644 --- a/filters/include/pcl/filters/impl/local_maximum.hpp +++ b/filters/include/pcl/filters/impl/local_maximum.hpp @@ -154,9 +154,9 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) // Check to see if a neighbor is higher than the query point float query_z = (*input_)[iii].z; - for (std::size_t k = 0; k < radius_indices.size (); ++k) // the query point itself is in the (unsorted) radius_indices, but that is okay since we compare with ">" + for (const auto& radius_index : radius_indices) // the query point itself is in the (unsorted) radius_indices, but that is okay since we compare with ">" { - if ((*input_)[radius_indices[k]].z > query_z) + if ((*input_)[radius_index].z > query_z) { // Query point is not the local max, no need to check others point_is_max[iii] = false; @@ -168,9 +168,9 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) // visited, excluding them from future consideration as local maxima if (point_is_max[iii]) { - for (std::size_t k = 0; k < radius_indices.size (); ++k) // the query point itself is in the (unsorted) radius_indices, but it must also be marked as visited + for (const auto& radius_index : radius_indices) // the query point itself is in the (unsorted) radius_indices, but it must also be marked as visited { - point_is_visited[radius_indices[k]] = true; + point_is_visited[radius_index] = true; } } diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index 991ac56470e..d9346bab944 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -323,25 +323,28 @@ class MeshBase { } // Adjust the indices - for (auto it = vertices_.begin(); it != vertices_.end(); ++it) { - if (it->idx_outgoing_half_edge_.isValid()) { - it->idx_outgoing_half_edge_ = - new_half_edge_indices[it->idx_outgoing_half_edge_.get()]; + for (auto& vertex : vertices_) { + if (vertex.idx_outgoing_half_edge_.isValid()) { + vertex.idx_outgoing_half_edge_ = + new_half_edge_indices[vertex.idx_outgoing_half_edge_.get()]; } } - for (auto it = half_edges_.begin(); it != half_edges_.end(); ++it) { - it->idx_terminating_vertex_ = - new_vertex_indices[it->idx_terminating_vertex_.get()]; - it->idx_next_half_edge_ = new_half_edge_indices[it->idx_next_half_edge_.get()]; - it->idx_prev_half_edge_ = new_half_edge_indices[it->idx_prev_half_edge_.get()]; - if (it->idx_face_.isValid()) { - it->idx_face_ = new_face_indices[it->idx_face_.get()]; + for (auto& half_edge : half_edges_) { + half_edge.idx_terminating_vertex_ = + new_vertex_indices[half_edge.idx_terminating_vertex_.get()]; + half_edge.idx_next_half_edge_ = + new_half_edge_indices[half_edge.idx_next_half_edge_.get()]; + half_edge.idx_prev_half_edge_ = + new_half_edge_indices[half_edge.idx_prev_half_edge_.get()]; + if (half_edge.idx_face_.isValid()) { + half_edge.idx_face_ = new_face_indices[half_edge.idx_face_.get()]; } } - for (auto it = faces_.begin(); it != faces_.end(); ++it) { - it->idx_inner_half_edge_ = new_half_edge_indices[it->idx_inner_half_edge_.get()]; + for (auto& face : faces_) { + face.idx_inner_half_edge_ = + new_half_edge_indices[face.idx_inner_half_edge_.get()]; } } diff --git a/keypoints/include/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp b/keypoints/include/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp index 2c1a3dff2ca..4f612bcb649 100644 --- a/keypoints/include/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp +++ b/keypoints/include/pcl/keypoints/impl/smoothed_surfaces_keypoint.hpp @@ -52,7 +52,7 @@ pcl::SmoothedSurfacesKeypoint::addSmoothedPointCloud (const Poi clouds_.push_back (cloud); cloud_normals_.push_back (normals); cloud_trees_.push_back (kdtree); - scales_.push_back (std::pair (scale, scales_.size ())); + scales_.emplace_back(scale, scales_.size ()); } @@ -115,15 +115,15 @@ pcl::SmoothedSurfacesKeypoint::detectKeypoints (PointCloudT &ou if (is_min || is_max) { bool passed_min = true, passed_max = true; - for (std::size_t scale_i = 0; scale_i < scales_.size (); ++scale_i) + for (const auto & scale : scales_) { - std::size_t cloud_i = scales_[scale_i].second; + std::size_t cloud_i = scale.second; // skip input cloud if (cloud_i == clouds_.size () - 1) continue; nn_indices.clear (); nn_distances.clear (); - cloud_trees_[cloud_i]->radiusSearch (point_i, scales_[scale_i].first * neighborhood_constant_, nn_indices, nn_distances); + cloud_trees_[cloud_i]->radiusSearch (point_i, scale.first * neighborhood_constant_, nn_indices, nn_distances); bool is_min_other_scale = true, is_max_other_scale = true; for (const auto &nn_index : nn_indices) @@ -225,7 +225,7 @@ pcl::SmoothedSurfacesKeypoint::initCompute () } // Add the input cloud as the last index - scales_.push_back (std::pair (input_scale_, scales_.size ())); + scales_.emplace_back(input_scale_, scales_.size ()); clouds_.push_back (input_); cloud_normals_.push_back (normals_); cloud_trees_.push_back (tree_); @@ -241,7 +241,7 @@ pcl::SmoothedSurfacesKeypoint::initCompute () } PCL_INFO ("Scales: "); - for (std::size_t i = 0; i < scales_.size (); ++i) PCL_INFO ("(%d %f), ", scales_[i].second, scales_[i].first); + for (const auto & scale : scales_) PCL_INFO ("(%d %f), ", scale.second, scale.first); PCL_INFO ("\n"); return (true); diff --git a/keypoints/include/pcl/keypoints/impl/trajkovic_2d.hpp b/keypoints/include/pcl/keypoints/impl/trajkovic_2d.hpp index 94c465aa1a5..8b1c1463834 100644 --- a/keypoints/include/pcl/keypoints/impl/trajkovic_2d.hpp +++ b/keypoints/include/pcl/keypoints/impl/trajkovic_2d.hpp @@ -246,6 +246,8 @@ TrajkovicKeypoint2D::detectKeypoints (PointClou shared(height, indices, occupency_map, output, width) \ num_threads(threads_) #endif + // Disable lint since this 'for' is part of the pragma + // NOLINTNEXTLINE(modernize-loop-convert) for (std::ptrdiff_t i = 0; i < static_cast (indices.size ()); ++i) { int idx = indices[i]; diff --git a/ml/include/pcl/ml/impl/dt/decision_tree_trainer.hpp b/ml/include/pcl/ml/impl/dt/decision_tree_trainer.hpp index be2d3610847..c1e7aaeef68 100644 --- a/ml/include/pcl/ml/impl/dt/decision_tree_trainer.hpp +++ b/ml/include/pcl/ml/impl/dt/decision_tree_trainer.hpp @@ -159,21 +159,15 @@ DecisionTreeTrainer:: if (!thresholds_.empty()) { // compute information gain for each threshold and store threshold with highest // information gain - for (std::size_t threshold_index = 0; threshold_index < thresholds_.size(); - ++threshold_index) { + for (const float& threshold : thresholds_) { - const float information_gain = - stats_estimator_->computeInformationGain(data_set_, - examples, - label_data, - feature_results, - flags, - thresholds_[threshold_index]); + const float information_gain = stats_estimator_->computeInformationGain( + data_set_, examples, label_data, feature_results, flags, threshold); if (information_gain > best_feature_information_gain) { best_feature_information_gain = information_gain; best_feature_index = static_cast(feature_index); - best_feature_threshold = thresholds_[threshold_index]; + best_feature_threshold = threshold; } } } diff --git a/people/include/pcl/people/impl/head_based_subcluster.hpp b/people/include/pcl/people/impl/head_based_subcluster.hpp index 43d333832eb..7c9866fcf27 100644 --- a/people/include/pcl/people/impl/head_based_subcluster.hpp +++ b/people/include/pcl/people/impl/head_based_subcluster.hpp @@ -270,9 +270,9 @@ pcl::people::HeadBasedSubclustering::subcluster (std::vector::const_iterator it = cluster_indices_.begin(); it != cluster_indices_.end(); ++it) + for(const auto & cluster_index : cluster_indices_) { - pcl::people::PersonCluster cluster(cloud_, *it, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_); // PersonCluster creation + pcl::people::PersonCluster cluster(cloud_, cluster_index, ground_coeffs_, sqrt_ground_coeffs_, head_centroid_, vertical_); // PersonCluster creation clusters.push_back(cluster); } diff --git a/recognition/include/pcl/recognition/3rdparty/metslib/model.hh b/recognition/include/pcl/recognition/3rdparty/metslib/model.hh index d2403bfc484..50657e39f90 100644 --- a/recognition/include/pcl/recognition/3rdparty/metslib/model.hh +++ b/recognition/include/pcl/recognition/3rdparty/metslib/model.hh @@ -36,6 +36,8 @@ #define METS_MODEL_HH_ namespace mets { +// Exempt third-party code from clang-tidy +// NOLINTBEGIN /// @brief Type of the objective/cost function. /// @@ -656,7 +658,7 @@ namespace mets { /// @brief Dtor. ~swap_full_neighborhood() override { - for(auto it = moves_m.begin(); + for(auto it = moves_m.begin(); it != moves_m.end(); ++it) delete *it; } @@ -681,7 +683,7 @@ namespace mets { /// @brief Dtor. ~invert_full_neighborhood() override { - for(auto it = moves_m.begin(); + for(auto it = moves_m.begin(); it != moves_m.end(); ++it) delete *it; } @@ -711,7 +713,7 @@ namespace mets { const Tp r) const { return l->operator==(*r); } }; - +// NOLINTEND } //________________________________________________________________________ diff --git a/recognition/include/pcl/recognition/3rdparty/metslib/tabu-search.hh b/recognition/include/pcl/recognition/3rdparty/metslib/tabu-search.hh index 1a92a0bf7e7..dfe82d960eb 100644 --- a/recognition/include/pcl/recognition/3rdparty/metslib/tabu-search.hh +++ b/recognition/include/pcl/recognition/3rdparty/metslib/tabu-search.hh @@ -497,7 +497,9 @@ mets::tabu_list_chain::is_tabu(feasible_solution& sol, /* const */ move& mov) co inline mets::simple_tabu_list::~simple_tabu_list() { - for(move_map_type::iterator m = tabu_hash_m.begin(); + // Disable lint for third-party code + // NOLINTNEXTLINE(modernize-loop-convert) + for(move_map_type::iterator m = tabu_hash_m.begin(); m!=tabu_hash_m.end(); ++m) delete m->first; } diff --git a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp index 51cff240b59..4783f7018d5 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp @@ -410,9 +410,9 @@ void pcl::GlobalHypothesesVerification::SAOptimize(std::vector 1) { - occupied_multiple+=complete_cloud_occupancy_by_RM_[i]; + for(const auto& i : complete_cloud_occupancy_by_RM_) { + if(i > 1) { + occupied_multiple+=i; } } diff --git a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp index a340e254439..5fdd7028f53 100644 --- a/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp +++ b/recognition/include/pcl/recognition/impl/linemod/line_rgbd.hpp @@ -167,10 +167,8 @@ LineRGBD::loadTemplates (const std::string &file_name, con float max_y = -std::numeric_limits::max (); float max_z = -std::numeric_limits::max (); std::size_t counter = 0; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (const auto & p : template_point_cloud) { - const PointXYZRGBA & p = template_point_cloud[j]; - if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -200,9 +198,9 @@ LineRGBD::loadTemplates (const std::string &file_name, con bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (auto & j : template_point_cloud) { - PointXYZRGBA p = template_point_cloud[j]; + PointXYZRGBA p = j; if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -211,7 +209,7 @@ LineRGBD::loadTemplates (const std::string &file_name, con p.y -= center_y; p.z -= center_z; - template_point_cloud[j] = p; + j = p; } } @@ -254,10 +252,8 @@ LineRGBD::createAndAddTemplate ( float max_y = -std::numeric_limits::max (); float max_z = -std::numeric_limits::max (); std::size_t counter = 0; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (const auto & p : template_point_cloud) { - const PointXYZRGBA & p = template_point_cloud[j]; - if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -287,9 +283,9 @@ LineRGBD::createAndAddTemplate ( bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (auto & j : template_point_cloud) { - PointXYZRGBA p = template_point_cloud[j]; + PointXYZRGBA p = j; if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -298,7 +294,7 @@ LineRGBD::createAndAddTemplate ( p.y -= center_y; p.z -= center_z; - template_point_cloud[j] = p; + j = p; } } @@ -345,10 +341,8 @@ LineRGBD::addTemplate (const SparseQuantizedMultiModTempla float max_y = -std::numeric_limits::max (); float max_z = -std::numeric_limits::max (); std::size_t counter = 0; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (const auto & p : template_point_cloud) { - const PointXYZRGBA & p = template_point_cloud[j]; - if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -378,9 +372,9 @@ LineRGBD::addTemplate (const SparseQuantizedMultiModTempla bb.y = (min_y + bb.height / 2.0f) - center_y - bb.height / 2.0f; bb.z = (min_z + bb.depth / 2.0f) - center_z - bb.depth / 2.0f; - for (std::size_t j = 0; j < template_point_cloud.size (); ++j) + for (auto & j : template_point_cloud) { - PointXYZRGBA p = template_point_cloud[j]; + PointXYZRGBA p = j; if (!std::isfinite (p.x) || !std::isfinite (p.y) || !std::isfinite (p.z)) continue; @@ -389,7 +383,7 @@ LineRGBD::addTemplate (const SparseQuantizedMultiModTempla p.y -= center_y; p.z -= center_z; - template_point_cloud[j] = p; + j = p; } } diff --git a/registration/include/pcl/registration/impl/ndt_2d.hpp b/registration/include/pcl/registration/impl/ndt_2d.hpp index 3f790cd6e2f..1aeb6d1bdb0 100644 --- a/registration/include/pcl/registration/impl/ndt_2d.hpp +++ b/registration/include/pcl/registration/impl/ndt_2d.hpp @@ -121,8 +121,8 @@ class NormalDist { Eigen::Vector2d sx = Eigen::Vector2d::Zero(); Eigen::Matrix2d sxx = Eigen::Matrix2d::Zero(); - for (auto i = pt_indices_.cbegin(); i != pt_indices_.cend(); i++) { - Eigen::Vector2d p(cloud[*i].x, cloud[*i].y); + for (const auto& pt_index : pt_indices_) { + Eigen::Vector2d p(cloud[pt_index].x, cloud[pt_index].y); sx += p; sxx += p * p.transpose(); } 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 3b77afdb75b..6834afb601e 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 @@ -399,20 +399,20 @@ pcl::SampleConsensusModelSphere::projectPoints ( pcl::for_each_type (NdConcatenateFunctor (input_->points[i], projected_points.points[i])); // Iterate through the 3d points and calculate the distances from them to the sphere - for (std::size_t i = 0; i < inliers.size (); ++i) + for (const auto& inlier : inliers) { // what i have: // P : Sample Point - const Eigen::Vector3d P (input_->points[inliers[i]].x, input_->points[inliers[i]].y, input_->points[inliers[i]].z); + const Eigen::Vector3d P (input_->points[inlier].x, input_->points[inlier].y, input_->points[inlier].z); const Eigen::Vector3d direction = (P - C).normalized(); // K : Point on Sphere const Eigen::Vector3d K = C + r * direction; - projected_points.points[inliers[i]].x = static_cast (K[0]); - projected_points.points[inliers[i]].y = static_cast (K[1]); - projected_points.points[inliers[i]].z = static_cast (K[2]); + projected_points.points[inlier].x = static_cast (K[0]); + projected_points.points[inlier].y = static_cast (K[1]); + projected_points.points[inlier].z = static_cast (K[2]); } } else diff --git a/test/features/test_normal_estimation.cpp b/test/features/test_normal_estimation.cpp index d1eb8d5e0aa..558ab312991 100644 --- a/test/features/test_normal_estimation.cpp +++ b/test/features/test_normal_estimation.cpp @@ -191,10 +191,10 @@ TEST (PCL, TranslatedNormalEstimation) NormalEstimation n; PointCloud translatedCloud(cloud); - for(size_t i = 0; i < translatedCloud.size(); ++i) { - translatedCloud[i].x += 100; - translatedCloud[i].y += 100; - translatedCloud[i].z += 100; + for(auto & i : translatedCloud) { + i.x += 100; + i.y += 100; + i.z += 100; } // computePointNormal (indices, Vector) diff --git a/test/io/test_iterators.cpp b/test/io/test_iterators.cpp index c44cbd564be..d09c71e8ec2 100644 --- a/test/io/test_iterators.cpp +++ b/test/io/test_iterators.cpp @@ -59,7 +59,9 @@ TEST (PCL, Iterators) { Point mean (0,0,0); - for (auto it = cloud.begin(); it != cloud.end(); ++it) + // Disable lint since this test is testing begin() and end() + // NOLINTNEXTLINE(modernize-loop-convert) + for (auto it = cloud.begin(); it != cloud.end(); ++it) { for (int i=0;i<3;i++) mean.data[i] += it->data[i]; } diff --git a/test/io/test_octree_compression.cpp b/test/io/test_octree_compression.cpp index 6cf9f2f2342..a044a33b07f 100644 --- a/test/io/test_octree_compression.cpp +++ b/test/io/test_octree_compression.cpp @@ -177,8 +177,8 @@ TEST(PCL, OctreeDeCompressionFile) 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]); + for (const float& voxel_size : voxel_sizes) { + pcl::octree::OctreePointCloud octree(voxel_size); pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud()); octree.setInputCloud((*input_cloud_ptr).makeShared()); octree.addPointsFromInputCloud(); diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index f4ba1e4c390..582099e7bc5 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -303,9 +303,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search) // bruteforce radius search std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; - for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) + for (const auto& point : cloudIn->points) { - const auto pointDist = pcl_tests::point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(point, searchPoint); if (pointDist <= (searchRadius+TOLERANCE)) { ++cloudSearchBruteforce_size_upper; @@ -501,9 +501,9 @@ TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_ // bruteforce radius search std::size_t cloudSearchBruteforce_size_lower = 0, cloudSearchBruteforce_size_upper = 0; - for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) + for (const auto& point : cloudIn->points) { - const auto pointDist = pcl_tests::point_distance(*it, searchPoint); + const auto pointDist = pcl_tests::point_distance(point, searchPoint); if (pointDist <= (searchRadius+TOLERANCE)) { ++cloudSearchBruteforce_size_upper; diff --git a/test/surface/test_poisson.cpp b/test/surface/test_poisson.cpp index 75491a17592..b6a0ec1bf10 100644 --- a/test/surface/test_poisson.cpp +++ b/test/surface/test_poisson.cpp @@ -75,8 +75,8 @@ TEST (PCL, Poisson) ASSERT_EQ (mesh.polygons.size (), 4828); // All polygons should be triangles - for (std::size_t i = 0; i < mesh.polygons.size (); ++i) - EXPECT_EQ (mesh.polygons[i].vertices.size (), 3); + for (const auto & polygon : mesh.polygons) + EXPECT_EQ (polygon.vertices.size (), 3); EXPECT_EQ (mesh.polygons[10].vertices[0], 197); EXPECT_EQ (mesh.polygons[10].vertices[1], 198); diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index 1832d83e2bf..0c3d8d2fa8c 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -116,13 +116,15 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir #pragma omp parallel for \ default(none) \ shared(output_dir, pcd_files, sigma_r, sigma_s) + // Disable lint since this 'for' is part of the pragma + // NOLINTNEXTLINE(modernize-loop-convert) for (int i = 0; i < static_cast(pcd_files.size ()); ++i) { // Load the first file Eigen::Vector4f translation; Eigen::Quaternionf rotation; pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2); - if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) + if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) continue; // Perform the feature estimation diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index f340ddb8816..aee26bf2aeb 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -135,13 +135,15 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir #pragma omp parallel for \ default(none) \ shared(k, output_dir, pcd_files, radius) + // Disable lint since this 'for' is part of the pragma + // NOLINTNEXTLINE(modernize-loop-convert) for (int i = 0; i < static_cast(pcd_files.size ()); ++i) { // Load the first file Eigen::Vector4f translation; Eigen::Quaternionf rotation; pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2); - if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) + if (!loadCloud (pcd_files[i], *cloud, translation, rotation)) continue; // Perform the feature estimation From 5cd00c9b30151afd19109d4e4b7b085637ff440e Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 28 Feb 2023 13:43:25 +0100 Subject: [PATCH 052/288] CI: updates and improvements - release pipeline: fix git tag of final release (was previously e.g. pcl-1.13.0-rc0, is now pcl-1.13.0). Pre-releases/release-candidates are still pcl-1.13.0-rc1 - ubuntu-variety: update available compilers - install libboost-system-dev. While this is installed implicitly by libboost-filesystem-dev, PCL needs the `system` module, so we should install it explicitly - install libpcap-dev, an optional dependency of PCL - update actions/checkout to v3 (see https://github.blog/changelog/2022-09-22-github-actions-all-actions-will-begin-running-on-node16-instead-of-node12/) --- .ci/azure-pipelines/release.yaml | 5 +++-- .ci/azure-pipelines/ubuntu-variety.yaml | 6 +++--- .dev/docker/env/Dockerfile | 2 ++ .dev/docker/release/Dockerfile | 1 + .github/workflows/clang-tidy.yml | 2 +- 5 files changed, 10 insertions(+), 6 deletions(-) diff --git a/.ci/azure-pipelines/release.yaml b/.ci/azure-pipelines/release.yaml index b088cf29270..81ba26c663e 100644 --- a/.ci/azure-pipelines/release.yaml +++ b/.ci/azure-pipelines/release.yaml @@ -204,8 +204,9 @@ stages: # find the commit hash on a quick non-forced update too fetchDepth: 10 - bash: | - if [ -z $RC ] || [ $RC -eq 0 ]; then isPreRelease=false; else isPreRelease=true; fi + if [ -z $RC ] || [ $RC -eq 0 ]; then isPreRelease=false; tagName="pcl-$(VERSION)"; else isPreRelease=true; tagName="pcl-$(VERSION)-rc$(RC)"; fi echo "##vso[task.setvariable variable=isPreRelease]${isPreRelease}" + echo "##vso[task.setvariable variable=tagName]${tagName}" - task: DownloadBuildArtifacts@0 inputs: downloadType: 'all' # can be anything except single @@ -223,7 +224,7 @@ stages: releaseNotesFilePath: '$(DOWNLOAD_LOCATION)/changelog/changelog.md' repositoryName: $(Build.Repository.Name) tagSource: 'userSpecifiedTag' - tag: "pcl-$(VERSION)-rc$(RC)" + tag: "$(tagName)" tagPattern: 'pcl-*' target: '$(Build.SourceVersion)' title: 'PCL $(VERSION)' diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml index 0910cd6f71d..12ae9db0ccb 100644 --- a/.ci/azure-pipelines/ubuntu-variety.yaml +++ b/.ci/azure-pipelines/ubuntu-variety.yaml @@ -32,9 +32,9 @@ jobs: POSSIBLE_VTK_VERSION=("7" "9") \ POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \ POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \ - POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "clang" "clang-11" "clang-12" "clang-13" "clang-14" "clang-15") \ - POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "clang" "clang-11" "clang-12" "clang-13" "clang-14" "clang-15") \ - POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "clang++" "clang++-11" "clang++-12" "clang++-13" "clang++-14" "clang++-15") \ + POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15") \ + POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15") \ + POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15") \ CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \ dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \ echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs" diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index 67a6e9d81b6..75dc31f048c 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -33,11 +33,13 @@ RUN apt-get update \ libboost-serialization-dev \ libboost-filesystem-dev \ libboost-iostreams-dev \ + libboost-system-dev \ libflann-dev \ libglew-dev \ libgtest-dev \ libopenni-dev \ libopenni2-dev \ + libpcap-dev \ libproj-dev \ libqhull-dev \ libqt5opengl5-dev \ diff --git a/.dev/docker/release/Dockerfile b/.dev/docker/release/Dockerfile index 65b04c89936..f1c6211c34b 100644 --- a/.dev/docker/release/Dockerfile +++ b/.dev/docker/release/Dockerfile @@ -18,6 +18,7 @@ RUN sed -i 's/^deb \(.*\)$/deb \1\ndeb-src \1/' /etc/apt/sources.list \ libboost-serialization-dev \ libboost-filesystem-dev \ libboost-iostreams-dev \ + libboost-system-dev \ libeigen3-dev \ libflann-dev \ libglew-dev \ diff --git a/.github/workflows/clang-tidy.yml b/.github/workflows/clang-tidy.yml index 86845c0c805..a78a188185a 100755 --- a/.github/workflows/clang-tidy.yml +++ b/.github/workflows/clang-tidy.yml @@ -9,7 +9,7 @@ jobs: image: pointcloudlibrary/env:22.04 steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v3 - name: Run clang-tidy run: | From 0d03224f10a704e02a4f7f6ca6008376d4b480ed Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 1 Mar 2023 21:09:30 +0100 Subject: [PATCH 053/288] CMake fixes and improvements - Don't disable warnings for gcc (warnings should be fixed by now) - Always add /bigobj flag for MSVC (from https://github.com/microsoft/vcpkg/blob/master/ports/pcl/add_bigobj_option.patch) - Disable kinfu and kinfu_large_scale for CUDA >= 12.0 --- CMakeLists.txt | 5 +++-- gpu/kinfu/CMakeLists.txt | 7 ++++++- gpu/kinfu_large_scale/CMakeLists.txt | 7 ++++++- 3 files changed, 15 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b63a78858fd..8990960b427 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -119,7 +119,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} ${AVX_FLAGS}") + string(APPEND CMAKE_CXX_FLAGS " -Wall -Wextra -fno-strict-aliasing ${SSE_FLAGS} ${AVX_FLAGS}") endif() if(PCL_WARNINGS_ARE_ERRORS) @@ -146,8 +146,9 @@ endif() if(CMAKE_COMPILER_IS_MSVC) add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX -DPCL_ONLY_CORE_POINT_TYPES ${SSE_DEFINITIONS}") + string(APPEND CMAKE_CXX_FLAGS " /bigobj") if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") - string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS} /bigobj") + string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${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/gpu/kinfu/CMakeLists.txt b/gpu/kinfu/CMakeLists.txt index 29cb73e955a..fbbd294fdbc 100644 --- a/gpu/kinfu/CMakeLists.txt +++ b/gpu/kinfu/CMakeLists.txt @@ -2,7 +2,12 @@ set(SUBSYS_NAME gpu_kinfu) set(SUBSYS_PATH gpu/kinfu) set(SUBSYS_DESC "Kinect Fusion implementation") set(SUBSYS_DEPS common io gpu_containers geometry search) -set(DEFAULT TRUE) +if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0") + set(DEFAULT FALSE) + set(REASON "Kinfu uses textures which was removed in CUDA 12") +else() + set(DEFAULT TRUE) +endif() PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/gpu/kinfu_large_scale/CMakeLists.txt b/gpu/kinfu_large_scale/CMakeLists.txt index d7efc4ad5aa..0488fcb46aa 100644 --- a/gpu/kinfu_large_scale/CMakeLists.txt +++ b/gpu/kinfu_large_scale/CMakeLists.txt @@ -2,7 +2,12 @@ set(SUBSYS_NAME gpu_kinfu_large_scale) set(SUBSYS_PATH gpu/kinfu_large_scale) set(SUBSYS_DESC "Kinect Fusion implementation, with volume shifting") set(SUBSYS_DEPS common io gpu_containers gpu_utils geometry search octree filters kdtree features surface) -set(DEFAULT TRUE) +if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0") + set(DEFAULT FALSE) + set(REASON "Kinfu_large_scale uses textures which was removed in CUDA 12") +else() + set(DEFAULT TRUE) +endif() PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) From 2b1ebddad81e0d007199416b39d4476fcd5a85d2 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 3 Mar 2023 14:02:21 +0100 Subject: [PATCH 054/288] Improve documentation --- common/include/pcl/common/io.h | 2 ++ .../conditional_euclidean_clustering.cpp | 2 +- doc/tutorials/content/writing_new_classes.rst | 2 +- .../recognition/face_detection/rf_face_detector_trainer.h | 5 ++++- 4 files changed, 8 insertions(+), 3 deletions(-) diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index 5ff5370ae6f..f6e846e26c9 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -54,6 +54,7 @@ namespace pcl /** \brief Get the index of a specified field (i.e., dimension/channel) * \param[in] cloud the point cloud message * \param[in] field_name the string defining the field name + * \return the index of the field or a negative integer if no field with the given name exists * \ingroup common */ inline int @@ -71,6 +72,7 @@ namespace pcl * \tparam PointT datatype for which fields is being queries * \param[in] field_name the string defining the field name * \param[out] fields a vector to the original \a PCLPointField vector that the raw PointCloud message contains + * \return the index of the field or a negative integer if no field with the given name exists * \ingroup common */ template inline int 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 eb4eb13e59c..158c38a0e83 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 @@ -37,7 +37,7 @@ customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, { if (std::abs (point_a.intensity - point_b.intensity) < 8.0f) return (true); - if (std::abs (point_a_normal.dot (point_b_normal)) < 0.06) + if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast (M_PI))) return (true); } else diff --git a/doc/tutorials/content/writing_new_classes.rst b/doc/tutorials/content/writing_new_classes.rst index 2dab0a40f77..45ac095c5e2 100644 --- a/doc/tutorials/content/writing_new_classes.rst +++ b/doc/tutorials/content/writing_new_classes.rst @@ -909,7 +909,7 @@ file, as follows: * All rights reserved */ -An additional like can be inserted if additional copyright is needed (or the +An additional line can be inserted if additional copyright is needed (or the original copyright can be changed): .. code-block:: cpp diff --git a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h index 175f94f86c9..f8dd642da07 100644 --- a/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h +++ b/recognition/include/pcl/recognition/face_detection/rf_face_detector_trainer.h @@ -59,7 +59,7 @@ namespace pcl virtual ~RFFaceDetectorTrainer() = default; /* - * Common parameters + * Set name of the file in which RFFaceDetectorTrainer will store the forest. */ void setForestFilename(std::string & ff) { @@ -136,6 +136,9 @@ namespace pcl used_for_pose_ = n; } + /* + * This forest is used to detect faces. + */ void setForest(pcl::DecisionForest & forest) { forest_ = forest; From d47f6d7fa6026e77e6d408b7c3e66e8dc40dfc49 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 3 Mar 2023 14:57:45 +0100 Subject: [PATCH 055/288] Small fixes and improvements - openni_klt.cpp: initialize counter_ to 0 - conversions.h: use std::size_t instead of uindex_t. This is an improvement when loading large clouds (e.g. more than 2^28 = 268 million XYZI points, because 2^28*16 overflows 32 bit unsigned, 16 being the point step/bytes per point). The user can switch uindex_t from 32 bit unsigned to 64 bit unsigned to solve this, but simply using std::size_t here is easier - voxel_grid_covariance.h: construct array with appropriate size - gicp.hpp: de-mean point neighbourhoods when computing covariance matrices - ppf_registration.hpp: switch messages from info to debug - region_growing.hpp: use auto for indices - opennurbs_system.h: do not throw error when WIN32 is defined (see also https://github.com/microsoft/vcpkg/blob/master/ports/pcl/fix_opennurbs_win32.patch) - octree_viewer.cpp: program name in help text - openni2_viewer.cpp: remove unused variables --- apps/src/openni_klt.cpp | 2 +- common/include/pcl/conversions.h | 4 +-- .../pcl/filters/voxel_grid_covariance.h | 2 +- .../include/pcl/registration/impl/gicp.hpp | 29 ++++++++++--------- .../registration/impl/ppf_registration.hpp | 14 ++++----- .../pcl/segmentation/impl/region_growing.hpp | 8 ++--- .../3rdparty/opennurbs/opennurbs_system.h | 8 ++--- tools/octree_viewer.cpp | 4 +-- tools/openni2_viewer.cpp | 4 --- 9 files changed, 36 insertions(+), 39 deletions(-) diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index 164426ba396..504d40dd665 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -112,7 +112,7 @@ class OpenNIViewer { using CloudConstPtr = typename Cloud::ConstPtr; OpenNIViewer(pcl::Grabber& grabber) - : grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0) + : grabber_(grabber), rgb_data_(nullptr), rgb_data_size_(0), counter_(0) {} void diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 652a1b41b67..6acb023e73b 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -198,10 +198,10 @@ namespace pcl else { // If not, memcpy each group of contiguous fields separately - for (uindex_t row = 0; row < msg.height; ++row) + for (std::size_t row = 0; row < msg.height; ++row) { const std::uint8_t* row_data = msg_data + row * msg.row_step; - for (uindex_t col = 0; col < msg.width; ++col) + for (std::size_t col = 0; col < msg.width; ++col) { const std::uint8_t* msg_data = row_data + col * msg.point_step; for (const detail::FieldMapping& mapping : field_map) diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index e2c815d3cb4..536d18aaba1 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -464,7 +464,7 @@ namespace pcl } // Find k-nearest neighbors in the occupied voxel centroid cloud - Indices k_indices; + Indices k_indices (k); k = kdtree_.nearestKSearch (point, k, k_indices, k_sqr_distances); // Find leaves corresponding to neighbors diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index 35bb8c1a9f9..b3ce37af2f3 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -62,10 +62,8 @@ GeneralizedIterativeClosestPoint::computeCovar } Eigen::Vector3d mean; - pcl::Indices nn_indices; - nn_indices.reserve(k_correspondences_); - std::vector nn_dist_sq; - nn_dist_sq.reserve(k_correspondences_); + pcl::Indices nn_indices(k_correspondences_); + std::vector nn_dist_sq(k_correspondences_); // We should never get there but who knows if (cloud_covariances.size() < cloud->size()) @@ -85,20 +83,23 @@ GeneralizedIterativeClosestPoint::computeCovar // Find the covariance matrix for (int j = 0; j < k_correspondences_; j++) { - const PointT& pt = (*cloud)[nn_indices[j]]; + // de-mean neighbourhood to avoid inaccuracies when far away from origin + const double ptx = (*cloud)[nn_indices[j]].x - query_point.x, + pty = (*cloud)[nn_indices[j]].y - query_point.y, + ptz = (*cloud)[nn_indices[j]].z - query_point.z; - mean[0] += pt.x; - mean[1] += pt.y; - mean[2] += pt.z; + mean[0] += ptx; + mean[1] += pty; + mean[2] += ptz; - cov(0, 0) += pt.x * pt.x; + cov(0, 0) += ptx * ptx; - cov(1, 0) += pt.y * pt.x; - cov(1, 1) += pt.y * pt.y; + cov(1, 0) += pty * ptx; + cov(1, 1) += pty * pty; - cov(2, 0) += pt.z * pt.x; - cov(2, 1) += pt.z * pt.y; - cov(2, 2) += pt.z * pt.z; + cov(2, 0) += ptz * ptx; + cov(2, 1) += ptz * pty; + cov(2, 2) += ptz * ptz; } mean /= static_cast(k_correspondences_); diff --git a/registration/include/pcl/registration/impl/ppf_registration.hpp b/registration/include/pcl/registration/impl/ppf_registration.hpp index 21cff70004c..18c5855605d 100644 --- a/registration/include/pcl/registration/impl/ppf_registration.hpp +++ b/registration/include/pcl/registration/impl/ppf_registration.hpp @@ -83,9 +83,9 @@ pcl::PPFRegistration::computeTransformation( const std::vector tmp_vec(aux_size, 0); std::vector> accumulator_array(input_->size(), tmp_vec); - PCL_INFO("Accumulator array size: %u x %u.\n", - accumulator_array.size(), - accumulator_array.back().size()); + PCL_DEBUG("Accumulator array size: %u x %u.\n", + accumulator_array.size(), + accumulator_array.back().size()); PoseWithVotesList voted_poses; // Consider every -th point as the reference @@ -232,7 +232,7 @@ pcl::PPFRegistration::clusterPoses( typename pcl::PPFRegistration::PoseWithVotesList& poses, typename pcl::PPFRegistration::PoseWithVotesList& result) { - PCL_INFO("Clustering poses ...\n"); + PCL_DEBUG("Clustering poses ...\n"); // Start off by sorting the poses by the number of votes sort(poses.begin(), poses.end(), poseWithVotesCompareFunction); @@ -268,9 +268,9 @@ pcl::PPFRegistration::clusterPoses( result.clear(); std::size_t max_clusters = (clusters.size() < 3) ? clusters.size() : 3; for (std::size_t cluster_i = 0; cluster_i < max_clusters; ++cluster_i) { - PCL_INFO("Winning cluster has #votes: %d and #poses voted: %d.\n", - cluster_votes[cluster_i].second, - clusters[cluster_votes[cluster_i].first].size()); + PCL_DEBUG("Winning cluster has #votes: %d and #poses voted: %d.\n", + cluster_votes[cluster_i].second, + clusters[cluster_votes[cluster_i].first].size()); Eigen::Vector3f translation_average(0.0, 0.0, 0.0); Eigen::Vector4f rotation_average(0.0, 0.0, 0.0, 0.0); for (typename PoseWithVotesList::iterator v_it = diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index 5ed4b03bc01..754ecb14e98 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -351,7 +351,7 @@ pcl::RegionGrowing::findPointNeighbours () { for (int i_point = 0; i_point < point_number; i_point++) { - int point_index = (*indices_)[i_point]; + const auto point_index = (*indices_)[i_point]; neighbours.clear (); search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); point_neighbours_[point_index].swap (neighbours); @@ -362,7 +362,7 @@ pcl::RegionGrowing::findPointNeighbours () for (int i_point = 0; i_point < point_number; i_point++) { neighbours.clear (); - int point_index = (*indices_)[i_point]; + const auto point_index = (*indices_)[i_point]; if (!pcl::isFinite ((*input_)[point_index])) continue; search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); @@ -386,7 +386,7 @@ pcl::RegionGrowing::applySmoothRegionGrowingAlgorithm () { for (int i_point = 0; i_point < num_of_pts; i_point++) { - int point_index = (*indices_)[i_point]; + const auto point_index = (*indices_)[i_point]; point_residual[i_point].first = (*normals_)[point_index].curvature; point_residual[i_point].second = point_index; } @@ -396,7 +396,7 @@ pcl::RegionGrowing::applySmoothRegionGrowingAlgorithm () { for (int i_point = 0; i_point < num_of_pts; i_point++) { - int point_index = (*indices_)[i_point]; + const auto point_index = (*indices_)[i_point]; point_residual[i_point].first = 0; point_residual[i_point].second = point_index; } diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_system.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_system.h index 384e7bac83e..cde07940121 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_system.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_system.h @@ -137,15 +137,15 @@ #if defined(_M_X64) && defined(WIN32) && defined(WIN64) // 23 August 2007 Dale Lear -#if defined(_INC_WINDOWS) +//#if defined(_INC_WINDOWS) // The user has included Microsoft's windows.h before opennurbs.h, // and windows.h has nested includes that unconditionally define WIN32. // Just undo the damage here or everybody that includes opennurbs.h after // windows.h has to fight with this Microsoft bug. #undef WIN32 -#else -#error do not define WIN32 for x64 builds -#endif +//#else +//#error do not define WIN32 for x64 builds +//#endif // NOTE _WIN32 is defined for any type of Windows build #endif diff --git a/tools/octree_viewer.cpp b/tools/octree_viewer.cpp index 7e09b0cb4e3..6381edbed0e 100644 --- a/tools/octree_viewer.cpp +++ b/tools/octree_viewer.cpp @@ -459,8 +459,8 @@ int main(int argc, char ** argv) { if (argc != 3) { - std::cerr << "ERROR: Syntax is octreeVisu " << std::endl; - std::cerr << "EXAMPLE: ./octreeVisu bun0.pcd 0.001" << std::endl; + std::cerr << "ERROR: Syntax is " << argv[0] << " " << std::endl; + std::cerr << "EXAMPLE: ./" << argv[0] << " bun0.pcd 0.001" << std::endl; return -1; } diff --git a/tools/openni2_viewer.cpp b/tools/openni2_viewer.cpp index 7296b4e54d4..24fd15cd79c 100644 --- a/tools/openni2_viewer.cpp +++ b/tools/openni2_viewer.cpp @@ -275,10 +275,6 @@ class OpenNI2Viewer unsigned rgb_data_size_; }; -// Create the PCLVisualizer object -pcl::visualization::PCLVisualizer::Ptr cld; -pcl::visualization::ImageViewer::Ptr img; - /* ---[ */ int main (int argc, char** argv) From 93af010e7931ed3dd8fdafcd7cf238d31e058c0e Mon Sep 17 00:00:00 2001 From: keineahnung2345 Date: Sat, 4 Mar 2023 23:30:51 +0800 Subject: [PATCH 056/288] [octree] use PCL_ERROR instead of assert (#5321) * [refactor] octree: use PCL_ERROR instead of assert * PCL_THROW_EXCEPTION for invalid resolution * revert to assert for min_child_idx * use assert for performance * use assert for performance reason * use assert for performance reason * use assert to circumvent "error: reference to local variable 'node' returned [-Werror=return-local-addr]" * [doc] add doc for child_idx_arg * use more assert * Revert some changes in octree_pointcloud.hpp * Revert some changes * Revert some changes * Re-add include --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- .../pcl/octree/impl/octree2buf_base.hpp | 14 ++++++-- .../include/pcl/octree/impl/octree_base.hpp | 21 ++++++++++-- .../pcl/octree/impl/octree_pointcloud.hpp | 34 ++++++++++++++++--- octree/include/pcl/octree/octree2buf_base.h | 12 +++---- octree/include/pcl/octree/octree_container.h | 4 ++- octree/include/pcl/octree/octree_nodes.h | 7 ++-- octree/include/pcl/octree/octree_pointcloud.h | 12 +++++-- 7 files changed, 82 insertions(+), 22 deletions(-) diff --git a/octree/include/pcl/octree/impl/octree2buf_base.hpp b/octree/include/pcl/octree/impl/octree2buf_base.hpp index 5f939f351ee..5736f06bd6e 100644 --- a/octree/include/pcl/octree/impl/octree2buf_base.hpp +++ b/octree/include/pcl/octree/impl/octree2buf_base.hpp @@ -71,7 +71,12 @@ Octree2BufBase::setMaxVoxelIndex( { uindex_t treeDepth; - assert(max_voxel_index_arg > 0); + if (max_voxel_index_arg <= 0) { + PCL_ERROR("[pcl::octree::Octree2BufBase::setMaxVoxelIndex] Max voxel index (%lu) " + "must be > 0!\n", + max_voxel_index_arg); + return; + } // tree depth == amount of bits of maxVoxels treeDepth = @@ -88,7 +93,12 @@ template void Octree2BufBase::setTreeDepth(uindex_t depth_arg) { - assert(depth_arg > 0); + if (depth_arg <= 0) { + PCL_ERROR( + "[pcl::octree::Octree2BufBase::setTreeDepth] Tree depth (%lu) must be > 0!\n", + depth_arg); + return; + } // set octree depth octree_depth_ = depth_arg; diff --git a/octree/include/pcl/octree/impl/octree_base.hpp b/octree/include/pcl/octree/impl/octree_base.hpp index a8d4b7787a7..3d25960f650 100644 --- a/octree/include/pcl/octree/impl/octree_base.hpp +++ b/octree/include/pcl/octree/impl/octree_base.hpp @@ -71,7 +71,12 @@ OctreeBase::setMaxVoxelIndex( { uindex_t tree_depth; - assert(max_voxel_index_arg > 0); + if (max_voxel_index_arg <= 0) { + PCL_ERROR("[pcl::octree::OctreeBase::setMaxVoxelIndex] Max voxel index (%lu) must " + "be > 0!\n", + max_voxel_index_arg); + return; + } // tree depth == bitlength of maxVoxels tree_depth = @@ -86,8 +91,18 @@ template void OctreeBase::setTreeDepth(uindex_t depth_arg) { - assert(depth_arg > 0); - assert(depth_arg <= OctreeKey::maxDepth); + if (depth_arg <= 0) { + PCL_ERROR("[pcl::octree::OctreeBase::setTreeDepth] Tree depth (%lu) must be > 0!\n", + depth_arg); + return; + } + if (depth_arg > OctreeKey::maxDepth) { + PCL_ERROR("[pcl::octree::OctreeBase::setTreeDepth] Tree depth (%lu) must be <= max " + "depth(%lu)!\n", + depth_arg, + OctreeKey::maxDepth); + return; + } // set octree depth octree_depth_ = depth_arg; diff --git a/octree/include/pcl/octree/impl/octree_pointcloud.hpp b/octree/include/pcl/octree/impl/octree_pointcloud.hpp index 9966e4be463..789cfb0b915 100644 --- a/octree/include/pcl/octree/impl/octree_pointcloud.hpp +++ b/octree/include/pcl/octree/impl/octree_pointcloud.hpp @@ -66,7 +66,11 @@ pcl::octree::OctreePointCloud , bounding_box_defined_(false) , max_objs_per_leaf_(0) { - assert(resolution > 0.0f); + if (resolution <= 0.0) { + PCL_THROW_EXCEPTION(InitFailedException, + "[pcl::octree::OctreePointCloud::OctreePointCloud] Resolution " + << resolution << " must be > 0!"); + } } ////////////////////////////////////////////////////////////////////////////////////////////// @@ -339,7 +343,12 @@ pcl::octree::OctreePointCloud PointT max_pt; // bounding box cannot be changed once the octree contains elements - assert(this->leaf_count_ == 0); + if (this->leaf_count_ != 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) " + "must be 0\n", + this->leaf_count_); + return; + } pcl::getMinMax3D(*input_, min_pt, max_pt); @@ -372,7 +381,12 @@ pcl::octree::OctreePointCloud const double max_z_arg) { // bounding box cannot be changed once the octree contains elements - assert(this->leaf_count_ == 0); + if (this->leaf_count_ != 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) " + "must be 0\n", + this->leaf_count_); + return; + } min_x_ = std::min(min_x_arg, max_x_arg); min_y_ = std::min(min_y_arg, max_y_arg); @@ -400,7 +414,12 @@ pcl::octree::OctreePointCloud const double max_z_arg) { // bounding box cannot be changed once the octree contains elements - assert(this->leaf_count_ == 0); + if (this->leaf_count_ != 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) " + "must be 0\n", + this->leaf_count_); + return; + } min_x_ = std::min(0.0, max_x_arg); min_y_ = std::min(0.0, max_y_arg); @@ -426,7 +445,12 @@ pcl::octree::OctreePointCloud defineBoundingBox(const double cubeLen_arg) { // bounding box cannot be changed once the octree contains elements - assert(this->leaf_count_ == 0); + if (this->leaf_count_ != 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::defineBoundingBox] Leaf count (%lu) " + "must be 0\n", + this->leaf_count_); + return; + } min_x_ = std::min(0.0, cubeLen_arg); min_y_ = std::min(0.0, cubeLen_arg); diff --git a/octree/include/pcl/octree/octree2buf_base.h b/octree/include/pcl/octree/octree2buf_base.h index df5db780562..1589b0303b6 100644 --- a/octree/include/pcl/octree/octree2buf_base.h +++ b/octree/include/pcl/octree/octree2buf_base.h @@ -89,8 +89,8 @@ class BufferedBranchNode : public OctreeNode { } /** \brief Get child pointer in current branch node - * \param buffer_arg: buffer selector - * \param index_arg: index of child in node + * \param buffer_arg: buffer selector, must be less than 2 + * \param index_arg: index of child in node, must be less than 8 * \return pointer to child node */ inline OctreeNode* @@ -101,8 +101,8 @@ class BufferedBranchNode : public OctreeNode { } /** \brief Set child pointer in current branch node - * \param buffer_arg: buffer selector - * \param index_arg: index of child in node + * \param buffer_arg: buffer selector, must be less than 2 + * \param index_arg: index of child in node, must be less than 8 * \param newNode_arg: pointer to new child node */ inline void @@ -115,8 +115,8 @@ class BufferedBranchNode : public OctreeNode { } /** \brief Check if branch is pointing to a particular child node - * \param buffer_arg: buffer selector - * \param index_arg: index of child in node + * \param buffer_arg: buffer selector, must be less than 2 + * \param index_arg: index of child in node, must be less than 8 * \return "true" if pointer to child node exists; "false" otherwise */ inline bool diff --git a/octree/include/pcl/octree/octree_container.h b/octree/include/pcl/octree/octree_container.h index 61384670535..cd549cb6dcb 100644 --- a/octree/include/pcl/octree/octree_container.h +++ b/octree/include/pcl/octree/octree_container.h @@ -38,6 +38,7 @@ #pragma once +#include #include #include @@ -161,7 +162,8 @@ class OctreeContainerEmpty : public OctreeContainerBase { index_t getPointIndex() const override { - assert("getPointIndex: undefined point index"); + PCL_ERROR( + "[pcl::octree::OctreeContainerBase::getPointIndex] Undefined point index!\n"); return -1; } diff --git a/octree/include/pcl/octree/octree_nodes.h b/octree/include/pcl/octree/octree_nodes.h index 447449782a4..d085f0f84a4 100644 --- a/octree/include/pcl/octree/octree_nodes.h +++ b/octree/include/pcl/octree/octree_nodes.h @@ -216,7 +216,7 @@ class OctreeBranchNode : public OctreeNode { ~OctreeBranchNode() override = default; /** \brief Access operator. - * \param child_idx_arg: index to child node + * \param child_idx_arg: index to child node, must be less than 8 * \return OctreeNode pointer * */ inline OctreeNode*& @@ -227,7 +227,7 @@ class OctreeBranchNode : public OctreeNode { } /** \brief Get pointer to child - * \param child_idx_arg: index to child node + * \param child_idx_arg: index to child node, must be less than 8 * \return OctreeNode pointer * */ inline OctreeNode* @@ -238,6 +238,7 @@ class OctreeBranchNode : public OctreeNode { } /** \brief Get pointer to child + * \param index: index to child node, must be less than 8 * \return OctreeNode pointer * */ inline void @@ -248,7 +249,7 @@ class OctreeBranchNode : public OctreeNode { } /** \brief Check if branch is pointing to a particular child node - * \param child_idx_arg: index to child node + * \param child_idx_arg: index to child node, must be less than 8 * \return "true" if pointer to child node exists; "false" otherwise * */ inline bool diff --git a/octree/include/pcl/octree/octree_pointcloud.h b/octree/include/pcl/octree/octree_pointcloud.h index de6c58fcdce..76fa60c656c 100644 --- a/octree/include/pcl/octree/octree_pointcloud.h +++ b/octree/include/pcl/octree/octree_pointcloud.h @@ -164,7 +164,11 @@ class OctreePointCloud : public OctreeT { setResolution(double resolution_arg) { // octree needs to be empty to change its resolution - assert(this->leaf_count_ == 0); + if (this->leaf_count_ > 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::setResolution] Octree needs to be " + "empty to change its resolution(leaf count should must be 0)!\n"); + return; + } resolution_ = resolution_arg; @@ -416,7 +420,11 @@ class OctreePointCloud : public OctreeT { inline void enableDynamicDepth(std::size_t maxObjsPerLeaf) { - assert(this->leaf_count_ == 0); + if (this->leaf_count_ > 0) { + PCL_ERROR("[pcl::octree::OctreePointCloud::enableDynamicDepth] Leaf count should " + "must be 0!\n"); + return; + } max_objs_per_leaf_ = maxObjsPerLeaf; this->dynamic_depth_enabled_ = max_objs_per_leaf_ > 0; From c828af828a4c3242a1f76f14547b8f391205e34e Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sun, 12 Mar 2023 20:55:37 +0100 Subject: [PATCH 057/288] Build only release for host-triplet (#5614) * Add host-triplet to only build release version for host dependencies. --- .dev/docker/windows/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index 44fbd8aca62..f8be7aaa059 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -48,4 +48,4 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm RUN cd .\vcpkg; ` .\bootstrap-vcpkg.bat; ` - .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --clean-after-build; + .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build; From 30124ee1ab5518a5cc7d03a186c46caf9aa99513 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Mon, 13 Mar 2023 02:04:03 -0700 Subject: [PATCH 058/288] clang-tidy: add modernize-make-unique and modernize-use-noexcept (#5618) * Streamlined modernize clang-tidy checks * Fixed clang-tidy escapes * Reverted to explicit check list per review * Commented odd-looking use of this-> * Reverted explicit this-> per review * Reverted this-> qualifier, changed per review --- .clang-tidy | 2 + common/include/pcl/exceptions.h | 8 +-- .../include/pcl/filters/impl/grid_minimum.hpp | 2 +- filters/src/voxel_grid_label.cpp | 2 +- io/include/pcl/io/io_exception.h | 2 +- .../pcl/io/openni_camera/openni_depth_image.h | 36 +++++----- .../pcl/io/openni_camera/openni_device.h | 68 +++++++++---------- .../io/openni_camera/openni_device_kinect.h | 10 +-- .../pcl/io/openni_camera/openni_device_oni.h | 12 ++-- .../openni_camera/openni_device_primesense.h | 4 +- .../io/openni_camera/openni_device_xtion.h | 4 +- .../pcl/io/openni_camera/openni_driver.h | 20 +++--- .../pcl/io/openni_camera/openni_exception.h | 8 +-- .../pcl/io/openni_camera/openni_image.h | 22 +++--- .../openni_camera/openni_image_bayer_grbg.h | 4 +- .../pcl/io/openni_camera/openni_ir_image.h | 20 +++--- io/src/io_exception.cpp | 2 +- io/src/openni_camera/openni_device.cpp | 52 +++++++------- io/src/openni_camera/openni_device_kinect.cpp | 6 +- io/src/openni_camera/openni_device_oni.cpp | 12 ++-- .../openni_device_primesense.cpp | 4 +- io/src/openni_camera/openni_device_xtion.cpp | 4 +- io/src/openni_camera/openni_driver.cpp | 16 ++--- io/src/openni_camera/openni_exception.cpp | 8 +-- io/src/ply_io.cpp | 2 +- .../pcl/surface/impl/grid_projection.hpp | 2 +- surface/include/pcl/surface/impl/mls.hpp | 10 +-- 27 files changed, 173 insertions(+), 169 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 35542031548..86977bd23a9 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -6,6 +6,7 @@ Checks: > google-readability-casting, modernize-deprecated-headers, modernize-loop-convert, + modernize-make-unique, modernize-redundant-void-arg, modernize-replace-random-shuffle, modernize-return-braced-init-list, @@ -14,6 +15,7 @@ Checks: > modernize-use-emplace, modernize-use-equals-default, modernize-use-equals-delete, + modernize-use-noexcept, modernize-use-nullptr, modernize-use-override, modernize-use-using, diff --git a/common/include/pcl/exceptions.h b/common/include/pcl/exceptions.h index 5053d887c04..3814839c89c 100644 --- a/common/include/pcl/exceptions.h +++ b/common/include/pcl/exceptions.h @@ -78,25 +78,25 @@ namespace pcl {} const char* - getFileName () const throw () + getFileName () const noexcept { return (file_name_); } const char* - getFunctionName () const throw () + getFunctionName () const noexcept { return (function_name_); } unsigned - getLineNumber () const throw () + getLineNumber () const noexcept { return (line_number_); } const char* - detailedMessage () const throw () + detailedMessage () const noexcept { return (what ()); } diff --git a/filters/include/pcl/filters/impl/grid_minimum.hpp b/filters/include/pcl/filters/impl/grid_minimum.hpp index 7b0b1915c71..fdb515d7b64 100644 --- a/filters/include/pcl/filters/impl/grid_minimum.hpp +++ b/filters/include/pcl/filters/impl/grid_minimum.hpp @@ -135,7 +135,7 @@ pcl::GridMinimum::applyFilterIndices (Indices &indices) // Second pass: sort the index_vector vector using value representing target cell as index // in effect all points belonging to the same output cell will be next to each other - std::sort (index_vector.begin (), index_vector.end (), std::less ()); + std::sort (index_vector.begin (), index_vector.end (), std::less<> ()); // Third pass: count output cells // we need to skip all the same, adjacenent idx values diff --git a/filters/src/voxel_grid_label.cpp b/filters/src/voxel_grid_label.cpp index a7f3f08c3ce..13dd7cdfdb4 100644 --- a/filters/src/voxel_grid_label.cpp +++ b/filters/src/voxel_grid_label.cpp @@ -189,7 +189,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) // Second pass: sort the index_vector vector using value representing target cell as index // in effect all points belonging to the same output cell will be next to each other - std::sort (index_vector.begin (), index_vector.end (), std::less ()); + std::sort (index_vector.begin (), index_vector.end (), std::less<> ()); // Third pass: count output cells // we need to skip all the same, adjacenent idx values diff --git a/io/include/pcl/io/io_exception.h b/io/include/pcl/io/io_exception.h index 156f32d4723..b80897317ba 100644 --- a/io/include/pcl/io/io_exception.h +++ b/io/include/pcl/io/io_exception.h @@ -73,7 +73,7 @@ namespace pcl operator= (const IOException& exception); const char* - what () const throw () override; + what () const noexcept override; const std::string& getFunctionName () const; diff --git a/io/include/pcl/io/openni_camera/openni_depth_image.h b/io/include/pcl/io/openni_camera/openni_depth_image.h index 40bb47ef269..c318fc9473b 100644 --- a/io/include/pcl/io/openni_camera/openni_depth_image.h +++ b/io/include/pcl/io/openni_camera/openni_depth_image.h @@ -77,7 +77,7 @@ namespace openni_wrapper * \return the actual depth data of type xn::DepthMetaData. */ inline const xn::DepthMetaData& - getDepthMetaData () const throw (); + getDepthMetaData () const noexcept; /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling. * \param[in] width the width of the desired disparity image. @@ -113,46 +113,46 @@ namespace openni_wrapper * \return baseline in meters */ inline float - getBaseline () const throw (); + getBaseline () const noexcept; /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image. * \return focal length in pixels */ inline float - getFocalLength () const throw (); + getFocalLength () const noexcept; /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image. * \return shadow value */ inline XnUInt64 - getShadowValue () const throw (); + getShadowValue () const noexcept; /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image. * \return no-sample value */ inline XnUInt64 - getNoSampleValue () const throw (); + getNoSampleValue () const noexcept; /** \return the width of the depth image */ inline unsigned - getWidth () const throw (); + getWidth () const noexcept; /** \return the height of the depth image */ inline unsigned - getHeight () const throw (); + getHeight () const noexcept; /** \return an ascending id for the depth frame * \attention not necessarily synchronized with other streams */ inline unsigned - getFrameID () const throw (); + getFrameID () const noexcept; /** \return a ascending timestamp for the depth frame * \attention its not the system time, thus can not be used directly to synchronize different sensors. * But definitely synchronized with other streams */ inline unsigned long - getTimeStamp () const throw (); + getTimeStamp () const noexcept; protected: pcl::shared_ptr depth_md_; @@ -172,55 +172,55 @@ namespace openni_wrapper DepthImage::~DepthImage () noexcept = default; const xn::DepthMetaData& - DepthImage::getDepthMetaData () const throw () + DepthImage::getDepthMetaData () const noexcept { return *depth_md_; } float - DepthImage::getBaseline () const throw () + DepthImage::getBaseline () const noexcept { return baseline_; } float - DepthImage::getFocalLength () const throw () + DepthImage::getFocalLength () const noexcept { return focal_length_; } XnUInt64 - DepthImage::getShadowValue () const throw () + DepthImage::getShadowValue () const noexcept { return shadow_value_; } XnUInt64 - DepthImage::getNoSampleValue () const throw () + DepthImage::getNoSampleValue () const noexcept { return no_sample_value_; } unsigned - DepthImage::getWidth () const throw () + DepthImage::getWidth () const noexcept { return depth_md_->XRes (); } unsigned - DepthImage::getHeight () const throw () + DepthImage::getHeight () const noexcept { return depth_md_->YRes (); } unsigned - DepthImage::getFrameID () const throw () + DepthImage::getFrameID () const noexcept { return depth_md_->FrameID (); } unsigned long - DepthImage::getTimeStamp () const throw () + DepthImage::getTimeStamp () const noexcept { return static_cast (depth_md_->Timestamp ()); } diff --git a/io/include/pcl/io/openni_camera/openni_device.h b/io/include/pcl/io/openni_camera/openni_device.h index 7115de514c0..4c80eef91e6 100644 --- a/io/include/pcl/io/openni_camera/openni_device.h +++ b/io/include/pcl/io/openni_camera/openni_device.h @@ -98,7 +98,7 @@ namespace openni_wrapper * \return true, if a compatible mode could be found, false otherwise. */ bool - findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (); + findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const noexcept; /** \brief finds a depth output mode that can be used to retrieve depth images in desired output mode. * e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possible by downsampling, @@ -108,39 +108,39 @@ namespace openni_wrapper * \return true, if a compatible mode could be found, false otherwise. */ bool - findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (); + findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const noexcept; /** \brief returns whether a given mode is natively supported by the device or not * \param[in] output_mode mode to be checked * \return true if mode natively available, false otherwise */ bool - isImageModeSupported (const XnMapOutputMode& output_mode) const throw (); + isImageModeSupported (const XnMapOutputMode& output_mode) const noexcept; /** \brief returns whether a given mode is natively supported by the device or not * \param[in] output_mode mode to be checked * \return true if mode natively available, false otherwise */ bool - isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (); + isDepthModeSupported (const XnMapOutputMode& output_mode) const noexcept; /** \brief returns the default image mode, which is simply the first entry in the list of modes * \return the default image mode */ const XnMapOutputMode& - getDefaultImageMode () const throw (); + getDefaultImageMode () const noexcept; /** \brief returns the default depth mode, which is simply the first entry in the list of modes * \return the default depth mode */ const XnMapOutputMode& - getDefaultDepthMode () const throw (); + getDefaultDepthMode () const noexcept; /** \brief returns the default IR mode, which is simply the first entry in the list of modes * \return the default IR mode */ const XnMapOutputMode& - getDefaultIRMode () const throw (); + getDefaultIRMode () const noexcept; /** \brief sets the output mode of the image stream * \param[in] output_mode the desired output mode @@ -180,11 +180,11 @@ namespace openni_wrapper /** \return whether the depth stream is registered to the RGB camera fram or not. */ bool - isDepthRegistered () const throw (); + isDepthRegistered () const noexcept; /** \return whether a registration of the depth stream to the RGB camera frame is supported or not. */ bool - isDepthRegistrationSupported () const throw (); + isDepthRegistrationSupported () const noexcept; /** \brief set the hardware synchronization between Depth and RGB stream on or off. * \param[in] on_off @@ -194,11 +194,11 @@ namespace openni_wrapper /** \return true if Depth stream is synchronized to RGB stream, false otherwise. */ bool - isSynchronized () const throw (); + isSynchronized () const noexcept; /** \return true if the Device supports hardware synchronization between Depth and RGB streams or not. */ virtual bool - isSynchronizationSupported () const throw (); + isSynchronizationSupported () const noexcept; /** \return true if depth stream is a cropped version of the native depth stream, false otherwise. */ bool @@ -215,23 +215,23 @@ namespace openni_wrapper /** \return true if cropping of the depth stream is supported, false otherwise. */ bool - isDepthCroppingSupported () const throw (); + isDepthCroppingSupported () const noexcept; /** \brief returns the focal length for the color camera in pixels. The pixels are assumed to be square. * Result depends on the output resolution of the image. */ inline float - getImageFocalLength (int output_x_resolution = 0) const throw (); + getImageFocalLength (int output_x_resolution = 0) const noexcept; /** \brief returns the focal length for the IR camera in pixels. The pixels are assumed to be square. * Result depends on the output resolution of the depth image. */ inline float - getDepthFocalLength (int output_x_resolution = 0) const throw (); + getDepthFocalLength (int output_x_resolution = 0) const noexcept; /** \return Baseline of the "stereo" frame. i.e. for PSDK compatible devices its the distance between the Projector and the IR camera. */ inline float - getBaseline () const throw (); + getBaseline () const noexcept; /** \brief starts the image stream. */ virtual void @@ -259,27 +259,27 @@ namespace openni_wrapper /** \return true if the device supports an image stream, false otherwise. */ bool - hasImageStream () const throw (); + hasImageStream () const noexcept; /** \return true if the device supports a depth stream, false otherwise. */ bool - hasDepthStream () const throw (); + hasDepthStream () const noexcept; /** \return true if the device supports an IR stream, false otherwise. */ bool - hasIRStream () const throw (); + hasIRStream () const noexcept; /** \return true if the image stream is running / started, false otherwise. */ virtual bool - isImageStreamRunning () const throw (); + isImageStreamRunning () const noexcept; /** \return true if the depth stream is running / started, false otherwise. */ virtual bool - isDepthStreamRunning () const throw (); + isDepthStreamRunning () const noexcept; /** \return true if the IR stream is running / started, false otherwise. */ virtual bool - isIRStreamRunning () const throw (); + isIRStreamRunning () const noexcept; /** \brief registers a callback function of std::function type for the image stream with an optional user defined parameter. * The callback will always be called with a new image and the user data "cookie". @@ -367,35 +367,35 @@ namespace openni_wrapper * \attention This might be an empty string!!! */ const char* - getSerialNumber () const throw (); + getSerialNumber () const noexcept; /** \brief returns the connection string for current device, which has following format vendorID/productID\@BusID/DeviceID. */ const char* - getConnectionString () const throw (); + getConnectionString () const noexcept; /** \return the Vendor name of the USB device. */ const char* - getVendorName () const throw (); + getVendorName () const noexcept; /** \return the product name of the USB device. */ const char* - getProductName () const throw (); + getProductName () const noexcept; /** \return the vendor ID of the USB device. */ unsigned short - getVendorID () const throw (); + getVendorID () const noexcept; /** \return the product ID of the USB device. */ unsigned short - getProductID () const throw (); + getProductID () const noexcept; /** \return the USB bus on which the device is connected. */ unsigned char - getBus () const throw (); + getBus () const noexcept; /** \return the USB Address of the device. */ unsigned char - getAddress () const throw (); + getAddress () const noexcept; /** \brief Set the RGB image focal length. * \param[in] focal_length the RGB image focal length @@ -469,13 +469,13 @@ namespace openni_wrapper IRDataThreadFunction (); virtual bool - isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0; + isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept = 0; void setRegistration (bool on_off); virtual Image::Ptr - getCurrentImage (pcl::shared_ptr image_data) const throw () = 0; + getCurrentImage (pcl::shared_ptr image_data) const noexcept = 0; void Init (); @@ -560,7 +560,7 @@ namespace openni_wrapper //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// float - OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw () + OpenNIDevice::getImageFocalLength (int output_x_resolution) const noexcept { if (output_x_resolution == 0) output_x_resolution = getImageOutputMode ().nXRes; @@ -571,7 +571,7 @@ namespace openni_wrapper //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// float - OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw () + OpenNIDevice::getDepthFocalLength (int output_x_resolution) const noexcept { if (output_x_resolution == 0) output_x_resolution = getDepthOutputMode ().nXRes; @@ -584,7 +584,7 @@ namespace openni_wrapper //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// float - OpenNIDevice::getBaseline () const throw () + OpenNIDevice::getBaseline () const noexcept { return (baseline_); } diff --git a/io/include/pcl/io/openni_camera/openni_device_kinect.h b/io/include/pcl/io/openni_camera/openni_device_kinect.h index 00c4d82fe92..9d7f2d37202 100644 --- a/io/include/pcl/io/openni_camera/openni_device_kinect.h +++ b/io/include/pcl/io/openni_camera/openni_device_kinect.h @@ -61,14 +61,14 @@ namespace openni_wrapper ~DeviceKinect () noexcept override; inline void setDebayeringMethod (const ImageBayerGRBG::DebayeringMethod& debayering_method) noexcept; - inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const throw (); + inline const ImageBayerGRBG::DebayeringMethod& getDebayeringMethod () const noexcept; - bool isSynchronizationSupported () const throw () override; + bool isSynchronizationSupported () const noexcept override; protected: - Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const throw () override; + Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const noexcept override; void enumAvailableModes () noexcept; - bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override; + bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override; ImageBayerGRBG::DebayeringMethod debayering_method_; } ; @@ -79,7 +79,7 @@ namespace openni_wrapper } const ImageBayerGRBG::DebayeringMethod& - DeviceKinect::getDebayeringMethod () const throw () + DeviceKinect::getDebayeringMethod () const noexcept { return debayering_method_; } diff --git a/io/include/pcl/io/openni_camera/openni_device_oni.h b/io/include/pcl/io/openni_camera/openni_device_oni.h index 31519eb89a0..f4cc8ff9f1e 100644 --- a/io/include/pcl/io/openni_camera/openni_device_oni.h +++ b/io/include/pcl/io/openni_camera/openni_device_oni.h @@ -77,11 +77,11 @@ namespace openni_wrapper void startIRStream () override; void stopIRStream () override; - bool isImageStreamRunning () const throw () override; - bool isDepthStreamRunning () const throw () override; - bool isIRStreamRunning () const throw () override; + bool isImageStreamRunning () const noexcept override; + bool isDepthStreamRunning () const noexcept override; + bool isIRStreamRunning () const noexcept override; - bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override; + bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override; /** \brief Trigger a new frame in the ONI stream. * \param[in] relative_offset the relative offset in case we want to seek in the file @@ -89,7 +89,7 @@ namespace openni_wrapper bool trigger (int relative_offset = 0); - bool isStreaming () const throw (); + bool isStreaming () const noexcept; /** \brief Check if there is any data left in the ONI file to process. */ inline bool @@ -99,7 +99,7 @@ namespace openni_wrapper } protected: - Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const throw () override; + Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const noexcept override; void PlayerThreadFunction (); static void __stdcall NewONIDepthDataAvailable (xn::ProductionNode& node, void* cookie) noexcept; diff --git a/io/include/pcl/io/openni_camera/openni_device_primesense.h b/io/include/pcl/io/openni_camera/openni_device_primesense.h index 4d22640f8fa..1727b459746 100644 --- a/io/include/pcl/io/openni_camera/openni_device_primesense.h +++ b/io/include/pcl/io/openni_camera/openni_device_primesense.h @@ -63,9 +63,9 @@ class DevicePrimesense : public OpenNIDevice //virtual void setImageOutputMode (const XnMapOutputMode& output_mode); protected: - Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const throw () override; + Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const noexcept override; void enumAvailableModes () noexcept; - bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override; + bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override; void startImageStream () override; void startDepthStream () override; diff --git a/io/include/pcl/io/openni_camera/openni_device_xtion.h b/io/include/pcl/io/openni_camera/openni_device_xtion.h index ad8d71746be..27ee8fa12b9 100644 --- a/io/include/pcl/io/openni_camera/openni_device_xtion.h +++ b/io/include/pcl/io/openni_camera/openni_device_xtion.h @@ -65,9 +65,9 @@ namespace openni_wrapper //virtual void setImageOutputMode (const XnMapOutputMode& output_mode); protected: - Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const throw () override; + Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const noexcept override; void enumAvailableModes () noexcept; - bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () override; + bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override; void startDepthStream () override; } ; diff --git a/io/include/pcl/io/openni_camera/openni_driver.h b/io/include/pcl/io/openni_camera/openni_driver.h index 747461e1c8d..3ba7692c3e4 100644 --- a/io/include/pcl/io/openni_camera/openni_driver.h +++ b/io/include/pcl/io/openni_camera/openni_driver.h @@ -89,7 +89,7 @@ namespace openni_wrapper * @author Suat Gedikli * @return the number of available devices. */ - inline unsigned getNumberDevices () const throw (); + inline unsigned getNumberDevices () const noexcept; /** * @author Suat Gedikli @@ -134,7 +134,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the serial number of the device. */ - const char* getSerialNumber (unsigned index) const throw (); + const char* getSerialNumber (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -142,7 +142,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the connection string of the device. */ - const char* getConnectionString (unsigned index) const throw (); + const char* getConnectionString (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -150,7 +150,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the vendor name of the USB device. */ - const char* getVendorName (unsigned index) const throw (); + const char* getVendorName (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -158,7 +158,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the product name of the USB device. */ - const char* getProductName (unsigned index) const throw (); + const char* getProductName (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -166,7 +166,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the vendor id of the USB device. */ - unsigned short getVendorID (unsigned index) const throw (); + unsigned short getVendorID (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -174,7 +174,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the product id of the USB device. */ - unsigned short getProductID (unsigned index) const throw (); + unsigned short getProductID (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -182,7 +182,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the bus id of the USB device. */ - unsigned char getBus (unsigned index) const throw (); + unsigned char getBus (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -190,7 +190,7 @@ namespace openni_wrapper * @param[in] index the index of the device in the device list. * @return the address of the USB device. */ - unsigned char getAddress (unsigned index) const throw (); + unsigned char getAddress (unsigned index) const noexcept; /** * @author Suat Gedikli @@ -245,7 +245,7 @@ namespace openni_wrapper } unsigned - OpenNIDriver::getNumberDevices () const throw () + OpenNIDriver::getNumberDevices () const noexcept { return static_cast (device_context_.size ()); } diff --git a/io/include/pcl/io/openni_camera/openni_exception.h b/io/include/pcl/io/openni_camera/openni_exception.h index e0e3789ebf1..85e0f19a328 100644 --- a/io/include/pcl/io/openni_camera/openni_exception.h +++ b/io/include/pcl/io/openni_camera/openni_exception.h @@ -93,22 +93,22 @@ namespace openni_wrapper * @brief virtual method, derived from std::exception * @return the message of the exception. */ - const char* what () const throw () override; + const char* what () const noexcept override; /** * @return the function name in which the exception was created. */ - const std::string& getFunctionName () const throw (); + const std::string& getFunctionName () const noexcept; /** * @return the filename in which the exception was created. */ - const std::string& getFileName () const throw (); + const std::string& getFileName () const noexcept; /** * @return the line number where the exception was created. */ - unsigned getLineNumber () const throw (); + unsigned getLineNumber () const noexcept; protected: std::string function_name_; std::string file_name_; diff --git a/io/include/pcl/io/openni_camera/openni_image.h b/io/include/pcl/io/openni_camera/openni_image.h index 1a3c4b2c67b..f42f884f527 100644 --- a/io/include/pcl/io/openni_camera/openni_image.h +++ b/io/include/pcl/io/openni_camera/openni_image.h @@ -116,7 +116,7 @@ namespace openni_wrapper * @param[in,out] rgb_buffer */ inline void - fillRaw (unsigned char* rgb_buffer) const throw () + fillRaw (unsigned char* rgb_buffer) const noexcept { memcpy (rgb_buffer, image_md_->Data (), image_md_->DataSize ()); } @@ -136,33 +136,33 @@ namespace openni_wrapper * @author Suat Gedikli * @return width of the image */ - inline unsigned getWidth () const throw (); + inline unsigned getWidth () const noexcept; /** * @author Suat Gedikli * @return height of the image */ - inline unsigned getHeight () const throw (); + inline unsigned getHeight () const noexcept; /** * @author Suat Gedikli * @return frame id of the image. * @note frame ids are ascending, but not necessarily synch'ed with other streams */ - inline unsigned getFrameID () const throw (); + inline unsigned getFrameID () const noexcept; /** * @author Suat Gedikli * @return the time stamp of the image * @note the time value is not synche'ed with the system time */ - inline unsigned long getTimeStamp () const throw (); + inline unsigned long getTimeStamp () const noexcept; /** * @author Suat Gedikli * @return the actual data in native OpenNI format. */ - inline const xn::ImageMetaData& getMetaData () const throw (); + inline const xn::ImageMetaData& getMetaData () const noexcept; protected: pcl::shared_ptr image_md_; @@ -176,31 +176,31 @@ namespace openni_wrapper Image::~Image () noexcept = default; unsigned - Image::getWidth () const throw () + Image::getWidth () const noexcept { return image_md_->XRes (); } unsigned - Image::getHeight () const throw () + Image::getHeight () const noexcept { return image_md_->YRes (); } unsigned - Image::getFrameID () const throw () + Image::getFrameID () const noexcept { return image_md_->FrameID (); } unsigned long - Image::getTimeStamp () const throw () + Image::getTimeStamp () const noexcept { return static_cast (image_md_->Timestamp ()); } const xn::ImageMetaData& - Image::getMetaData () const throw () + Image::getMetaData () const noexcept { return *image_md_; } diff --git a/io/include/pcl/io/openni_camera/openni_image_bayer_grbg.h b/io/include/pcl/io/openni_camera/openni_image_bayer_grbg.h index 052387f7d32..cd09c26338e 100644 --- a/io/include/pcl/io/openni_camera/openni_image_bayer_grbg.h +++ b/io/include/pcl/io/openni_camera/openni_image_bayer_grbg.h @@ -74,7 +74,7 @@ namespace openni_wrapper void fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step = 0) const override; bool isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const override; inline void setDebayeringMethod (const DebayeringMethod& method) noexcept; - inline DebayeringMethod getDebayeringMethod () const throw (); + inline DebayeringMethod getDebayeringMethod () const noexcept; inline static bool resizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height); @@ -89,7 +89,7 @@ namespace openni_wrapper } ImageBayerGRBG::DebayeringMethod - ImageBayerGRBG::getDebayeringMethod () const throw () + ImageBayerGRBG::getDebayeringMethod () const noexcept { return debayering_method_; } diff --git a/io/include/pcl/io/openni_camera/openni_ir_image.h b/io/include/pcl/io/openni_camera/openni_ir_image.h index 7320ef61339..e06b4bab4d5 100644 --- a/io/include/pcl/io/openni_camera/openni_ir_image.h +++ b/io/include/pcl/io/openni_camera/openni_ir_image.h @@ -59,11 +59,11 @@ class PCL_EXPORTS IRImage void fillRaw (unsigned width, unsigned height, unsigned short* ir_buffer, unsigned line_step = 0) const; - inline unsigned getWidth () const throw (); - inline unsigned getHeight () const throw (); - inline unsigned getFrameID () const throw (); - inline unsigned long getTimeStamp () const throw (); - inline const xn::IRMetaData& getMetaData () const throw (); + inline unsigned getWidth () const noexcept; + inline unsigned getHeight () const noexcept; + inline unsigned getFrameID () const noexcept; + inline unsigned long getTimeStamp () const noexcept; + inline const xn::IRMetaData& getMetaData () const noexcept; protected: pcl::shared_ptr ir_md_; @@ -76,27 +76,27 @@ IRImage::IRImage (pcl::shared_ptr ir_meta_data) noexcept IRImage::~IRImage () noexcept = default; -unsigned IRImage::getWidth () const throw () +unsigned IRImage::getWidth () const noexcept { return ir_md_->XRes (); } -unsigned IRImage::getHeight () const throw () +unsigned IRImage::getHeight () const noexcept { return ir_md_->YRes (); } -unsigned IRImage::getFrameID () const throw () +unsigned IRImage::getFrameID () const noexcept { return ir_md_->FrameID (); } -unsigned long IRImage::getTimeStamp () const throw () +unsigned long IRImage::getTimeStamp () const noexcept { return static_cast (ir_md_->Timestamp ()); } -const xn::IRMetaData& IRImage::getMetaData () const throw () +const xn::IRMetaData& IRImage::getMetaData () const noexcept { return *ir_md_; } diff --git a/io/src/io_exception.cpp b/io/src/io_exception.cpp index b0fdaa61abb..f41e72fdbc5 100644 --- a/io/src/io_exception.cpp +++ b/io/src/io_exception.cpp @@ -57,7 +57,7 @@ pcl::io::IOException::operator = (const IOException& exception) } const char* -pcl::io::IOException::what () const throw () +pcl::io::IOException::what () const noexcept { return (message_long_.c_str ()); } diff --git a/io/src/openni_camera/openni_device.cpp b/io/src/openni_camera/openni_device.cpp index fbd195c7b7b..928906542ca 100644 --- a/io/src/openni_camera/openni_device.cpp +++ b/io/src/openni_camera/openni_device.cpp @@ -611,7 +611,7 @@ openni_wrapper::OpenNIDevice::stopIRStream () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isImageStreamRunning () const throw () +openni_wrapper::OpenNIDevice::isImageStreamRunning () const noexcept { std::lock_guard image_lock (image_mutex_); return (image_generator_.IsValid () && image_generator_.IsGenerating ()); @@ -619,7 +619,7 @@ openni_wrapper::OpenNIDevice::isImageStreamRunning () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isDepthStreamRunning () const throw () +openni_wrapper::OpenNIDevice::isDepthStreamRunning () const noexcept { std::lock_guard depth_lock (depth_mutex_); return (depth_generator_.IsValid () && depth_generator_.IsGenerating ()); @@ -627,7 +627,7 @@ openni_wrapper::OpenNIDevice::isDepthStreamRunning () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isIRStreamRunning () const throw () +openni_wrapper::OpenNIDevice::isIRStreamRunning () const noexcept { std::lock_guard ir_lock (ir_mutex_); return (ir_generator_.IsValid () && ir_generator_.IsGenerating ()); @@ -635,7 +635,7 @@ openni_wrapper::OpenNIDevice::isIRStreamRunning () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::hasImageStream () const throw () +openni_wrapper::OpenNIDevice::hasImageStream () const noexcept { std::lock_guard lock (image_mutex_); return (image_generator_.IsValid () != 0); @@ -644,7 +644,7 @@ openni_wrapper::OpenNIDevice::hasImageStream () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::hasDepthStream () const throw () +openni_wrapper::OpenNIDevice::hasDepthStream () const noexcept { std::lock_guard lock (depth_mutex_); return (depth_generator_.IsValid () != 0); @@ -653,7 +653,7 @@ openni_wrapper::OpenNIDevice::hasDepthStream () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::hasIRStream () const throw () +openni_wrapper::OpenNIDevice::hasIRStream () const noexcept { std::lock_guard ir_lock (ir_mutex_); return (ir_generator_.IsValid () != 0); @@ -692,7 +692,7 @@ openni_wrapper::OpenNIDevice::setDepthRegistration (bool on_off) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isDepthRegistered () const throw () +openni_wrapper::OpenNIDevice::isDepthRegistered () const noexcept { if (hasDepthStream () && hasImageStream() ) { @@ -708,7 +708,7 @@ openni_wrapper::OpenNIDevice::isDepthRegistered () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const throw () +openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const noexcept { std::lock_guard image_lock (image_mutex_); std::lock_guard depth_lock (depth_mutex_); @@ -718,7 +718,7 @@ openni_wrapper::OpenNIDevice::isDepthRegistrationSupported () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isSynchronizationSupported () const throw () +openni_wrapper::OpenNIDevice::isSynchronizationSupported () const noexcept { std::lock_guard image_lock (image_mutex_); std::lock_guard depth_lock (depth_mutex_); @@ -754,7 +754,7 @@ openni_wrapper::OpenNIDevice::setSynchronization (bool on_off) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isSynchronized () const throw () +openni_wrapper::OpenNIDevice::isSynchronized () const noexcept { if (hasDepthStream () && hasImageStream()) { @@ -769,7 +769,7 @@ openni_wrapper::OpenNIDevice::isSynchronized () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isDepthCroppingSupported () const throw () +openni_wrapper::OpenNIDevice::isDepthCroppingSupported () const noexcept { std::lock_guard depth_lock (depth_mutex_); return (image_generator_.IsValid() && depth_generator_.IsCapabilitySupported (XN_CAPABILITY_CROPPING) ); @@ -975,21 +975,21 @@ openni_wrapper::OpenNIDevice::unregisterIRCallback (const OpenNIDevice::Callback ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDevice::getSerialNumber () const throw () +openni_wrapper::OpenNIDevice::getSerialNumber () const noexcept { return (device_node_info_.GetInstanceName ()); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDevice::getConnectionString () const throw () +openni_wrapper::OpenNIDevice::getConnectionString () const noexcept { return (device_node_info_.GetCreationInfo ()); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned short -openni_wrapper::OpenNIDevice::getVendorID () const throw () +openni_wrapper::OpenNIDevice::getVendorID () const noexcept { unsigned short vendor_id; unsigned short product_id; @@ -1008,7 +1008,7 @@ openni_wrapper::OpenNIDevice::getVendorID () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned short -openni_wrapper::OpenNIDevice::getProductID () const throw () +openni_wrapper::OpenNIDevice::getProductID () const noexcept { unsigned short vendor_id; unsigned short product_id; @@ -1025,7 +1025,7 @@ openni_wrapper::OpenNIDevice::getProductID () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned char -openni_wrapper::OpenNIDevice::getBus () const throw () +openni_wrapper::OpenNIDevice::getBus () const noexcept { unsigned char bus = 0; #ifndef _WIN32 @@ -1039,7 +1039,7 @@ openni_wrapper::OpenNIDevice::getBus () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned char -openni_wrapper::OpenNIDevice::getAddress () const throw () +openni_wrapper::OpenNIDevice::getAddress () const noexcept { unsigned char address = 0; #ifndef _WIN32 @@ -1053,7 +1053,7 @@ openni_wrapper::OpenNIDevice::getAddress () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDevice::getVendorName () const throw () +openni_wrapper::OpenNIDevice::getVendorName () const noexcept { auto& description = const_cast(device_node_info_.GetDescription ()); return (description.strVendor); @@ -1061,7 +1061,7 @@ openni_wrapper::OpenNIDevice::getVendorName () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDevice::getProductName () const throw () +openni_wrapper::OpenNIDevice::getProductName () const noexcept { auto& description = const_cast(device_node_info_.GetDescription ()); return (description.strName); @@ -1069,7 +1069,7 @@ openni_wrapper::OpenNIDevice::getProductName () const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw () +openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const noexcept { if (isImageModeSupported (output_mode)) { @@ -1098,7 +1098,7 @@ openni_wrapper::OpenNIDevice::findCompatibleImageMode (const XnMapOutputMode& ou ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const throw () +openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode) const noexcept { if (isDepthModeSupported (output_mode)) { @@ -1127,7 +1127,7 @@ openni_wrapper::OpenNIDevice::findCompatibleDepthMode (const XnMapOutputMode& ou ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const throw () +openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& output_mode) const noexcept { for (const auto &available_image_mode : available_image_modes_) { @@ -1139,7 +1139,7 @@ openni_wrapper::OpenNIDevice::isImageModeSupported (const XnMapOutputMode& outpu ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const throw () +openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& output_mode) const noexcept { for (const auto &available_depth_mode : available_depth_modes_) { @@ -1151,21 +1151,21 @@ openni_wrapper::OpenNIDevice::isDepthModeSupported (const XnMapOutputMode& outpu ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const XnMapOutputMode& -openni_wrapper::OpenNIDevice::getDefaultImageMode () const throw () +openni_wrapper::OpenNIDevice::getDefaultImageMode () const noexcept { return (available_image_modes_[0]); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const XnMapOutputMode& -openni_wrapper::OpenNIDevice::getDefaultDepthMode () const throw () +openni_wrapper::OpenNIDevice::getDefaultDepthMode () const noexcept { return (available_depth_modes_[0]); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const XnMapOutputMode& -openni_wrapper::OpenNIDevice::getDefaultIRMode () const throw () +openni_wrapper::OpenNIDevice::getDefaultIRMode () const noexcept { /// @todo Something else here? return (available_depth_modes_[0]); diff --git a/io/src/openni_camera/openni_device_kinect.cpp b/io/src/openni_camera/openni_device_kinect.cpp index fee348e6ac2..36e229d3d43 100644 --- a/io/src/openni_camera/openni_device_kinect.cpp +++ b/io/src/openni_camera/openni_device_kinect.cpp @@ -53,7 +53,7 @@ namespace openni_wrapper ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceKinect::isSynchronizationSupported () const throw () +openni_wrapper::DeviceKinect::isSynchronizationSupported () const noexcept { return (false); } @@ -105,7 +105,7 @@ openni_wrapper::DeviceKinect::~DeviceKinect () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () +openni_wrapper::DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept { return (ImageBayerGRBG::resizingSupported (input_width, input_height, output_width, output_height)); } @@ -132,7 +132,7 @@ openni_wrapper::DeviceKinect::enumAvailableModes () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// openni_wrapper::Image::Ptr -openni_wrapper::DeviceKinect::getCurrentImage (pcl::shared_ptr image_data) const throw () +openni_wrapper::DeviceKinect::getCurrentImage (pcl::shared_ptr image_data) const noexcept { return (Image::Ptr (new ImageBayerGRBG (image_data, debayering_method_))); } diff --git a/io/src/openni_camera/openni_device_oni.cpp b/io/src/openni_camera/openni_device_oni.cpp index 6006649e526..94e3bfdac59 100644 --- a/io/src/openni_camera/openni_device_oni.cpp +++ b/io/src/openni_camera/openni_device_oni.cpp @@ -161,21 +161,21 @@ openni_wrapper::DeviceONI::stopIRStream () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceONI::isImageStreamRunning () const throw () +openni_wrapper::DeviceONI::isImageStreamRunning () const noexcept { return (image_stream_running_); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceONI::isDepthStreamRunning () const throw () +openni_wrapper::DeviceONI::isDepthStreamRunning () const noexcept { return (depth_stream_running_); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceONI::isIRStreamRunning () const throw () +openni_wrapper::DeviceONI::isIRStreamRunning () const noexcept { return (ir_stream_running_); } @@ -205,7 +205,7 @@ openni_wrapper::DeviceONI::trigger (int relative_offset) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceONI::isStreaming () const throw () +openni_wrapper::DeviceONI::isStreaming () const noexcept { return (streaming_); } @@ -248,14 +248,14 @@ openni_wrapper::DeviceONI::NewONIIRDataAvailable (xn::ProductionNode&, void* coo ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// openni_wrapper::Image::Ptr -openni_wrapper::DeviceONI::getCurrentImage(pcl::shared_ptr image_meta_data) const throw () +openni_wrapper::DeviceONI::getCurrentImage(pcl::shared_ptr image_meta_data) const noexcept { return (openni_wrapper::Image::Ptr (new openni_wrapper::ImageRGB24 (image_meta_data))); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () +openni_wrapper::DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept { return (openni_wrapper::ImageRGB24::resizingSupported (input_width, input_height, output_width, output_height)); } diff --git a/io/src/openni_camera/openni_device_primesense.cpp b/io/src/openni_camera/openni_device_primesense.cpp index 20072c47cf7..c0f66a26f7d 100644 --- a/io/src/openni_camera/openni_device_primesense.cpp +++ b/io/src/openni_camera/openni_device_primesense.cpp @@ -102,7 +102,7 @@ openni_wrapper::DevicePrimesense::isImageResizeSupported ( unsigned input_width, unsigned input_height, unsigned output_width, - unsigned output_height) const throw () + unsigned output_height) const noexcept { return (ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height)); } @@ -170,7 +170,7 @@ openni_wrapper::DevicePrimesense::enumAvailableModes () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// openni_wrapper::Image::Ptr -openni_wrapper::DevicePrimesense::getCurrentImage (pcl::shared_ptr image_data) const throw () +openni_wrapper::DevicePrimesense::getCurrentImage (pcl::shared_ptr image_data) const noexcept { return (openni_wrapper::Image::Ptr (new ImageYUV422 (image_data))); } diff --git a/io/src/openni_camera/openni_device_xtion.cpp b/io/src/openni_camera/openni_device_xtion.cpp index 56925743cf3..f65d20fa25d 100644 --- a/io/src/openni_camera/openni_device_xtion.cpp +++ b/io/src/openni_camera/openni_device_xtion.cpp @@ -73,7 +73,7 @@ openni_wrapper::DeviceXtionPro::~DeviceXtionPro () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// bool -openni_wrapper::DeviceXtionPro::isImageResizeSupported (unsigned, unsigned, unsigned, unsigned) const throw () +openni_wrapper::DeviceXtionPro::isImageResizeSupported (unsigned, unsigned, unsigned, unsigned) const noexcept { return (false); } @@ -115,7 +115,7 @@ openni_wrapper::DeviceXtionPro::enumAvailableModes () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// openni_wrapper::Image::Ptr -openni_wrapper::DeviceXtionPro::getCurrentImage (pcl::shared_ptr) const throw () +openni_wrapper::DeviceXtionPro::getCurrentImage (pcl::shared_ptr) const noexcept { return (Image::Ptr (reinterpret_cast (0))); } diff --git a/io/src/openni_camera/openni_driver.cpp b/io/src/openni_camera/openni_driver.cpp index f561f28ec15..11e50769a2a 100644 --- a/io/src/openni_camera/openni_driver.cpp +++ b/io/src/openni_camera/openni_driver.cpp @@ -406,7 +406,7 @@ openni_wrapper::OpenNIDriver::getDeviceInfos () noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDriver::getSerialNumber (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getSerialNumber (unsigned index) const noexcept { #ifndef _WIN32 return (device_context_[index].device_node.GetInstanceName ()); @@ -457,28 +457,28 @@ openni_wrapper::OpenNIDriver::getDeviceType (const std::string& connectionString ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDriver::getConnectionString (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getConnectionString (unsigned index) const noexcept { return (device_context_[index].device_node.GetCreationInfo ()); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDriver::getVendorName (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getVendorName (unsigned index) const noexcept { return (device_context_[index].device_node.GetDescription ().strVendor); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// const char* -openni_wrapper::OpenNIDriver::getProductName (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getProductName (unsigned index) const noexcept { return (device_context_[index].device_node.GetDescription ().strName); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned short -openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const noexcept { unsigned short vendor_id; unsigned short product_id; @@ -495,7 +495,7 @@ openni_wrapper::OpenNIDriver::getVendorID (unsigned index) const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned short -openni_wrapper::OpenNIDriver::getProductID (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getProductID (unsigned index) const noexcept { unsigned short vendor_id; unsigned short product_id; @@ -512,7 +512,7 @@ openni_wrapper::OpenNIDriver::getProductID (unsigned index) const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned char -openni_wrapper::OpenNIDriver::getBus (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getBus (unsigned index) const noexcept { unsigned char bus = 0; #ifndef _WIN32 @@ -526,7 +526,7 @@ openni_wrapper::OpenNIDriver::getBus (unsigned index) const throw () ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// unsigned char -openni_wrapper::OpenNIDriver::getAddress (unsigned index) const throw () +openni_wrapper::OpenNIDriver::getAddress (unsigned index) const noexcept { unsigned char address = 0; #ifndef _WIN32 diff --git a/io/src/openni_camera/openni_exception.cpp b/io/src/openni_camera/openni_exception.cpp index bfc39583fd1..2887f5b6201 100644 --- a/io/src/openni_camera/openni_exception.cpp +++ b/io/src/openni_camera/openni_exception.cpp @@ -62,22 +62,22 @@ OpenNIException& OpenNIException::operator = (const OpenNIException& exception) return *this; } -const char* OpenNIException::what () const throw () +const char* OpenNIException::what () const noexcept { return message_long_.c_str(); } -const std::string& OpenNIException::getFunctionName () const throw () +const std::string& OpenNIException::getFunctionName () const noexcept { return function_name_; } -const std::string& OpenNIException::getFileName () const throw () +const std::string& OpenNIException::getFileName () const noexcept { return file_name_; } -unsigned OpenNIException::getLineNumber () const throw () +unsigned OpenNIException::getLineNumber () const noexcept { return line_number_; } diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 4df171ab587..14735a5af6f 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -358,7 +358,7 @@ namespace pcl cloud_->point_step = static_cast (std::numeric_limits::max ()); do_resize_ = true; return std::tuple, std::function, std::function > ( - std::bind (&pcl::PLYReader::vertexListPropertyBeginCallback, this, property_name, std::placeholders::_1), + [this, property_name](SizeType size) { this->vertexListPropertyBeginCallback(property_name, size); }, [this] (ContentType value) { vertexListPropertyContentCallback (value); }, [this] { vertexListPropertyEndCallback (); } ); diff --git a/surface/include/pcl/surface/impl/grid_projection.hpp b/surface/include/pcl/surface/impl/grid_projection.hpp index 8ebc8ae1e71..7264ff26af6 100644 --- a/surface/include/pcl/surface/impl/grid_projection.hpp +++ b/surface/include/pcl/surface/impl/grid_projection.hpp @@ -640,7 +640,7 @@ pcl::GridProjection::reconstructPolygons (std::vector &p cell_data.data_indices.push_back (cp); getCellCenterFromIndex (index_3d, cell_data.pt_on_surface); cell_hash_map_[index_1d] = cell_data; - occupied_cell_list_[index_1d] = 1; + occupied_cell_list_[index_1d] = true; } else { diff --git a/surface/include/pcl/surface/impl/mls.hpp b/surface/include/pcl/surface/impl/mls.hpp index e13a8af9d08..8f5a3fb82e6 100644 --- a/surface/include/pcl/surface/impl/mls.hpp +++ b/surface/include/pcl/surface/impl/mls.hpp @@ -40,18 +40,20 @@ #ifndef PCL_SURFACE_IMPL_MLS_H_ #define PCL_SURFACE_IMPL_MLS_H_ -#include -#include +#include #include // for getMinMax3D #include -#include #include #include // for KdTree #include // for OrganizedNeighbor +#include +#include #include // for cross #include // for inverse +#include + #ifdef _OPENMP #include #endif @@ -117,7 +119,7 @@ pcl::MovingLeastSquares::process (PointCloudOut &output) std::random_device rd; rng_.seed (rd()); const double tmp = search_radius_ / 2.0; - rng_uniform_distribution_.reset (new std::uniform_real_distribution<> (-tmp, tmp)); + rng_uniform_distribution_ = std::make_unique> (-tmp, tmp); break; } From 0120b475c2b143953f231d14c95fd7cc6766e9bd Mon Sep 17 00:00:00 2001 From: Destranix Date: Fri, 24 Mar 2023 12:10:10 +0100 Subject: [PATCH 059/288] fixes #5640 --- filters/include/pcl/filters/plane_clipper3D.h | 2 +- filters/include/pcl/filters/uniform_sampling.h | 2 +- filters/include/pcl/filters/voxel_grid.h | 2 +- filters/include/pcl/filters/voxel_grid_occlusion_estimation.h | 2 +- .../include/pcl/gpu/kinfu_large_scale/point_intensity.h | 2 +- registration/include/pcl/registration/gicp.h | 2 +- .../include/pcl/registration/incremental_registration.h | 2 +- registration/include/pcl/registration/vertex_estimates.h | 2 +- test/common/test_transforms.cpp | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/filters/include/pcl/filters/plane_clipper3D.h b/filters/include/pcl/filters/plane_clipper3D.h index 507685bcffb..a886f3bcef9 100644 --- a/filters/include/pcl/filters/plane_clipper3D.h +++ b/filters/include/pcl/filters/plane_clipper3D.h @@ -54,7 +54,7 @@ namespace pcl using Ptr = shared_ptr< PlaneClipper3D >; using ConstPtr = shared_ptr< const PlaneClipper3D >; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW /** * @author Suat Gedikli diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index 18d0f046314..896d7b6e927 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -71,7 +71,7 @@ namespace pcl using Ptr = shared_ptr >; using ConstPtr = shared_ptr >; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW /** \brief Empty constructor. */ UniformSampling (bool extract_removed_indices = false) : diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 1f06d46d4cd..517c4d11bae 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -190,7 +190,7 @@ namespace pcl using Ptr = shared_ptr >; using ConstPtr = shared_ptr >; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW /** \brief Empty constructor. */ VoxelGrid () : diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index cac545941e9..ffa585ee614 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -67,7 +67,7 @@ namespace pcl public: - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW /** \brief Empty constructor. */ VoxelGridOcclusionEstimation () diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h index 97e1f6098a0..6880239de89 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/point_intensity.h @@ -47,7 +47,7 @@ struct EIGEN_ALIGN16 PointIntensity { - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW union { struct diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 6694098469e..2eae855abbf 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -113,7 +113,7 @@ class GeneralizedIterativeClosestPoint typename IterativeClosestPoint::Matrix4; using AngleAxis = typename Eigen::AngleAxis; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW /** \brief Empty constructor. */ GeneralizedIterativeClosestPoint() diff --git a/registration/include/pcl/registration/incremental_registration.h b/registration/include/pcl/registration/incremental_registration.h index a3f035d190f..ad928d8729f 100644 --- a/registration/include/pcl/registration/incremental_registration.h +++ b/registration/include/pcl/registration/incremental_registration.h @@ -111,7 +111,7 @@ class IncrementalRegistration { /** \brief Set registration instance used to align clouds */ inline void setRegistration(RegistrationPtr); - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW protected: /** \brief last registered point cloud */ diff --git a/registration/include/pcl/registration/vertex_estimates.h b/registration/include/pcl/registration/vertex_estimates.h index 4131cffd87d..7bdebcad606 100644 --- a/registration/include/pcl/registration/vertex_estimates.h +++ b/registration/include/pcl/registration/vertex_estimates.h @@ -65,7 +65,7 @@ struct PoseEstimate { : pose(p), cloud(c) {} - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace registration } // namespace pcl diff --git a/test/common/test_transforms.cpp b/test/common/test_transforms.cpp index 9b131c0a986..36f4a62deed 100644 --- a/test/common/test_transforms.cpp +++ b/test/common/test_transforms.cpp @@ -105,7 +105,7 @@ class Transforms : public ::testing::Test // Indices, every second point Indices indices; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW }; TYPED_TEST_SUITE (Transforms, TransformTypes); From 07ef7ee40180b8d4c57e20ecb5fc4dc8801a78ff Mon Sep 17 00:00:00 2001 From: Rasmus Date: Mon, 3 Apr 2023 20:08:03 +0200 Subject: [PATCH 060/288] Improved manual registration (#5530) * Prevent crash on macosx * Guard QVTKOpenGLWindow.h inclusion and usage behind VTK version detection * fix vtk-qt crash on macos for manual_registration app * Apply suggestions from code review * Make the manual_registration program actually display the registration * Add iterative refinement * Extend pcl_manual_registration with visual aides and alignment inspection popup * Remove the usage of timers to reduce unnecessary load and re-rendering. Remove unused variables. * Use GICP instead of ICP * Rm unused filters build dependency for pcl_manual_registration * manual_registration now accepts voxel size as 3rd cmdline parameter * manual_registration: simplify logging of computed transforms * Remove dead code from manual_registration.ui * Apply formatting fixes --------- Co-authored-by: Lars Glud --- apps/CMakeLists.txt | 9 +- apps/include/pcl/apps/manual_registration.h | 62 +++----- apps/include/pcl/apps/pcl_viewer_dialog.h | 34 +++++ .../manual_registration.cpp | 139 +++++++++++------- .../manual_registration.ui | 16 +- .../manual_registration/pcl_viewer_dialog.cpp | 49 ++++++ .../manual_registration/pcl_viewer_dialog.ui | 38 +++++ 7 files changed, 233 insertions(+), 114 deletions(-) create mode 100644 apps/include/pcl/apps/pcl_viewer_dialog.h create mode 100644 apps/src/manual_registration/pcl_viewer_dialog.cpp create mode 100644 apps/src/manual_registration/pcl_viewer_dialog.ui diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index 85ae4a2dac8..4c88a7ab121 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -85,10 +85,13 @@ if(VTK_FOUND) ${SUBSYS_NAME} SOURCES include/pcl/apps/manual_registration.h + include/pcl/apps/pcl_viewer_dialog.h src/manual_registration/manual_registration.cpp + src/manual_registration/pcl_viewer_dialog.cpp src/manual_registration/manual_registration.ui + src/manual_registration/pcl_viewer_dialog.ui BUNDLE) - + target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets) PCL_ADD_EXECUTABLE(pcl_pcd_video_player @@ -99,7 +102,7 @@ if(VTK_FOUND) src/pcd_video_player/pcd_video_player.cpp src/pcd_video_player/pcd_video_player.ui BUNDLE) - + target_link_libraries(pcl_pcd_video_player pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets) endif() @@ -163,7 +166,7 @@ if(VTK_FOUND) include/pcl/apps/openni_passthrough.h src/openni_passthrough.cpp src/openni_passthrough.ui) - + target_link_libraries(pcl_openni_passthrough pcl_common pcl_io pcl_filters pcl_visualization ${QTX}::Widgets) list(APPEND CMAKE_AUTOUIC_SEARCH_PATHS "src") diff --git a/apps/include/pcl/apps/manual_registration.h b/apps/include/pcl/apps/manual_registration.h index 466c230645f..d8421e32bbc 100644 --- a/apps/include/pcl/apps/manual_registration.h +++ b/apps/include/pcl/apps/manual_registration.h @@ -46,24 +46,7 @@ #include #include -using PointT = pcl::PointXYZRGBA; - -// Useful macros -// clang-format off -#define FPS_CALC(_WHAT_) \ - do { \ - static unsigned count = 0; \ - static double last = pcl::getTime(); \ - double now = pcl::getTime(); \ - ++count; \ - if (now - last >= 1.0) { \ - std::cout << "Average framerate(" << _WHAT_ << "): " \ - << double(count) / double(now - last) << " Hz" << std::endl; \ - count = 0; \ - last = now; \ - } \ - } while (false) -// clang-format on +using PointT = pcl::PointXYZ; namespace Ui { class MainWindow; @@ -76,25 +59,27 @@ class ManualRegistration : public QMainWindow { using CloudPtr = Cloud::Ptr; using CloudConstPtr = Cloud::ConstPtr; - ManualRegistration(); + PCL_MAKE_ALIGNED_OPERATOR_NEW; + + ManualRegistration(float voxel_size); ~ManualRegistration() override = default; void - setSrcCloud(pcl::PointCloud::Ptr cloud_src) + setSrcCloud(pcl::PointCloud::Ptr cloud_src) { cloud_src_ = std::move(cloud_src); - cloud_src_present_ = true; + vis_src_->addPointCloud(cloud_src_, "cloud_src_"); } void - setDstCloud(pcl::PointCloud::Ptr cloud_dst) + setDstCloud(pcl::PointCloud::Ptr cloud_dst) { cloud_dst_ = std::move(cloud_dst); - cloud_dst_present_ = true; + vis_dst_->addPointCloud(cloud_dst_, "cloud_dst_"); } void - SourcePointPickCallback(const pcl::visualization::PointPickingEvent& event, void*); + SrcPointPickCallback(const pcl::visualization::PointPickingEvent& event, void*); void DstPointPickCallback(const pcl::visualization::PointPickingEvent& event, void*); @@ -105,21 +90,15 @@ class ManualRegistration : public QMainWindow { pcl::visualization::PCLVisualizer::Ptr vis_src_; pcl::visualization::PCLVisualizer::Ptr vis_dst_; - pcl::PointCloud::Ptr cloud_src_; - pcl::PointCloud::Ptr cloud_dst_; + pcl::PointCloud::Ptr cloud_src_; + pcl::PointCloud::Ptr cloud_dst_; QMutex mtx_; QMutex vis_mtx_; Ui::MainWindow* ui_; - QTimer* vis_timer_; - - bool cloud_src_present_; - bool cloud_src_modified_; - bool cloud_dst_present_; - bool cloud_dst_modified_; - bool src_point_selected_; - bool dst_point_selected_; + bool src_point_selected_{false}; + bool dst_point_selected_{false}; pcl::PointXYZ src_point_; pcl::PointXYZ dst_point_; @@ -127,7 +106,12 @@ class ManualRegistration : public QMainWindow { pcl::PointCloud src_pc_; pcl::PointCloud dst_pc_; - Eigen::Matrix4f transform_; + Eigen::Matrix4f transform_ = Eigen::Affine3f::Identity().matrix(); + + std::set annotations_src_; + std::set annotations_dst_; + + const float voxel_size_; public Q_SLOTS: void @@ -144,12 +128,4 @@ public Q_SLOTS: applyTransformPressed(); void refinePressed(); - void - undoPressed(); - void - safePressed(); - -private Q_SLOTS: - void - timeoutSlot(); }; diff --git a/apps/include/pcl/apps/pcl_viewer_dialog.h b/apps/include/pcl/apps/pcl_viewer_dialog.h new file mode 100644 index 00000000000..0a3cff7df22 --- /dev/null +++ b/apps/include/pcl/apps/pcl_viewer_dialog.h @@ -0,0 +1,34 @@ +#pragma once +#include +#include +#include + +#include + +#include +#include + +using CloudT = pcl::PointCloud; + +namespace Ui { +class PCLViewerDialogUi; +} + +class PCLViewerDialog : public QDialog { + Q_OBJECT + Ui::PCLViewerDialogUi* ui_; + pcl::visualization::PCLVisualizer::Ptr vis_; + +public: + PCLViewerDialog(QWidget* parent = 0); + + void + setPointClouds(CloudT::ConstPtr src_cloud, + CloudT::ConstPtr tgt_cloud, + const Eigen::Affine3f& t); + +public Q_SLOTS: + + void + refreshView(); +}; diff --git a/apps/src/manual_registration/manual_registration.cpp b/apps/src/manual_registration/manual_registration.cpp index 8dff3b9b5df..fde1a6f189f 100644 --- a/apps/src/manual_registration/manual_registration.cpp +++ b/apps/src/manual_registration/manual_registration.cpp @@ -39,7 +39,10 @@ */ #include +#include +#include #include // for loadPCDFile +#include #include #include @@ -59,16 +62,13 @@ #include using namespace pcl; +using namespace pcl::visualization; +using std::string; +using std::to_string; ////////////////////////////////////////////////////////////////////////////////////////////////////////// -ManualRegistration::ManualRegistration() +ManualRegistration::ManualRegistration(float voxel_size) : voxel_size_(voxel_size) { - // Create a timer - vis_timer_ = new QTimer(this); - vis_timer_->start(5); // 5ms - - connect(vis_timer_, SIGNAL(timeout()), this, SLOT(timeoutSlot())); - ui_ = new Ui::MainWindow; ui_->setupUi(this); @@ -91,7 +91,7 @@ ManualRegistration::ManualRegistration() vis_src_->getInteractorStyle()->setKeyboardModifier( pcl::visualization::INTERACTOR_KB_MOD_SHIFT); - vis_src_->registerPointPickingCallback(&ManualRegistration::SourcePointPickCallback, + vis_src_->registerPointPickingCallback(&ManualRegistration::SrcPointPickCallback, *this); // Set up the destination window @@ -133,15 +133,10 @@ ManualRegistration::ManualRegistration() this, SLOT(applyTransformPressed())); connect(ui_->refineButton, SIGNAL(clicked()), this, SLOT(refinePressed())); - connect(ui_->undoButton, SIGNAL(clicked()), this, SLOT(undoPressed())); - connect(ui_->safeButton, SIGNAL(clicked()), this, SLOT(safePressed())); - - cloud_src_modified_ = true; // first iteration is always a new pointcloud - cloud_dst_modified_ = true; } void -ManualRegistration::SourcePointPickCallback( +ManualRegistration::SrcPointPickCallback( const pcl::visualization::PointPickingEvent& event, void*) { // Check to see if we got a valid point. Early exit. @@ -186,6 +181,15 @@ ManualRegistration::confirmSrcPointPressed() PCL_INFO("Selected %zu source points\n", static_cast(src_pc_.size())); src_point_selected_ = false; src_pc_.width = src_pc_.size(); + const string annotation = "marker-" + to_string(annotations_src_.size()); + vis_src_->addSphere(src_point_, 0.02, annotation); + vis_src_->setShapeRenderingProperties(PCL_VISUALIZER_OPACITY, 0.2, annotation); + vis_src_->setShapeRenderingProperties( + PCL_VISUALIZER_COLOR, 0.5, 0.25, 0.25, annotation); + vis_src_->getShapeActorMap()->at(annotation)->SetPickable(false); + annotations_src_.emplace(annotation); + + refreshView(); } else { PCL_INFO("Please select a point in the source window first\n"); @@ -201,6 +205,16 @@ ManualRegistration::confirmDstPointPressed() static_cast(dst_pc_.size())); dst_point_selected_ = false; dst_pc_.width = dst_pc_.size(); + + const string annotation = "marker-" + std::to_string(annotations_dst_.size()); + vis_dst_->addSphere(dst_point_, 0.02, annotation); + vis_dst_->setShapeRenderingProperties(PCL_VISUALIZER_OPACITY, 0.2, annotation); + vis_dst_->setShapeRenderingProperties( + PCL_VISUALIZER_COLOR, 0.5, 0.25, 0.25, annotation); + vis_dst_->getShapeActorMap()->at(annotation)->SetPickable(false); + annotations_dst_.emplace(annotation); + + refreshView(); } else { PCL_INFO("Please select a point in the destination window first\n"); @@ -216,12 +230,13 @@ ManualRegistration::calculatePressed() } pcl::registration::TransformationEstimationSVD tfe; tfe.estimateRigidTransformation(src_pc_, dst_pc_, transform_); - std::cout << "Transform : " << std::endl << transform_ << std::endl; + PCL_INFO_STREAM("Calculated transform:\n" << transform_ << std::endl); } void ManualRegistration::clearPressed() { + PCL_INFO("Clearing points."); dst_point_selected_ = false; src_point_selected_ = false; src_pc_.clear(); @@ -230,6 +245,18 @@ ManualRegistration::clearPressed() src_pc_.width = 0; dst_pc_.height = 1; dst_pc_.width = 0; + + for (const string& annotation : annotations_src_) { + vis_src_->removeShape(annotation); + } + annotations_src_.clear(); + + for (const string& annotation : annotations_dst_) { + vis_dst_->removeShape(annotation); + } + annotations_dst_.clear(); + + refreshView(); } void @@ -269,38 +296,42 @@ ManualRegistration::orthoChanged(int state) // TODO void ManualRegistration::applyTransformPressed() -{} +{ + PCLViewerDialog* diag = new PCLViewerDialog(this); + diag->setModal(true); + diag->setGeometry(this->x(), this->y(), this->width(), this->height()); + diag->setPointClouds(cloud_src_, cloud_dst_, Eigen::Affine3f(transform_)); + diag->show(); +} void ManualRegistration::refinePressed() -{} - -void -ManualRegistration::undoPressed() -{} - -void -ManualRegistration::safePressed() -{} - -void -ManualRegistration::timeoutSlot() { - if (cloud_src_present_ && cloud_src_modified_) { - if (!vis_src_->updatePointCloud(cloud_src_, "cloud_src_")) { - vis_src_->addPointCloud(cloud_src_, "cloud_src_"); - vis_src_->resetCameraViewpoint("cloud_src_"); - } - cloud_src_modified_ = false; - } - if (cloud_dst_present_ && cloud_dst_modified_) { - if (!vis_dst_->updatePointCloud(cloud_dst_, "cloud_dst_")) { - vis_dst_->addPointCloud(cloud_dst_, "cloud_dst_"); - vis_dst_->resetCameraViewpoint("cloud_dst_"); - } - cloud_dst_modified_ = false; - } - refreshView(); + PCL_INFO("Refining transform ...\n"); + VoxelGrid grid_filter; + grid_filter.setLeafSize(voxel_size_, voxel_size_, voxel_size_); + PointCloud::Ptr src_copy{new PointCloud(*cloud_src_)}; + PointCloud::Ptr dst_copy{new PointCloud(*cloud_dst_)}; + grid_filter.setInputCloud(src_copy); + grid_filter.filter(*src_copy); + grid_filter.setInputCloud(dst_copy); + grid_filter.filter(*dst_copy); + + using ICP = GeneralizedIterativeClosestPoint; + ICP::Ptr icp = pcl::make_shared(); + icp->setInputSource(src_copy); + icp->setInputTarget(dst_copy); + + icp->setMaximumIterations(100); + icp->setMaxCorrespondenceDistance(0.3); + icp->setEuclideanFitnessEpsilon(0.01); + icp->setTransformationEpsilon(0.01); + icp->setTransformationRotationEpsilon(0.01); + PointCloud::Ptr aligned{new PointCloud}; + icp->align(*aligned, transform_); + transform_ = icp->getFinalTransformation(); + + PCL_INFO_STREAM("Calculated transform:\n" << transform_ << std::endl); } void @@ -308,8 +339,10 @@ ManualRegistration::refreshView() { #if VTK_MAJOR_VERSION > 8 ui_->qvtk_widget_dst->renderWindow()->Render(); + ui_->qvtk_widget_src->renderWindow()->Render(); #else ui_->qvtk_widget_dst->update(); + ui_->qvtk_widget_src->update(); #endif // VTK_MAJOR_VERSION > 8 } @@ -319,6 +352,7 @@ print_usage() PCL_INFO("manual_registration cloud1.pcd cloud2.pcd\n"); PCL_INFO("\t cloud1 \t source cloud\n"); PCL_INFO("\t cloud2 \t destination cloud\n"); + PCL_INFO("\t voxel_size \t voxel size for automatic refinement\n"); } int @@ -329,31 +363,30 @@ main(int argc, char** argv) #endif QApplication app(argc, argv); - pcl::PointCloud::Ptr cloud_src( - new pcl::PointCloud); - pcl::PointCloud::Ptr cloud_dst( - new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_src(new pcl::PointCloud); + pcl::PointCloud::Ptr cloud_dst(new pcl::PointCloud); - if (argc < 3) { + if (argc < 4) { PCL_ERROR("Incorrect usage\n"); print_usage(); + return -1; } // TODO do this with PCL console - if (pcl::io::loadPCDFile(argv[1], *cloud_src) == - -1) //* load the file + if (pcl::io::loadPCDFile(argv[1], *cloud_src) == -1) //* load the file { PCL_ERROR("Couldn't read file %s \n", argv[1]); return -1; } - if (pcl::io::loadPCDFile(argv[2], *cloud_dst) == - -1) //* load the file + if (pcl::io::loadPCDFile(argv[2], *cloud_dst) == -1) //* load the file { PCL_ERROR("Couldn't read file %s \n", argv[2]); return -1; } - ManualRegistration man_reg; + const float voxel_size = std::atof(argv[3]); + + ManualRegistration man_reg(voxel_size); man_reg.setSrcCloud(cloud_src); man_reg.setDstCloud(cloud_dst); diff --git a/apps/src/manual_registration/manual_registration.ui b/apps/src/manual_registration/manual_registration.ui index 1d4032f3715..f695cf763b8 100644 --- a/apps/src/manual_registration/manual_registration.ui +++ b/apps/src/manual_registration/manual_registration.ui @@ -96,24 +96,10 @@ - - - - Safe Transform - - - - - - - Undo - - - - OrthoGraphic + Orthographic diff --git a/apps/src/manual_registration/pcl_viewer_dialog.cpp b/apps/src/manual_registration/pcl_viewer_dialog.cpp new file mode 100644 index 00000000000..f1dd1fb0e18 --- /dev/null +++ b/apps/src/manual_registration/pcl_viewer_dialog.cpp @@ -0,0 +1,49 @@ +#include + +#include + +#include +#include + +using namespace pcl::visualization; + +PCLViewerDialog::PCLViewerDialog(QWidget* parent) : QDialog(parent) +{ + ui_ = new Ui::PCLViewerDialogUi; + ui_->setupUi(this); + + // Set up the source window +#if VTK_MAJOR_VERSION > 8 + auto renderer = vtkSmartPointer::New(); + auto renderWindow = vtkSmartPointer::New(); + renderWindow->AddRenderer(renderer); + vis_.reset(new pcl::visualization::PCLVisualizer(renderer, renderWindow, "", false)); +#else + vis_.reset(new pcl::visualization::PCLVisualizer("", false)); +#endif // VTK_MAJOR_VERSION > 8 + setRenderWindowCompat(*(ui_->qvtk_widget), *(vis_->getRenderWindow())); + vis_->setupInteractor(getInteractorCompat(*(ui_->qvtk_widget)), + getRenderWindowCompat(*(ui_->qvtk_widget))); +} +void +PCLViewerDialog::setPointClouds(CloudT::ConstPtr src_cloud, + CloudT::ConstPtr tgt_cloud, + const Eigen::Affine3f& t) +{ + vis_->addPointCloud(tgt_cloud, "cloud_dst_"); + vis_->addPointCloud(src_cloud, "cloud_src_"); + vis_->updatePointCloudPose("cloud_src_", t); + vis_->setPointCloudRenderingProperties(PCL_VISUALIZER_COLOR, 1, 0, 0, "cloud_src_"); + + refreshView(); +} + +void +PCLViewerDialog::refreshView() +{ +#if VTK_MAJOR_VERSION > 8 + ui_->qvtk_widget->renderWindow()->Render(); +#else + ui_->qvtk_widget->update(); +#endif // VTK_MAJOR_VERSION > 8 +} diff --git a/apps/src/manual_registration/pcl_viewer_dialog.ui b/apps/src/manual_registration/pcl_viewer_dialog.ui new file mode 100644 index 00000000000..cc45c862a2f --- /dev/null +++ b/apps/src/manual_registration/pcl_viewer_dialog.ui @@ -0,0 +1,38 @@ + + + PCLViewerDialogUi + + + + 0 + + + + + + + + + + + background-color: rgb(0, 0, 0); + + + + + + + + PCLQVTKWidget + QOpenGLWidget +
    pcl/visualization/qvtk_compatibility.h
    +
    + + PCLViewerDialog + QDialog +
    pcl/apps/pcl_viewer_dialog.h
    +
    +
    + + +
    From 472e154237cd268a479355de7320e303833f55dc Mon Sep 17 00:00:00 2001 From: Rasmus Date: Mon, 3 Apr 2023 23:25:27 +0200 Subject: [PATCH 061/288] Add hints for ordering of -matrix arguments for pcl_transform_point_cloud (#5646) Intuitively I would have assumed row by row ordering, but actually you have to use column by column. --- tools/transform_point_cloud.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/transform_point_cloud.cpp b/tools/transform_point_cloud.cpp index af3769a7b01..e7dcfd6b7ae 100644 --- a/tools/transform_point_cloud.cpp +++ b/tools/transform_point_cloud.cpp @@ -60,8 +60,8 @@ printHelp (int, char **argv) print_info (" -quat x,y,z,w = rotation as quaternion\n"); print_info (" -axisangle ax,ay,az,theta = rotation in axis-angle form\n"); print_info (" -scale x,y,z = scale each dimension with these values\n"); - print_info (" -matrix v1,v2,...,v8,v9 = a 3x3 affine transform\n"); - print_info (" -matrix v1,v2,...,v15,v16 = a 4x4 transformation matrix\n"); + print_info (" -matrix v1,v2,...,v8,v9 = a 3x3 affine transform in column-major order\n"); + print_info (" -matrix v1,v2,...,v15,v16 = a 4x4 transformation matrix in column-major order\n"); print_info (" Note: If a rotation is not specified, it will default to no rotation.\n"); print_info (" If redundant or conflicting transforms are specified, then:\n"); print_info (" -axisangle will override -quat\n"); From 26212118dca2bc3f96abfc80d544b6242c3ca298 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 4 Apr 2023 20:48:53 +0200 Subject: [PATCH 062/288] MinCutSegmentation: use correct allocation size, fix segfault Fixes https://github.com/PointCloudLibrary/pcl/issues/5636 --- .../include/pcl/segmentation/impl/min_cut_segmentation.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index 0b390c3b892..0288a260497 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -496,7 +496,7 @@ pcl::MinCutSegmentation::recalculateBinaryPotentials () std::vector< std::set > edge_marker; std::set out_edges_marker; edge_marker.clear (); - edge_marker.resize (indices_->size () + 2, out_edges_marker); + edge_marker.resize (input_->size () + 2, out_edges_marker); for (boost::tie (vertex_iter, vertex_end) = boost::vertices (*graph_); vertex_iter != vertex_end; ++vertex_iter) { From aed1a96908659ad5a39b6f66b58bf9f00e81984f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 5 Apr 2023 20:49:28 +0200 Subject: [PATCH 063/288] Octree: grow in positive direction instead of negative Fixes https://github.com/PointCloudLibrary/pcl/issues/5637 The octree must grow if a point lies outside in (at least) one axis. For each axis, the bounding box may be violated in the lower bound, or upper bound, or neither. Currently, in the last case, the tree will grow in the negative direction. With these changes it will instead grow in the positive direction. This is better because the points will be closer to min_*_, which will lead to smaller errors when computing the key. It is necessary to adapt the GFPFH test because GFPFH uses an octree and the feature is influenced by which octree leafs are occupied exactly. Previously, the test cloud resulted in an octree with bounding box (-108;20)(-104;24)(-72;56), with these changes the bounding box is (-12;20)(-12;20)(-12;20), which makes more sense. I am also not sure how much sense this test makes because the test assignes the class labels more or less randomly, while the paper says they should represent a "geometric primitive" (plane, sphere, ...). --- octree/include/pcl/octree/impl/octree_pointcloud.hpp | 12 ++++++------ test/features/test_pfh_estimation.cpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/octree/include/pcl/octree/impl/octree_pointcloud.hpp b/octree/include/pcl/octree/impl/octree_pointcloud.hpp index 789cfb0b915..6ba8d3aa3fe 100644 --- a/octree/include/pcl/octree/impl/octree_pointcloud.hpp +++ b/octree/include/pcl/octree/impl/octree_pointcloud.hpp @@ -523,9 +523,9 @@ pcl::octree::OctreePointCloud // octree not empty - we add another tree level and thus increase its size by a // factor of 2*2*2 - child_idx = static_cast(((!bUpperBoundViolationX) << 2) | - ((!bUpperBoundViolationY) << 1) | - ((!bUpperBoundViolationZ))); + child_idx = static_cast(((bLowerBoundViolationX) << 2) | + ((bLowerBoundViolationY) << 1) | + ((bLowerBoundViolationZ))); BranchNode* newRootBranch; @@ -538,13 +538,13 @@ pcl::octree::OctreePointCloud octreeSideLen = static_cast(1 << this->octree_depth_) * resolution_; - if (!bUpperBoundViolationX) + if (bLowerBoundViolationX) min_x_ -= octreeSideLen; - if (!bUpperBoundViolationY) + if (bLowerBoundViolationY) min_y_ -= octreeSideLen; - if (!bUpperBoundViolationZ) + if (bLowerBoundViolationZ) min_z_ -= octreeSideLen; // configure tree depth of octree diff --git a/test/features/test_pfh_estimation.cpp b/test/features/test_pfh_estimation.cpp index 563f0ddd732..3575a5b05f1 100644 --- a/test/features/test_pfh_estimation.cpp +++ b/test/features/test_pfh_estimation.cpp @@ -504,7 +504,7 @@ TEST (PCL, GFPFH) PointCloud descriptor; gfpfh.compute (descriptor); - const float ref_values[] = { 1877, 6375, 5361, 14393, 6674, 2471, 2248, 2753, 3117, 4585, 14388, 32407, 15122, 3061, 3202, 794 }; + const float ref_values[] = { 1881, 6378, 5343, 14406, 6726, 2379, 2295, 2724, 3177, 4518, 14283, 32341, 15131, 3195, 3238, 813 }; EXPECT_EQ (descriptor.size (), 1); for (std::size_t i = 0; i < static_cast(descriptor[0].descriptorSize ()); ++i) From 21d4c29f69289301871d3f1338302fd186a22b2b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 6 Apr 2023 20:09:37 +0200 Subject: [PATCH 064/288] Marching cubes: add hint for template parameter --- surface/include/pcl/surface/marching_cubes.h | 1 + surface/include/pcl/surface/marching_cubes_hoppe.h | 1 + surface/include/pcl/surface/marching_cubes_rbf.h | 1 + 3 files changed, 3 insertions(+) diff --git a/surface/include/pcl/surface/marching_cubes.h b/surface/include/pcl/surface/marching_cubes.h index 97296ad05e6..c09c0aafa50 100644 --- a/surface/include/pcl/surface/marching_cubes.h +++ b/surface/include/pcl/surface/marching_cubes.h @@ -356,6 +356,7 @@ namespace pcl * Lorensen W.E., Cline H.E., "Marching cubes: A high resolution 3d surface construction algorithm", * SIGGRAPH '87 * + * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal` * \author Alexandru E. Ichim * \ingroup surface */ diff --git a/surface/include/pcl/surface/marching_cubes_hoppe.h b/surface/include/pcl/surface/marching_cubes_hoppe.h index f1014a7c928..7f66bdd960a 100644 --- a/surface/include/pcl/surface/marching_cubes_hoppe.h +++ b/surface/include/pcl/surface/marching_cubes_hoppe.h @@ -45,6 +45,7 @@ namespace pcl * from tangent planes, proposed by Hoppe et. al. in: * Hoppe H., DeRose T., Duchamp T., MC-Donald J., Stuetzle W., "Surface reconstruction from unorganized points", * SIGGRAPH '92 + * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal` * \author Alexandru E. Ichim * \ingroup surface */ diff --git a/surface/include/pcl/surface/marching_cubes_rbf.h b/surface/include/pcl/surface/marching_cubes_rbf.h index 7a81c7c0fcd..8acaed9b8cc 100644 --- a/surface/include/pcl/surface/marching_cubes_rbf.h +++ b/surface/include/pcl/surface/marching_cubes_rbf.h @@ -49,6 +49,7 @@ namespace pcl * * \note This algorithm in its current implementation may not be suitable for very * large point clouds, due to high memory requirements. + * \tparam PointNT Use `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal` * \author Alexandru E. Ichim * \ingroup surface */ From 88c1209dd6258b6adc1d2e47293af4512d0b0f96 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 7 Apr 2023 20:37:16 +0200 Subject: [PATCH 065/288] io/doc: add overview of file reading and writing functions --- io/io.doxy | 30 +++++++++++++++++++++++++++++- 1 file changed, 29 insertions(+), 1 deletion(-) diff --git a/io/io.doxy b/io/io.doxy index caa55d01928..9e0d3982fd5 100644 --- a/io/io.doxy +++ b/io/io.doxy @@ -4,7 +4,7 @@ \section secIoPresentation Overview The \b pcl_io library contains classes and functions for reading and writing - point cloud data (PCD) files, as well as capturing point clouds from a + files, as well as capturing point clouds from a variety of sensing devices. An introduction to some of these capabilities can be found in the following tutorials: @@ -13,6 +13,34 @@ - Writing PointCloud data to PCD files - The OpenNI Grabber Framework in PCL - Grabbing point clouds from Ensenso cameras + + + + + + + + + + + + +
    Reading from files
    pcl::PointCloudpcl::PCLPointCloud2pcl::PolygonMeshpcl::TextureMesh
    PCD (ASCII/BINARY/COMPRESSED)\link pcl::io::loadPCDFile(const std::string&,pcl::PointCloud&) loadPCDFile \endlink\link pcl::io::loadPCDFile(const std::string&,pcl::PCLPointCloud2&) loadPCDFile \endlink
    PLY (ASCII/BINARY)\link pcl::io::loadPLYFile(const std::string&,pcl::PointCloud&) loadPLYFile \endlink\link pcl::io::loadPLYFile(const std::string&,pcl::PCLPointCloud2&) loadPLYFile \endlink\link pcl::io::loadPLYFile(const std::string&,pcl::PolygonMesh&) loadPLYFile \endlink
    OBJ (ASCII)\link pcl::io::loadOBJFile(const std::string&,pcl::PointCloud&) loadOBJFile \endlink\link pcl::io::loadOBJFile(const std::string&,pcl::PCLPointCloud2&) loadOBJFile \endlink\link pcl::io::loadOBJFile(const std::string&,pcl::PolygonMesh&) loadOBJFile \endlink\link pcl::io::loadOBJFile(const std::string&,pcl::TextureMesh&) loadOBJFile \endlink
    IFS\link pcl::io::loadIFSFile(const std::string&,pcl::PointCloud&) loadIFSFile \endlink\link pcl::io::loadIFSFile(const std::string&,pcl::PCLPointCloud2&) loadIFSFile \endlink\link pcl::io::loadIFSFile(const std::string&,pcl::PolygonMesh&) loadIFSFile \endlink
    STL (ASCII/BINARY)\link pcl::io::loadPolygonFileSTL(const std::string&,pcl::PolygonMesh&) loadPolygonFileSTL \endlink
    VTK\link pcl::io::loadPolygonFileVTK(const std::string&,pcl::PolygonMesh&) loadPolygonFileVTK \endlink
    CSV/ASCIIvia pcl::ASCIIReader
    Automatic format detection\link pcl::io::load(const std::string&,pcl::PointCloud&) load \endlink\link pcl::io::load(const std::string&,pcl::PCLPointCloud2&) load \endlink\link pcl::io::load(const std::string&,pcl::PolygonMesh&) load \endlink\link pcl::io::load(const std::string&,pcl::TextureMesh&) load \endlink
    + + + + + + + + + + + + + + +
    Writing to files
    pcl::PointCloudpcl::PCLPointCloud2pcl::PolygonMeshpcl::TextureMesh
    PCD ASCII\link pcl::io::savePCDFile(const std::string&,const pcl::PointCloud&,bool) savePCDFile \endlink\link pcl::io::savePCDFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,const bool) savePCDFile \endlink
    PCD BINARY\link pcl::io::savePCDFile(const std::string&,const pcl::PointCloud&,bool) savePCDFile \endlink\link pcl::io::savePCDFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,const bool) savePCDFile \endlink
    PCD COMPRESSED\link pcl::io::savePCDFileBinaryCompressed(const std::string&,const pcl::PointCloud&) savePCDFileBinaryCompressed \endlinkvia pcl::PCDWriter
    PLY ASCII\link pcl::io::savePLYFile(const std::string&,const pcl::PointCloud&,bool) savePLYFile \endlink\link pcl::io::savePLYFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,bool,bool) savePLYFile \endlink\link pcl::io::savePLYFile(const std::string&,const pcl::PolygonMesh&,unsigned) savePLYFile \endlink
    PLY BINARY\link pcl::io::savePLYFile(const std::string&,const pcl::PointCloud&,bool) savePLYFile \endlink\link pcl::io::savePLYFile(const std::string&,const pcl::PCLPointCloud2&,const Eigen::Vector4f&,const Eigen::Quaternionf&,bool,bool) savePLYFile \endlink\link pcl::io::savePLYFileBinary(const std::string&,const pcl::PolygonMesh&) savePLYFileBinary \endlink
    OBJ (ASCII)\link pcl::io::saveOBJFile(const std::string&,const pcl::PolygonMesh&,unsigned) saveOBJFile \endlink\link pcl::io::saveOBJFile(const std::string&,const pcl::TextureMesh&,unsigned) saveOBJFile \endlink
    IFS\link pcl::io::saveIFSFile(const std::string&,const pcl::PointCloud&) saveIFSFile \endlink\link pcl::io::saveIFSFile(const std::string&,const pcl::PCLPointCloud2&) saveIFSFile \endlink
    STL (ASCII/BINARY)\link pcl::io::savePolygonFileSTL(const std::string&,const pcl::PolygonMesh&,const bool) savePolygonFileSTL \endlink
    VTK\link pcl::io::saveVTKFile(const std::string&,const pcl::PCLPointCloud2&,unsigned) saveVTKFile \endlink\link pcl::io::saveVTKFile(const std::string&,const pcl::PolygonMesh&,unsigned) saveVTKFile \endlink or \link pcl::io::savePolygonFileVTK(const std::string&,const pcl::PolygonMesh&,const bool) savePolygonFileVTK \endlink
    Automatic format detection\link pcl::io::save(const std::string&,const pcl::PointCloud&) save \endlink\link pcl::io::save(const std::string&,const pcl::PCLPointCloud2&,unsigned) save \endlink\link pcl::io::save(const std::string&,const pcl::PolygonMesh&,unsigned) save \endlink\link pcl::io::save(const std::string&,const pcl::TextureMesh&,unsigned) save \endlink
    PCL is agnostic with respect to the data sources that are used to generate 3D point clouds. While OpenNI-compatible cameras have recently been at the From ff2e760da1d0fbaf900a3fe88bd41c05829699b3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 8 Apr 2023 14:12:14 +0200 Subject: [PATCH 066/288] People: fix segfault in SSE HoG computation Found by running test_people_detection with valgrind --- people/src/hog.cpp | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/people/src/hog.cpp b/people/src/hog.cpp index f4700b6fe1c..c29b48991c2 100644 --- a/people/src/hog.cpp +++ b/people/src/hog.cpp @@ -233,13 +233,35 @@ pcl::people::HOG::gradHist( float *M, float *O, int h, int w, int bin_size, int } // main rows, has top and bottom bins, use SSE for minor speedup for( ; ; y++ ) { - yb0 = static_cast(yb); if(yb0>=hb-1) break; GHinit(); + // We must stop at hb-3, otherwise the SSE functions access memory outside the valid regions + yb0 = static_cast(yb); if(yb0>=(hb-3)) break; GHinit(); _m0=pcl::sse_set(M0[y]); _m1=pcl::sse_set(M1[y]); if(hasLf) { _m=pcl::sse_set(0,0,ms[1],ms[0]); GH(H0+O0[y],_m,_m0); GH(H0+O1[y],_m,_m1); } if(hasRt) { _m=pcl::sse_set(0,0,ms[3],ms[2]); GH(H0+O0[y]+hb,_m,_m0); GH(H0+O1[y]+hb,_m,_m1); } } + for( ; ; y++ ) { // Do the two remaining steps without SSE, just like in the #else case below + yb0 = static_cast(yb); + if(yb0>=hb-1) + break; + GHinit(); + + if(hasLf) + { + H0[O0[y]+1]+=ms[1]*M0[y]; + H0[O1[y]+1]+=ms[1]*M1[y]; + H0[O0[y]]+=ms[0]*M0[y]; + H0[O1[y]]+=ms[0]*M1[y]; + } + if(hasRt) + { + H0[O0[y]+hb+1]+=ms[3]*M0[y]; + H0[O1[y]+hb+1]+=ms[3]*M1[y]; + H0[O0[y]+hb]+=ms[2]*M0[y]; + H0[O1[y]+hb]+=ms[2]*M1[y]; + } + } // final rows, no bottom bin_size for( ; y(yb); GHinit(); From 3b13f59ac8a15cfde15cf8f520605f3453e9f97c Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sun, 16 Apr 2023 20:02:35 +0200 Subject: [PATCH 067/288] Allow compilation with Boost 1.82 (#5668) --- PCLConfig.cmake.in | 2 +- cmake/pcl_find_boost.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 0dd3c4140b5..d3fa589a6d9 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -96,7 +96,7 @@ macro(find_boost) set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" - "1.81.0" "1.81" "1.80.0" "1.80" + "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index 7b7783861b7..016aa2037a9 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -14,7 +14,7 @@ else() endif() set(Boost_ADDITIONAL_VERSIONS - "1.81.0" "1.81" "1.80.0" "1.80" + "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") From 75d96764cc9fd4cb49b7acc40c7a329245d3f4d3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 17 Apr 2023 10:19:10 +0200 Subject: [PATCH 068/288] [apps] Improve pcl_openni_face_detector - setForestFilename sets the filename where the forest will be written to, if trainWithDataProvider is called. So it makes no sense to call setForestFilename here - suggest forest and model files from data repository - check if opening of forest file was successful --- apps/src/face_detection/openni_face_detection.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/apps/src/face_detection/openni_face_detection.cpp b/apps/src/face_detection/openni_face_detection.cpp index 3af6d65961b..5a12081eb6a 100644 --- a/apps/src/face_detection/openni_face_detection.cpp +++ b/apps/src/face_detection/openni_face_detection.cpp @@ -103,8 +103,9 @@ main(int argc, char** argv) int pose_refinement_ = 0; int icp_iterations = 5; - std::string forest_fn = "../data/forests/forest.txt"; - std::string model_path_ = "../data/ply_models/face.pcd"; + // Use for example biwi_face_database from https://github.com/PointCloudLibrary/data + std::string forest_fn = "../data/biwi_face_database/forest_example.txt"; + std::string model_path_ = "../data/biwi_face_database/model.pcd"; pcl::console::parse_argument(argc, argv, "-forest_fn", forest_fn); pcl::console::parse_argument(argc, argv, "-max_variance", trans_max_variance); @@ -119,7 +120,6 @@ main(int argc, char** argv) pcl::console::parse_argument(argc, argv, "-icp_iterations", icp_iterations); pcl::RFFaceDetectorTrainer fdrf; - fdrf.setForestFilename(forest_fn); fdrf.setWSize(80); fdrf.setUseNormals(static_cast(use_normals)); fdrf.setWStride(STRIDE_SW); @@ -134,7 +134,10 @@ main(int argc, char** argv) // load forest from file and pass it to the detector std::filebuf fb; - fb.open(forest_fn.c_str(), std::ios::in); + if (!fb.open(forest_fn.c_str(), std::ios::in)) { + PCL_ERROR("Could not open file %s\n", forest_fn.c_str()); + return 1; + } std::istream os(&fb); using NodeType = pcl::face_detection::RFTreeNode; From 2934ff58f61b82b647ab7e9d09980c1aedd668e9 Mon Sep 17 00:00:00 2001 From: Alessio Stella Date: Mon, 17 Apr 2023 12:58:24 +0200 Subject: [PATCH 069/288] fix MSVS not supporting unsigned int in for loop with openMP (#5666) --- io/src/real_sense_2_grabber.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/io/src/real_sense_2_grabber.cpp b/io/src/real_sense_2_grabber.cpp index bd84192f198..9de6970857c 100644 --- a/io/src/real_sense_2_grabber.cpp +++ b/io/src/real_sense_2_grabber.cpp @@ -299,7 +299,7 @@ namespace pcl default(none) \ shared(cloud, cloud_texture_ptr, cloud_vertices_ptr, mapColorFunc) #endif - for (std::size_t index = 0; index < cloud->size (); ++index) + for (std::ptrdiff_t index = 0; index < static_cast(cloud->size()); ++index) { const auto ptr = cloud_vertices_ptr + index; const auto uvptr = cloud_texture_ptr + index; From 2e33d5079fcb29380f91d7d9b668be6fdcdf92da Mon Sep 17 00:00:00 2001 From: DownerCase <119755054+DownerCase@users.noreply.github.com> Date: Fri, 21 Apr 2023 09:41:37 +0100 Subject: [PATCH 070/288] Fix Linux and Windows spinOnce behaviour (#5542) * Fix Linux and Windows spinOnce behaviour Repeatedly calling processEvents is necessary to service the message queue in a timely manner. On Windows this also avoids the problem of missing WM_QUIT messages due to being stuck in a modal event loop, most commonly resizing or moving the window. * Avoid busy waiting and add failsafe one-shot timer --- visualization/src/pcl_visualizer.cpp | 23 ++++++++++++++++++----- 1 file changed, 18 insertions(+), 5 deletions(-) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 63b09df13c6..f2eb40e4ff7 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -593,11 +593,24 @@ pcl::visualization::PCLVisualizer::spinOnce (int time, bool force_redraw) #if VTK_MAJOR_VERSION >= 9 && (VTK_MINOR_VERSION != 0 || VTK_BUILD_VERSION != 0) && (VTK_MINOR_VERSION != 0 || VTK_BUILD_VERSION != 1) // All VTK 9 versions, except 9.0.0 and 9.0.1 - if(interactor_->IsA("vtkXRenderWindowInteractor")) { - DO_EVERY (1.0 / interactor_->GetDesiredUpdateRate (), - interactor_->ProcessEvents (); - std::this_thread::sleep_for (std::chrono::milliseconds (time)); - ); + if (interactor_->IsA("vtkXRenderWindowInteractor") || interactor_->IsA("vtkWin32RenderWindowInteractor")) { + const auto start_time = std::chrono::steady_clock::now(); + const auto stop_time = start_time + std::chrono::milliseconds(time); + + // Older versions of VTK 9 block for up to 1s or more on X11 when there are no events. + // So add a one-shot timer to guarantee an event will happen roughly by the time the user expects this function to return + // https://gitlab.kitware.com/vtk/vtk/-/issues/18951#note_1351387 + interactor_->CreateOneShotTimer(time); + + // Process any pending events at least once, this could take a while due to a long running render event + interactor_->ProcessEvents(); + + // Wait for the requested amount of time to have elapsed or exit immediately via GetDone being true when terminateApp is called + while(std::chrono::steady_clock::now() < stop_time && !interactor_->GetDone() ) + { + interactor_->ProcessEvents(); + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } } else #endif From 730d20cf8d615bfa5847f38d2742e715b1db6840 Mon Sep 17 00:00:00 2001 From: Ram Krishna Singh <30290728+rkscodes@users.noreply.github.com> Date: Fri, 21 Apr 2023 19:37:35 +0530 Subject: [PATCH 071/288] Triplet vcpkg build instruction update (#5656) * updated VCPKG tutorial for #5631 * Added the suggested changes * Fix typo --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- doc/tutorials/content/pcl_vcpkg_windows.rst | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/doc/tutorials/content/pcl_vcpkg_windows.rst b/doc/tutorials/content/pcl_vcpkg_windows.rst index 79ea37fbed3..f97ebd747c8 100644 --- a/doc/tutorials/content/pcl_vcpkg_windows.rst +++ b/doc/tutorials/content/pcl_vcpkg_windows.rst @@ -74,6 +74,16 @@ will install PCL with default options as well as default triplet type (ie. x86). ./vcpkg install pcl +.. note:: + This will build executables 2 times in release mode, as default host triplet is x64-windows + on most modern PC systems, but vcpkg install x86 by default. So to fix it you can set + host-triplet same as default triplet. + + ./vcpkg install pcl --host-triplet x86-windows + + Or, you can use same custom triplet for both --triplet and --host-triplet + + ./vcpkg install pcl --triplet --host-triplet .. note:: From 502bd2b013ce635f21632d523aa8cf2e04f7b7ac Mon Sep 17 00:00:00 2001 From: Kai Pastor Date: Sun, 23 Apr 2023 06:24:02 +0200 Subject: [PATCH 072/288] Prefer system zlib over opennurbs vendored copy --- CMakeLists.txt | 9 +++++++ pcl_config.h.in | 2 ++ surface/CMakeLists.txt | 13 +++++++++- .../3rdparty/opennurbs/opennurbs_zlib.h | 18 +++++++++++++ .../src/3rdparty/opennurbs/openNURBS.cmake | 23 ++-------------- .../src/3rdparty/opennurbs/opennurbs_zlib.cpp | 8 ++++++ surface/src/3rdparty/opennurbs/zlib.cmake | 26 +++++++++++++++++++ 7 files changed, 77 insertions(+), 22 deletions(-) create mode 100644 surface/src/3rdparty/opennurbs/zlib.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 8990960b427..8dd786981aa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -416,6 +416,15 @@ endif() # Boost (required) include("${PCL_SOURCE_DIR}/cmake/pcl_find_boost.cmake") +# System zlib (for nurbs on surface) +option(WITH_SYSTEM_ZLIB "Use system zlib" TRUE) +if(WITH_SYSTEM_ZLIB) + find_package(ZLIB) + if(ZLIB_FOUND) + set(HAVE_ZLIB ON) + endif() +endif() + ### ---[ Create the config.h file set(pcl_config_h_in "${CMAKE_CURRENT_SOURCE_DIR}/pcl_config.h.in") set(pcl_config_h "${CMAKE_CURRENT_BINARY_DIR}/include/pcl/pcl_config.h") diff --git a/pcl_config.h.in b/pcl_config.h.in index b5ef2cbf9bf..13d04c3fbfc 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -52,6 +52,8 @@ #cmakedefine HAVE_PNG +#cmakedefine HAVE_ZLIB + /* Precompile for a minimal set of point types instead of all. */ #cmakedefine PCL_ONLY_CORE_POINT_TYPES diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index c29105e6a67..e42c81d1312 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -1,6 +1,7 @@ set(SUBSYS_NAME surface) set(SUBSYS_DESC "Point cloud surface library") set(SUBSYS_DEPS common search kdtree octree) +set(SUBSYS_EXT_DEPS "") set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) @@ -66,6 +67,16 @@ if(BUILD_surface_on_nurbs) include(src/3rdparty/opennurbs/openNURBS.cmake) include(src/on_nurbs/on_nurbs.cmake) + + if(WITH_SYSTEM_ZLIB) + find_package(ZLIB REQUIRED) + list(APPEND ON_NURBS_LIBRARIES ${ZLIB_LIBRARIES}) + list(APPEND SUBSYS_EXT_DEPS zlib) + else() + include(src/3rdparty/opennurbs/zlib.cmake) + list(APPEND OPENNURBS_INCLUDES ${ZLIB_INCLUDES}) + list(APPEND OPENNURBS_SOURCES ${ZLIB_SOURCES}) + endif() endif() set(POISSON_INCLUDES @@ -196,7 +207,7 @@ if(QHULL_FOUND) target_link_libraries("${LIB_NAME}" QHULL::QHULL) endif() -PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) +PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS}) # Install include files PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) diff --git a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_zlib.h b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_zlib.h index 12787e1201f..7622b3a6a7d 100644 --- a/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_zlib.h +++ b/surface/include/pcl/surface/3rdparty/opennurbs/opennurbs_zlib.h @@ -28,6 +28,22 @@ // and statically link with the zlib library. All the necessary // header files are included by opennurbs.h. +// PCL can use an external zlib. + +#include + +#if defined(HAVE_ZLIB) + +#define z_deflate deflate +#define z_inflate inflate +#define z_Bytef Bytef + +#define zcalloc pcl_zcalloc +#define zcfree pcl_zcfree + +#include + +#else #if !defined(Z_PREFIX) /* decorates zlib functions with a "z_" prefix to prevent symbol collision. */ @@ -41,6 +57,8 @@ #include "zlib.h" +#endif // HAVE_ZLIB + ON_BEGIN_EXTERNC voidpf zcalloc (voidpf, unsigned, unsigned); void zcfree (voidpf, voidpf); diff --git a/surface/src/3rdparty/opennurbs/openNURBS.cmake b/surface/src/3rdparty/opennurbs/openNURBS.cmake index 51ca678d018..fdcfa7e92dd 100644 --- a/surface/src/3rdparty/opennurbs/openNURBS.cmake +++ b/surface/src/3rdparty/opennurbs/openNURBS.cmake @@ -102,16 +102,7 @@ set(OPENNURBS_INCLUDES include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_workspace.h include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_xform.h include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/opennurbs_zlib.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/crc32.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/deflate.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffast.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffixed.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inflate.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inftrees.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/trees.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zconf.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zlib.h - include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zutil.h) +) set(OPENNURBS_SOURCES src/3rdparty/opennurbs/opennurbs_3dm_attributes.cpp @@ -222,14 +213,4 @@ set(OPENNURBS_SOURCES src/3rdparty/opennurbs/opennurbs_xform.cpp src/3rdparty/opennurbs/opennurbs_zlib.cpp src/3rdparty/opennurbs/opennurbs_zlib_memory.cpp - src/3rdparty/opennurbs/adler32.c - src/3rdparty/opennurbs/compress.c - src/3rdparty/opennurbs/crc32.c - src/3rdparty/opennurbs/deflate.c - src/3rdparty/opennurbs/infback.c - src/3rdparty/opennurbs/inffast.c - src/3rdparty/opennurbs/inflate.c - src/3rdparty/opennurbs/inftrees.c - src/3rdparty/opennurbs/trees.c - src/3rdparty/opennurbs/uncompr.c - src/3rdparty/opennurbs/zutil.c) +) diff --git a/surface/src/3rdparty/opennurbs/opennurbs_zlib.cpp b/surface/src/3rdparty/opennurbs/opennurbs_zlib.cpp index 688c803df65..03e61993177 100644 --- a/surface/src/3rdparty/opennurbs/opennurbs_zlib.cpp +++ b/surface/src/3rdparty/opennurbs/opennurbs_zlib.cpp @@ -16,6 +16,8 @@ #include "pcl/surface/3rdparty/opennurbs/opennurbs.h" +#if !defined(HAVE_ZLIB) + #if defined(ON_DLL_EXPORTS) // When compiling a Windows DLL opennurbs, we // statically link ./zlib/.../zlib....lib into @@ -72,6 +74,8 @@ #endif // ON_DLL_EXPORTS +#endif // !HAVE_ZLIB + bool ON_BinaryArchive::WriteCompressedBuffer( std::size_t sizeof__inbuffer, // sizeof uncompressed input data @@ -641,7 +645,11 @@ struct ON_CompressedBufferHelper sizeof_x_buffer = 16384 }; unsigned char buffer[sizeof_x_buffer]; +#if defined(HAVE_ZLIB) + z_stream strm = []() { z_stream zs; zs.zalloc = pcl_zcalloc; zs.zfree = pcl_zcfree; return zs; } (); +#else z_stream strm; +#endif std::size_t m_buffer_compressed_capacity; }; diff --git a/surface/src/3rdparty/opennurbs/zlib.cmake b/surface/src/3rdparty/opennurbs/zlib.cmake new file mode 100644 index 00000000000..d730f223975 --- /dev/null +++ b/surface/src/3rdparty/opennurbs/zlib.cmake @@ -0,0 +1,26 @@ +set(ZLIB_INCLUDES + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/crc32.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/deflate.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffast.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inffixed.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inflate.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/inftrees.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/trees.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zconf.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zlib.h + include/pcl/${SUBSYS_NAME}/3rdparty/opennurbs/zutil.h +) + +set(ZLIB_SOURCES + src/3rdparty/opennurbs/adler32.c + src/3rdparty/opennurbs/compress.c + src/3rdparty/opennurbs/crc32.c + src/3rdparty/opennurbs/deflate.c + src/3rdparty/opennurbs/infback.c + src/3rdparty/opennurbs/inffast.c + src/3rdparty/opennurbs/inflate.c + src/3rdparty/opennurbs/inftrees.c + src/3rdparty/opennurbs/trees.c + src/3rdparty/opennurbs/uncompr.c + src/3rdparty/opennurbs/zutil.c +) From 98879df93d2ac466c5b45c8de0349edaf998d5f4 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 25 Apr 2023 13:45:12 +0200 Subject: [PATCH 073/288] Update release dockerfile - VTK 7 is not available any more - /etc/apt/sources.list is not found, the sed command can be removed --- .dev/docker/release/Dockerfile | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/.dev/docker/release/Dockerfile b/.dev/docker/release/Dockerfile index f1c6211c34b..64afbab8da7 100644 --- a/.dev/docker/release/Dockerfile +++ b/.dev/docker/release/Dockerfile @@ -1,14 +1,12 @@ FROM debian:testing -ARG VTK_VERSION=7 +ARG VTK_VERSION=9 ENV DEBIAN_FRONTEND=noninteractive ARG PCL_INDEX_SIGNED=true ARG PCL_INDEX_SIZE=32 -# Add sources so we can just install build-dependencies of PCL -RUN sed -i 's/^deb \(.*\)$/deb \1\ndeb-src \1/' /etc/apt/sources.list \ - && apt update \ +RUN apt update \ && apt install -y \ bash \ cmake \ From 322b62911e48590dc42deecfaa26f79db624f85a Mon Sep 17 00:00:00 2001 From: mynickmynick mynickmynick Date: Tue, 25 Apr 2023 14:17:14 +0200 Subject: [PATCH 074/288] ConvexHull used to print a lot of info on stdout (if compute area is set) which was not necessary and slowed down the elaboration time of 20%. Now only if VerbosityLevel(pcl::console::L_DEBUG) --- surface/include/pcl/surface/impl/convex_hull.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/surface/include/pcl/surface/impl/convex_hull.hpp b/surface/include/pcl/surface/impl/convex_hull.hpp index aa36cdd9efb..47d7e80d82c 100644 --- a/surface/include/pcl/surface/impl/convex_hull.hpp +++ b/surface/include/pcl/surface/impl/convex_hull.hpp @@ -136,7 +136,7 @@ pcl::ConvexHull::performReconstruction2D (PointCloud &hull, std::vecto // output from qh_produce_output(), use NULL to skip qh_produce_output() FILE *outfile = nullptr; - if (compute_area_) + if (compute_area_ && pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG)) outfile = stderr; // option flags for qhull, see qh_opt.htm @@ -299,7 +299,7 @@ pcl::ConvexHull::performReconstruction3D ( // output from qh_produce_output(), use NULL to skip qh_produce_output() FILE *outfile = nullptr; - if (compute_area_) + if (compute_area_ && pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG)) outfile = stderr; // option flags for qhull, see qh_opt.htm From f2b9f23eba45e4935a5ea26fc440328a5c1090b8 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 26 Apr 2023 10:33:50 +0200 Subject: [PATCH 075/288] Add release log for 1.13.1-rc1 (#5687) --- CHANGES.md | 101 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 101 insertions(+) diff --git a/CHANGES.md b/CHANGES.md index c6679ae924e..076e69f9e08 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -1,5 +1,106 @@ # ChangeList +## = 1.13.1 (24 April 2023) = + +### Notable changes + +**New features** *added to PCL* + +* **[common]** Add overload to fromPCLPointCloud2 to avoid copying data [[#5608](https://github.com/PointCloudLibrary/pcl/pull/5608)] +* **[io]** Add writeBinary to ostream for PCDWriter [[#5598](https://github.com/PointCloudLibrary/pcl/pull/5598)] +* **[docs][io]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)] + +**Removal** *of the public APIs deprecated in previous releases* + +* **[gpu]** Remove CUDA code for already unsupported CUDA versions [[#5535](https://github.com/PointCloudLibrary/pcl/pull/5535)] +* **[tools]** Remove pcl_video.cpp [[#5595](https://github.com/PointCloudLibrary/pcl/pull/5595)] +* **[io][tools]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)] + +**Behavior changes** *in classes, apps, or tools* + +* **[cmake]** Require at least MSVC 2017 [[#5562](https://github.com/PointCloudLibrary/pcl/pull/5562)] + +### Changes grouped by module + +#### CMake: + +* Link to VTK::FiltersGeneral [[#5547](https://github.com/PointCloudLibrary/pcl/pull/5547)] +* Add support for Boost 1.81 [[#5558](https://github.com/PointCloudLibrary/pcl/pull/5558)] +* **[behavior change]** Require at least MSVC 2017 [[#5562](https://github.com/PointCloudLibrary/pcl/pull/5562)] +* Make sure that find_package(PCL) does not leak internals or overwrite variables [[#5582](https://github.com/PointCloudLibrary/pcl/pull/5582)] +* Misc small fixes and improvements [[#5624](https://github.com/PointCloudLibrary/pcl/pull/5624)] +* Allow compilation with Boost 1.82 [[#5668](https://github.com/PointCloudLibrary/pcl/pull/5668)] + +#### libpcl_common: + +* **[new feature]** Add overload to fromPCLPointCloud2 to avoid copying data [[#5608](https://github.com/PointCloudLibrary/pcl/pull/5608)] + +#### libpcl_features: + +* Fix crash in SpinImageEstimation [[#5586](https://github.com/PointCloudLibrary/pcl/pull/5586)] +* Fix access violation in IntegralImageNormalEstimation when using dept… [[#5585](https://github.com/PointCloudLibrary/pcl/pull/5585)] + +#### libpcl_filters: + +* Fix bug in LocalMaximum [[#5572](https://github.com/PointCloudLibrary/pcl/pull/5572)] + +#### libpcl_gpu: + +* **[removal]** Remove CUDA code for already unsupported CUDA versions [[#5535](https://github.com/PointCloudLibrary/pcl/pull/5535)] + +#### libpcl_io: + +* Link to VTK::FiltersGeneral [[#5547](https://github.com/PointCloudLibrary/pcl/pull/5547)] +* Fix pcl:ply_reader_fuzzer: Crash in pcl::PLYReader::read [[#5552](https://github.com/PointCloudLibrary/pcl/pull/5552)] +* **[new feature]** Add writeBinary to ostream for PCDWriter [[#5598](https://github.com/PointCloudLibrary/pcl/pull/5598)] +* **[removal]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)] +* **[new feature]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)] +* fix MSVS not supporting unsigned int in for loop with openMP [[#5666](https://github.com/PointCloudLibrary/pcl/pull/5666)] + +#### libpcl_octree: + +* use PCL_ERROR instead of assert [[#5321](https://github.com/PointCloudLibrary/pcl/pull/5321)] + +#### libpcl_people: + +* People: fix segfault in SSE HoG computation [[#5658](https://github.com/PointCloudLibrary/pcl/pull/5658)] + +#### libpcl_registration: + +* Fix potential memory problems in GICP and IncrementalRegistration [[#5557](https://github.com/PointCloudLibrary/pcl/pull/5557)] + +#### libpcl_segmentation: + +* MinCutSegmentation: use correct allocation size, fix segfault [[#5651](https://github.com/PointCloudLibrary/pcl/pull/5651)] + +#### libpcl_visualization: + +* Fix Linux and Windows spinOnce behaviour [[#5542](https://github.com/PointCloudLibrary/pcl/pull/5542)] + +#### PCL Apps: + +* Make apps Qt6 compatible [[#5570](https://github.com/PointCloudLibrary/pcl/pull/5570)] +* OpenNI apps: Improve handling of command line arguments [[#5494](https://github.com/PointCloudLibrary/pcl/pull/5494)] +* Improved manual registration [[#5530](https://github.com/PointCloudLibrary/pcl/pull/5530)] +* Improve pcl_openni_face_detector [[#5669](https://github.com/PointCloudLibrary/pcl/pull/5669)] + +#### PCL Docs: + +* Add tutorial for using VCPKG on Windows [[#4814](https://github.com/PointCloudLibrary/pcl/pull/4814)] +* **[new feature]** io/doc: add overview of file reading and writing functions [[#5657](https://github.com/PointCloudLibrary/pcl/pull/5657)] + +#### PCL Tools: + +* radius filter: fix incorrect printf format specifier and typo [[#5536](https://github.com/PointCloudLibrary/pcl/pull/5536)] +* Remove NaNs from clouds after loading in icp tool [[#5568](https://github.com/PointCloudLibrary/pcl/pull/5568)] +* **[removal]** Remove pcl_video.cpp [[#5595](https://github.com/PointCloudLibrary/pcl/pull/5595)] +* **[removal]** Remove last usage of boost::date_time and replace it with std::chrono [[#5596](https://github.com/PointCloudLibrary/pcl/pull/5596)] + +#### CI: + +* vcpkg: build only release for host-triplet [[#5614](https://github.com/PointCloudLibrary/pcl/pull/5614)] +* Misc small fixes and improvements [[#5624](https://github.com/PointCloudLibrary/pcl/pull/5624)] + ## = 1.13.0 (10 December 2022) = ### Notable changes From fe19581ca50bf0d39172638cafeeec70d9473a9e Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Fri, 28 Apr 2023 11:24:56 +0200 Subject: [PATCH 076/288] Point Cloud Editor: fix select2D after switch to QOpenGLWidget (#5685) * Point Cloud Editor: fix select2D after switch to QOpenGLWidget In commit https://github.com/PointCloudLibrary/pcl/commit/38cbd621d0632895e1bed04841a612f97f574abc the CloudEditorWidget was switched from QGLWidget to QOpenGLWidget to be compatible with Qt6. The select2D tool needs the viewport and the projection matrix, which are loaded with `glGetIntegerv(GL_VIEWPORT,viewport)` and `glGetFloatv(GL_PROJECTION_MATRIX, project)` (they are set in `CloudEditorWidget::resizeGL`). However, since the switch to QOpenGLWidget, the received projection matrix is just the identity matrix, and the viewport does not look correct either. It seems that QOpenGLWidget overwrites them. These changes introduce variables in CloudEditorWidget to safely store the viewport and projection matrix, and passes a function to the select2D tool to ask for them when needed. * Add include for windows * Additional fix for hdpi mac displays --- .../pcl/apps/point_cloud_editor/cloudEditorWidget.h | 4 ++++ .../include/pcl/apps/point_cloud_editor/select2DTool.h | 5 ++++- apps/point_cloud_editor/src/cloudEditorWidget.cpp | 10 +++++++++- apps/point_cloud_editor/src/select2DTool.cpp | 7 +++---- 4 files changed, 20 insertions(+), 6 deletions(-) diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h index e8fdb0e9280..91ff49e32fe 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h @@ -319,5 +319,9 @@ class CloudEditorWidget : public QOpenGLWidget /// a dialog displaying the statistics of the cloud editor StatisticsDialog stat_dialog_; + /// the viewport, set by resizeGL + std::array viewport_; + /// the projection matrix, set by resizeGL + std::array projection_matrix_; }; diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h index f48e354552c..2052f10e8e7 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h @@ -57,7 +57,8 @@ class Select2DTool : public ToolInterface /// @brief Constructor /// @param selection_ptr a shared pointer pointing to the selection object. /// @param cloud_ptr a shared pointer pointing to the cloud object. - Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr); + /// @param get_viewport_and_projection_mat a function that can be used to get the viewport and the projection matrix + Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr, std::function get_viewport_and_projection_mat); /// @brief Destructor ~Select2DTool () override; @@ -154,4 +155,6 @@ class Select2DTool : public ToolInterface /// switch for selection box rendering bool display_box_; + /// function to get the viewport and the projection matrix (initialized by ctor) + std::function get_viewport_and_projection_mat_; }; diff --git a/apps/point_cloud_editor/src/cloudEditorWidget.cpp b/apps/point_cloud_editor/src/cloudEditorWidget.cpp index 7ba8089f176..f4cd6d4d03a 100644 --- a/apps/point_cloud_editor/src/cloudEditorWidget.cpp +++ b/apps/point_cloud_editor/src/cloudEditorWidget.cpp @@ -47,6 +47,9 @@ #ifdef OPENGL_IS_A_FRAMEWORK # include #else +# ifdef _WIN32 +# include +# endif // _WIN32 # include #endif @@ -201,7 +204,7 @@ CloudEditorWidget::select2D () if (!cloud_ptr_) return; tool_ptr_ = std::shared_ptr(new Select2DTool(selection_ptr_, - cloud_ptr_)); + cloud_ptr_, [this](GLint * viewport, GLfloat * projection_matrix){ std::copy_n(this->viewport_.begin(), 4, viewport); std::copy_n(this->projection_matrix_.begin(), 16, projection_matrix); })); update(); } @@ -472,11 +475,16 @@ CloudEditorWidget::paintGL () void CloudEditorWidget::resizeGL (int width, int height) { + const auto ratio = this->devicePixelRatio(); + width = static_cast(width*ratio); + height = static_cast(height*ratio); glViewport(0, 0, width, height); + viewport_ = {0, 0, width, height}; cam_aspect_ = double(width) / double(height); glMatrixMode(GL_PROJECTION); glLoadIdentity(); gluPerspective(cam_fov_, cam_aspect_, cam_near_, cam_far_); + glGetFloatv(GL_PROJECTION_MATRIX, projection_matrix_.data()); glMatrixMode(GL_MODELVIEW); glLoadIdentity(); } diff --git a/apps/point_cloud_editor/src/select2DTool.cpp b/apps/point_cloud_editor/src/select2DTool.cpp index 93e431027bf..60025238bd2 100644 --- a/apps/point_cloud_editor/src/select2DTool.cpp +++ b/apps/point_cloud_editor/src/select2DTool.cpp @@ -48,8 +48,8 @@ const float Select2DTool::DEFAULT_TOOL_DISPLAY_COLOR_GREEN_ = 1.0f; const float Select2DTool::DEFAULT_TOOL_DISPLAY_COLOR_BLUE_ = 1.0f; -Select2DTool::Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr) - : selection_ptr_(std::move(selection_ptr)), cloud_ptr_(std::move(cloud_ptr)), display_box_(false) +Select2DTool::Select2DTool (SelectionPtr selection_ptr, CloudPtr cloud_ptr, std::function get_viewport_and_projection_mat) + : selection_ptr_(std::move(selection_ptr)), cloud_ptr_(std::move(cloud_ptr)), display_box_(false), get_viewport_and_projection_mat_(get_viewport_and_projection_mat) { } @@ -88,10 +88,9 @@ Select2DTool::end (int x, int y, BitMask modifiers, BitMask) return; GLint viewport[4]; - glGetIntegerv(GL_VIEWPORT,viewport); IndexVector indices; GLfloat project[16]; - glGetFloatv(GL_PROJECTION_MATRIX, project); + get_viewport_and_projection_mat_(viewport, project); Point3DVector ptsvec; cloud_ptr_->getDisplaySpacePoints(ptsvec); From 07d3cb935a5dfd9e4403a2876c780ecb9e37a0a5 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 2 May 2023 10:09:40 +0200 Subject: [PATCH 077/288] Make io more locale invariant - Expand test: write with English locale, then read with German locale (previously the test only wrote with German, read with English) - In `copyStringValue` used by PCD reader: clear error flags after replacing content of istringstream, otherwise the `!(is >> value)` test always fails and `atof` is used (which uses the global locale) --- io/include/pcl/io/file_io.h | 3 ++ io/src/ply_io.cpp | 1 + test/io/test_io.cpp | 90 +++++++++++++++++++++++++++++-------- test/io/test_ply_io.cpp | 2 + 4 files changed, 77 insertions(+), 19 deletions(-) diff --git a/io/include/pcl/io/file_io.h b/io/include/pcl/io/file_io.h index 25fe20a2141..b7ec74b8cda 100644 --- a/io/include/pcl/io/file_io.h +++ b/io/include/pcl/io/file_io.h @@ -342,6 +342,7 @@ namespace pcl } else { is.str(st); + is.clear(); // clear error state flags if (!(is >> value)) value = static_cast(atof(st.c_str())); } @@ -364,6 +365,7 @@ namespace pcl std::int8_t value; int val; is.str(st); + is.clear(); // clear error state flags // is >> val; -- unfortunately this fails on older GCC versions and CLANG on MacOS if (!(is >> val)) { val = static_cast(atof(st.c_str())); @@ -388,6 +390,7 @@ namespace pcl std::uint8_t value; int val; is.str(st); + is.clear(); // clear error state flags // is >> val; -- unfortunately this fails on older GCC versions and CLANG on // MacOS if (!(is >> val)) { diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 14735a5af6f..96f1a407517 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -787,6 +787,7 @@ pcl::PLYWriter::generateHeader (const pcl::PCLPointCloud2 &cloud, int valid_points) { std::ostringstream oss; + oss.imbue (std::locale::classic ()); // mostly to make sure that no thousands separator is printed // Begin header oss << "ply"; if (!binary) diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index 97716de54aa..53438b2e92f 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -1519,27 +1519,29 @@ TEST (PCL, LZFInMem) TEST (PCL, Locale) { #ifndef __APPLE__ + PointCloud cloud, cloud2, cloud3; + cloud.width = 640; + cloud.height = 480; + cloud.resize (cloud.width * cloud.height); + cloud.is_dense = true; + + srand (static_cast (time (nullptr))); + const auto nr_p = cloud.size (); + // Randomly create a new point cloud + cloud[0].x = std::numeric_limits::quiet_NaN (); + cloud[0].y = std::numeric_limits::quiet_NaN (); + cloud[0].z = std::numeric_limits::quiet_NaN (); + + for (std::size_t i = 1; i < nr_p; ++i) + { + cloud[i].x = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].y = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + cloud[i].z = static_cast (1024 * rand () / (RAND_MAX + 1.0)); + } + + // First write with German locale, then read with English locale try { - PointCloud cloud, cloud2; - cloud.width = 640; - cloud.height = 480; - cloud.resize (cloud.width * cloud.height); - cloud.is_dense = true; - - srand (static_cast (time (nullptr))); - const auto nr_p = cloud.size (); - // Randomly create a new point cloud - cloud[0].x = std::numeric_limits::quiet_NaN (); - cloud[0].y = std::numeric_limits::quiet_NaN (); - cloud[0].z = std::numeric_limits::quiet_NaN (); - - for (std::size_t i = 1; i < nr_p; ++i) - { - cloud[i].x = static_cast (1024 * rand () / (RAND_MAX + 1.0)); - cloud[i].y = static_cast (1024 * rand () / (RAND_MAX + 1.0)); - cloud[i].z = static_cast (1024 * rand () / (RAND_MAX + 1.0)); - } PCDWriter writer; try { @@ -1592,6 +1594,56 @@ TEST (PCL, Locale) } remove ("test_pcl_io_ascii_locale.pcd"); + + // Now write with English locale, then read with German locale + try + { +#ifdef _WIN32 + std::locale::global (std::locale ("English_US")); +#else + std::locale::global (std::locale ("en_US.UTF-8")); +#endif + } + catch (const std::runtime_error&) + { + PCL_WARN ("Failed to set locale, skipping test.\n"); + } + PCDWriter writer; + int res = writer.writeASCII ("test_pcl_io_ascii_locale.pcd", cloud); + EXPECT_EQ (res, 0); + + PCDReader reader; + try + { +#ifdef _WIN32 + std::locale::global (std::locale ("German_germany")); +#else + std::locale::global (std::locale ("de_DE.UTF-8")); +#endif + } + catch (const std::runtime_error&) + { + PCL_WARN ("Failed to set locale, skipping test.\n"); + } + reader.read ("test_pcl_io_ascii_locale.pcd", cloud3); + std::locale::global (std::locale::classic ()); + + EXPECT_EQ (cloud3.width, cloud.width); + EXPECT_EQ (cloud3.height, cloud.height); + EXPECT_FALSE (cloud3.is_dense); + EXPECT_EQ (cloud3.size (), cloud.size ()); + + EXPECT_TRUE (std::isnan(cloud3[0].x)); + EXPECT_TRUE (std::isnan(cloud3[0].y)); + EXPECT_TRUE (std::isnan(cloud3[0].z)); + for (std::size_t i = 1; i < cloud3.size (); ++i) + { + ASSERT_FLOAT_EQ (cloud3[i].x, cloud[i].x); + ASSERT_FLOAT_EQ (cloud3[i].y, cloud[i].y); + ASSERT_FLOAT_EQ (cloud3[i].z, cloud[i].z); + } + + remove ("test_pcl_io_ascii_locale.pcd"); #endif } diff --git a/test/io/test_ply_io.cpp b/test/io/test_ply_io.cpp index 7fce8deea5e..7901a7e36e0 100644 --- a/test/io/test_ply_io.cpp +++ b/test/io/test_ply_io.cpp @@ -105,6 +105,7 @@ TEST (PCL, PLYReaderWriter) EXPECT_FLOAT_EQ (cloud[counter].z, cloud2[counter].z); // test for fromPCLPointCloud2 () EXPECT_FLOAT_EQ (cloud[counter].intensity, cloud2[counter].intensity); // test for fromPCLPointCloud2 () } + remove ("test_pcl_io.ply"); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -567,6 +568,7 @@ TEST_F (PLYTest, Float64Cloud) // create file std::ofstream fs; + fs.imbue (std::locale::classic ()); // make sure that floats are printed with decimal point fs.open (mesh_file_ply_.c_str ()); fs << "ply\n" "format ascii 1.0\n" From 8a402824b8009b28bbbb4e093ff0036b9cb66478 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 9 May 2023 12:44:21 +0200 Subject: [PATCH 078/288] Updated changelog to include Point cloud Editor fix. (#5696) * Updated changelog to include Point cloud Editor fix. * Change release date in changes. --- CHANGES.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/CHANGES.md b/CHANGES.md index 076e69f9e08..06a63c1c420 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -1,6 +1,6 @@ # ChangeList -## = 1.13.1 (24 April 2023) = +## = 1.13.1 (10 May 2023) = ### Notable changes @@ -83,6 +83,7 @@ * OpenNI apps: Improve handling of command line arguments [[#5494](https://github.com/PointCloudLibrary/pcl/pull/5494)] * Improved manual registration [[#5530](https://github.com/PointCloudLibrary/pcl/pull/5530)] * Improve pcl_openni_face_detector [[#5669](https://github.com/PointCloudLibrary/pcl/pull/5669)] +* Point Cloud Editor: fix select2D after switch to QOpenGLWidget [[#5685](https://github.com/PointCloudLibrary/pcl/pull/5685)] #### PCL Docs: From b3a7428534ba307f40bf7e409d4cc56bb818b907 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 10 May 2023 08:44:47 +0200 Subject: [PATCH 079/288] Bumped version (#5704) --- CMakeLists.txt | 2 +- README.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8990960b427..51879ed127a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.13.0.99) +project(PCL VERSION 1.13.1) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) diff --git a/README.md b/README.md index 1ba99d1ec8c..ad4443647f8 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ [![Release][release-image]][releases] [![License][license-image]][license] -[release-image]: https://img.shields.io/badge/release-1.13.0-green.svg?style=flat +[release-image]: https://img.shields.io/badge/release-1.13.1-green.svg?style=flat [releases]: https://github.com/PointCloudLibrary/pcl/releases [license-image]: https://img.shields.io/badge/license-BSD-green.svg?style=flat From 745d10d286c6788f3ba1fedea3ae1e8983dde52a Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 10 May 2023 13:18:45 +0200 Subject: [PATCH 080/288] Bump after release 1.13.1 (#5705) --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 51879ed127a..b383dd895ba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.13.1) +project(PCL VERSION 1.13.1.99) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) From 4cca66cc965a860209ec9da72589ab7ea0301927 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Wed, 10 May 2023 05:09:33 -0700 Subject: [PATCH 081/288] Added modernize-use-bool-literals, modernize-use-default-member-init clang-tidy checks (#5665) * First set of modernize-use-default-member-init changes * Fixed issues found by inspection --- 2d/include/pcl/2d/edge.h | 23 ++---- 2d/include/pcl/2d/kernel.h | 6 +- .../include/pcl/common/bivariate_polynomial.h | 7 +- common/include/pcl/common/centroid.h | 25 +++--- .../pcl/common/impl/bivariate_polynomial.hpp | 12 ++- common/include/pcl/common/pca.h | 79 +++++++++---------- common/include/pcl/impl/point_types.hpp | 10 ++- common/include/pcl/point_representation.h | 4 +- common/include/pcl/range_image/range_image.h | 10 +-- .../pcl/range_image/range_image_planar.h | 6 +- common/src/range_image.cpp | 5 +- common/src/range_image_planar.cpp | 6 +- 12 files changed, 88 insertions(+), 105 deletions(-) diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index d606d91242a..61c9f2844fd 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -116,25 +116,16 @@ class Edge { private: OUTPUT_TYPE output_type_; DETECTOR_KERNEL_TYPE detector_kernel_type_; - bool non_maximal_suppression_; - bool hysteresis_thresholding_; + bool non_maximal_suppression_{false}; + bool hysteresis_thresholding_{false}; - float hysteresis_threshold_low_; - float hysteresis_threshold_high_; - float non_max_suppression_radius_x_; - float non_max_suppression_radius_y_; + float hysteresis_threshold_low_{20}; + float hysteresis_threshold_high_{80}; + float non_max_suppression_radius_x_{3}; + float non_max_suppression_radius_y_{3}; public: - Edge() - : output_type_(OUTPUT_X) - , detector_kernel_type_(SOBEL) - , non_maximal_suppression_(false) - , hysteresis_thresholding_(false) - , hysteresis_threshold_low_(20) - , hysteresis_threshold_high_(80) - , non_max_suppression_radius_x_(3) - , non_max_suppression_radius_y_(3) - {} + Edge() : output_type_(OUTPUT_X), detector_kernel_type_(SOBEL) {} /** \brief Set the output type. * \param[in] output_type the output type diff --git a/2d/include/pcl/2d/kernel.h b/2d/include/pcl/2d/kernel.h index 499d3a38393..a910b90f8c9 100644 --- a/2d/include/pcl/2d/kernel.h +++ b/2d/include/pcl/2d/kernel.h @@ -63,11 +63,11 @@ class kernel { GAUSSIAN //!< GAUSSIAN }; - int kernel_size_; - float sigma_; + int kernel_size_{3}; + float sigma_{1.0}; KERNEL_ENUM kernel_type_; - kernel() : kernel_size_(3), sigma_(1.0), kernel_type_(GAUSSIAN) {} + kernel() : kernel_type_(GAUSSIAN) {} /** * diff --git a/common/include/pcl/common/bivariate_polynomial.h b/common/include/pcl/common/bivariate_polynomial.h index 615320b4094..b347872040e 100644 --- a/common/include/pcl/common/bivariate_polynomial.h +++ b/common/include/pcl/common/bivariate_polynomial.h @@ -114,9 +114,10 @@ namespace pcl getNoOfParametersFromDegree (int n) { return ((n+2)* (n+1))/2;} //-----VARIABLES----- - int degree; - real* parameters; - BivariatePolynomialT* gradient_x, * gradient_y; + int degree{0}; + real* parameters{nullptr}; + BivariatePolynomialT* gradient_x{nullptr}; + BivariatePolynomialT* gradient_y{nullptr}; protected: //-----METHODS----- diff --git a/common/include/pcl/common/centroid.h b/common/include/pcl/common/centroid.h index 0f456f16b4b..cb88773fc49 100644 --- a/common/include/pcl/common/centroid.h +++ b/common/include/pcl/common/centroid.h @@ -89,18 +89,18 @@ namespace pcl * \ingroup common */ template inline unsigned int - compute3DCentroid (const pcl::PointCloud &cloud, + compute3DCentroid (const pcl::PointCloud &cloud, Eigen::Matrix ¢roid); template inline unsigned int - compute3DCentroid (const pcl::PointCloud &cloud, + compute3DCentroid (const pcl::PointCloud &cloud, Eigen::Vector4f ¢roid) { return (compute3DCentroid (cloud, centroid)); } template inline unsigned int - compute3DCentroid (const pcl::PointCloud &cloud, + compute3DCentroid (const pcl::PointCloud &cloud, Eigen::Vector4d ¢roid) { return (compute3DCentroid (cloud, centroid)); @@ -844,8 +844,7 @@ namespace pcl using Pod = typename traits::POD::type; NdCentroidFunctor (const PointT &p, Eigen::Matrix ¢roid) - : f_idx_ (0), - centroid_ (centroid), + : centroid_ (centroid), p_ (reinterpret_cast(p)) { } template inline void operator() () @@ -865,7 +864,7 @@ namespace pcl } private: - int f_idx_; + int f_idx_{0}; Eigen::Matrix ¢roid_; const Pod &p_; }; @@ -877,18 +876,18 @@ namespace pcl * \ingroup common */ template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, Eigen::Matrix ¢roid); template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, Eigen::VectorXf ¢roid) { return (computeNDCentroid (cloud, centroid)); } template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, Eigen::VectorXd ¢roid) { return (computeNDCentroid (cloud, centroid)); @@ -907,7 +906,7 @@ namespace pcl Eigen::Matrix ¢roid); template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, const Indices &indices, Eigen::VectorXf ¢roid) { @@ -915,7 +914,7 @@ namespace pcl } template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, const Indices &indices, Eigen::VectorXd ¢roid) { @@ -935,7 +934,7 @@ namespace pcl Eigen::Matrix ¢roid); template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, const pcl::PointIndices &indices, Eigen::VectorXf ¢roid) { @@ -943,7 +942,7 @@ namespace pcl } template inline void - computeNDCentroid (const pcl::PointCloud &cloud, + computeNDCentroid (const pcl::PointCloud &cloud, const pcl::PointIndices &indices, Eigen::VectorXd ¢roid) { diff --git a/common/include/pcl/common/impl/bivariate_polynomial.hpp b/common/include/pcl/common/impl/bivariate_polynomial.hpp index 9a29abf2b87..6ae8db6fd0a 100644 --- a/common/include/pcl/common/impl/bivariate_polynomial.hpp +++ b/common/include/pcl/common/impl/bivariate_polynomial.hpp @@ -52,16 +52,14 @@ namespace pcl { template -BivariatePolynomialT::BivariatePolynomialT (int new_degree) : - degree(0), parameters(nullptr), gradient_x(nullptr), gradient_y(nullptr) +BivariatePolynomialT::BivariatePolynomialT (int new_degree) { setDegree(new_degree); } template -BivariatePolynomialT::BivariatePolynomialT (const BivariatePolynomialT& other) : - degree(0), parameters(NULL), gradient_x(NULL), gradient_y(NULL) +BivariatePolynomialT::BivariatePolynomialT (const BivariatePolynomialT& other) { deepCopy (other); } @@ -140,11 +138,11 @@ BivariatePolynomialT::deepCopy (const pcl::BivariatePolynomialT& oth template void BivariatePolynomialT::calculateGradient (bool forceRecalc) { - if (gradient_x!=NULL && !forceRecalc) return; + if (gradient_x!=nullptr && !forceRecalc) return; - if (gradient_x == NULL) + if (gradient_x == nullptr) gradient_x = new pcl::BivariatePolynomialT (degree-1); - if (gradient_y == NULL) + if (gradient_y == nullptr) gradient_y = new pcl::BivariatePolynomialT (degree-1); unsigned int parameterPosDx=0, parameterPosDy=0; diff --git a/common/include/pcl/common/pca.h b/common/include/pcl/common/pca.h index f48f0e1084a..c253a2b8f5c 100644 --- a/common/include/pcl/common/pca.h +++ b/common/include/pcl/common/pca.h @@ -41,17 +41,17 @@ #include #include -namespace pcl +namespace pcl { /** Principal Component analysis (PCA) class.\n - * Principal components are extracted by singular values decomposition on the - * covariance matrix of the centered input cloud. Available data after pca computation + * Principal components are extracted by singular values decomposition on the + * covariance matrix of the centered input cloud. Available data after pca computation * are:\n * - The Mean of the input data\n * - The Eigenvectors: Ordered set of vectors representing the resultant principal components and the eigenspace cartesian basis (right-handed coordinate system).\n * - The Eigenvalues: Eigenvectors correspondent loadings ordered in descending order.\n\n - * Other methods allow projection in the eigenspace, reconstruction from eigenspace and - * update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and + * Other methods allow projection in the eigenspace, reconstruction from eigenspace and + * update of the eigenspace with a new datum (according Matej Artec, Matjaz Jogan and * Ales Leonardis: "Incremental PCA for On-line Visual Learning and Recognition"). * * \author Nizar Sallem @@ -74,30 +74,29 @@ namespace pcl using Base::setInputCloud; /** Updating method flag */ - enum FLAG + enum FLAG { /** keep the new basis vectors if possible */ - increase, + increase, /** preserve subspace dimension */ preserve }; - + /** \brief Default Constructor * \param basis_only flag to compute only the PCA basis */ PCA (bool basis_only = false) : Base () - , compute_done_ (false) - , basis_only_ (basis_only) + , basis_only_ (basis_only) {} /** Copy Constructor * \param[in] pca PCA object */ - PCA (PCA const & pca) + PCA (PCA const & pca) : Base (pca) , compute_done_ (pca.compute_done_) - , basis_only_ (pca.basis_only_) + , basis_only_ (pca.basis_only_) , eigenvectors_ (pca.eigenvectors_) , coefficients_ (pca.coefficients_) , mean_ (pca.mean_) @@ -107,8 +106,8 @@ namespace pcl /** Assignment operator * \param[in] pca PCA object */ - inline PCA& - operator= (PCA const & pca) + inline PCA& + operator= (PCA const & pca) { eigenvectors_ = pca.eigenvectors_; coefficients_ = pca.coefficients_; @@ -116,13 +115,13 @@ namespace pcl mean_ = pca.mean_; return (*this); } - + /** \brief Provide a pointer to the input dataset * \param cloud the const boost shared pointer to a PointCloud message */ - inline void - setInputCloud (const PointCloudConstPtr &cloud) override - { + inline void + setInputCloud (const PointCloudConstPtr &cloud) override + { Base::setInputCloud (cloud); compute_done_ = false; } @@ -175,74 +174,74 @@ namespace pcl /** \brief Mean accessor * \throw InitFailedException */ - inline Eigen::Vector4f& - getMean () + inline Eigen::Vector4f& + getMean () { if (!compute_done_) initCompute (); if (!compute_done_) - PCL_THROW_EXCEPTION (InitFailedException, + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::getMean] PCA initCompute failed"); return (mean_); } /** Eigen Vectors accessor - * \return Column ordered eigenvectors, representing the eigenspace cartesian basis (right-handed coordinate system). + * \return Column ordered eigenvectors, representing the eigenspace cartesian basis (right-handed coordinate system). * \throw InitFailedException */ - inline Eigen::Matrix3f& - getEigenVectors () + inline Eigen::Matrix3f& + getEigenVectors () { if (!compute_done_) initCompute (); if (!compute_done_) - PCL_THROW_EXCEPTION (InitFailedException, + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::getEigenVectors] PCA initCompute failed"); return (eigenvectors_); } - + /** Eigen Values accessor * \throw InitFailedException */ - inline Eigen::Vector3f& + inline Eigen::Vector3f& getEigenValues () { if (!compute_done_) initCompute (); if (!compute_done_) - PCL_THROW_EXCEPTION (InitFailedException, + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::getEigenVectors] PCA getEigenValues failed"); return (eigenvalues_); } - + /** Coefficients accessor * \throw InitFailedException */ - inline Eigen::MatrixXf& - getCoefficients () + inline Eigen::MatrixXf& + getCoefficients () { if (!compute_done_) initCompute (); if (!compute_done_) - PCL_THROW_EXCEPTION (InitFailedException, + PCL_THROW_EXCEPTION (InitFailedException, "[pcl::PCA::getEigenVectors] PCA getCoefficients failed"); return (coefficients_); } - + /** update PCA with a new point - * \param[in] input input point + * \param[in] input input point * \param[in] flag update flag * \throw InitFailedException */ - inline void + inline void update (const PointT& input, FLAG flag = preserve); - + /** Project point on the eigenspace. * \param[in] input point from original dataset * \param[out] projection the point in eigen vectors space * \throw InitFailedException */ - inline void + inline void project (const PointT& input, PointT& projection); /** Project cloud on the eigenspace. @@ -252,13 +251,13 @@ namespace pcl */ inline void project (const PointCloud& input, PointCloud& projection); - + /** Reconstruct point from its projection * \param[in] projection point from eigenvector space * \param[out] input reconstructed point * \throw InitFailedException */ - inline void + inline void reconstruct (const PointT& projection, PointT& input); /** Reconstruct cloud from its projection @@ -272,7 +271,7 @@ namespace pcl inline bool initCompute (); - bool compute_done_; + bool compute_done_{false}; bool basis_only_; Eigen::Matrix3f eigenvectors_; Eigen::MatrixXf coefficients_; diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index a3aee983201..570a1bb4050 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -740,26 +740,28 @@ namespace pcl /** \brief A 2D point structure representing Euclidean xy coordinates. * \ingroup common */ + // NOLINTBEGIN(modernize-use-default-member-init) struct PointXY { union { float data[2]; struct - { - float x; - float y; + { + float x; + float y; }; }; inline constexpr PointXY(float _x, float _y): x(_x), y(_y) {} inline constexpr PointXY(): x(0.0f), y(0.0f) {} - + inline pcl::Vector2fMap getVector2fMap () { return (pcl::Vector2fMap (data)); } inline pcl::Vector2fMapConst getVector2fMap () const { return (pcl::Vector2fMapConst (data)); } friend std::ostream& operator << (std::ostream& os, const PointXY& p); }; + // NOLINTEND(modernize-use-default-member-init) PCL_EXPORTS std::ostream& operator << (std::ostream& os, const PointUV& p); /** \brief A 2D point structure representing pixel image coordinates. diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index a7f2e57c346..3d918a86df1 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -245,7 +245,7 @@ namespace pcl using Pod = typename traits::POD::type; NdCopyPointFunctor (const PointDefault &p1, float * p2) - : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } + : p1_ (reinterpret_cast(p1)), p2_ (p2) {} template inline void operator() () { @@ -285,7 +285,7 @@ namespace pcl private: const Pod &p1_; float * p2_; - int f_idx_; + int f_idx_{0}; }; public: diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 5cf84900c05..a80322c4f11 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -767,13 +767,13 @@ namespace pcl // =====PROTECTED MEMBER VARIABLES===== Eigen::Affine3f to_range_image_system_; /**< Inverse of to_world_system_ */ Eigen::Affine3f to_world_system_; /**< Inverse of to_range_image_system_ */ - float angular_resolution_x_; /**< Angular resolution of the range image in x direction in radians per pixel */ - float angular_resolution_y_; /**< Angular resolution of the range image in y direction in radians per pixel */ - float angular_resolution_x_reciprocal_; /**< 1.0/angular_resolution_x_ - provided for better performance of + float angular_resolution_x_{0}; /**< Angular resolution of the range image in x direction in radians per pixel */ + float angular_resolution_y_{0}; /**< Angular resolution of the range image in y direction in radians per pixel */ + float angular_resolution_x_reciprocal_{0}; /**< 1.0/angular_resolution_x_ - provided for better performance of * multiplication compared to division */ - float angular_resolution_y_reciprocal_; /**< 1.0/angular_resolution_y_ - provided for better performance of + float angular_resolution_y_reciprocal_{0}; /**< 1.0/angular_resolution_y_ - provided for better performance of * multiplication compared to division */ - int image_offset_x_, image_offset_y_; /**< Position of the top left corner of the range image compared to + int image_offset_x_{0}, image_offset_y_{0}; /**< Position of the top left corner of the range image compared to * an image of full size (360x180 degrees) */ PointWithRange unobserved_point; /**< This point is used to be able to return * a reference to a non-existing point */ diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index 3d2cac07048..85afe3889b3 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -206,9 +206,9 @@ namespace pcl protected: - float focal_length_x_, focal_length_y_; //!< The focal length of the image in pixels - float focal_length_x_reciprocal_, focal_length_y_reciprocal_; //!< 1/focal_length -> for internal use - float center_x_, center_y_; //!< The principle point of the image + float focal_length_x_{0.0f}, focal_length_y_{0.0f}; //!< The focal length of the image in pixels + float focal_length_x_reciprocal_{0.0f}, focal_length_y_reciprocal_{0.0f}; //!< 1/focal_length -> for internal use + float center_x_{0.0f}, center_y_{0.0f}; //!< The principle point of the image }; } // namespace end diff --git a/common/src/range_image.cpp b/common/src/range_image.cpp index 89455135aad..615c753beb2 100644 --- a/common/src/range_image.cpp +++ b/common/src/range_image.cpp @@ -105,10 +105,7 @@ RangeImage::getCoordinateFrameTransformation (RangeImage::CoordinateFrame coordi ///////////////////////////////////////////////////////////////////////// RangeImage::RangeImage () : to_range_image_system_ (Eigen::Affine3f::Identity ()), - to_world_system_ (Eigen::Affine3f::Identity ()), - angular_resolution_x_ (0), angular_resolution_y_ (0), - angular_resolution_x_reciprocal_ (0), angular_resolution_y_reciprocal_ (0), - image_offset_x_ (0), image_offset_y_ (0) + to_world_system_ (Eigen::Affine3f::Identity ()) { createLookupTables (); reset (); diff --git a/common/src/range_image_planar.cpp b/common/src/range_image_planar.cpp index 97b249bc77a..784c40ccb64 100644 --- a/common/src/range_image_planar.cpp +++ b/common/src/range_image_planar.cpp @@ -43,11 +43,7 @@ using std::cerr; namespace pcl { ///////////////////////////////////////////////////////////////////////// - RangeImagePlanar::RangeImagePlanar () : focal_length_x_ (0.0f), focal_length_y_ (0.0f), - focal_length_x_reciprocal_ (0.0f), focal_length_y_reciprocal_ (0.0f), - center_x_ (0.0f), center_y_ (0.0f) - { - } + RangeImagePlanar::RangeImagePlanar () = default; ///////////////////////////////////////////////////////////////////////// RangeImagePlanar::~RangeImagePlanar () = default; From 5f2125ff205d2db5167ad83b276a3d39252e2f3b Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Fri, 12 May 2023 16:11:35 +0200 Subject: [PATCH 082/288] Enable writing very large PCD files on Windows (#5675) * Enable writing very large PCD files on Windows CreateFileMapping accepts the file size in two 32 bit, unsigned integer parameters (a high and a low part). Previously, PCL has always set the high part to 0, meaning that the maximal file size was 2^32. To be sure that the shift operator shifts in zeros, the integer has to be unsigned, so data_idx is changed to an unsigned integer everywhere. * Remove return after throw --- io/include/pcl/io/impl/pcd_io.hpp | 38 ++++++++----------------------- io/src/lzf_image_io.cpp | 2 +- io/src/pcd_io.cpp | 7 +++--- 3 files changed, 14 insertions(+), 33 deletions(-) diff --git a/io/include/pcl/io/impl/pcd_io.hpp b/io/include/pcl/io/impl/pcd_io.hpp index 20b748843d9..2c832361ccf 100644 --- a/io/include/pcl/io/impl/pcd_io.hpp +++ b/io/include/pcl/io/impl/pcd_io.hpp @@ -115,25 +115,22 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, { PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data!\n"); } - int data_idx = 0; std::ostringstream oss; oss << generateHeader (cloud) << "DATA binary\n"; oss.flush (); - data_idx = static_cast (oss.tellp ()); + const auto data_idx = static_cast (oss.tellp ()); #ifdef _WIN32 HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); if (h_native_file == INVALID_HANDLE_VALUE) { throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!"); - return (-1); } #else int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH); if (fd < 0) { throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!"); - return (-1); } #endif // Mandatory lock file @@ -162,13 +159,17 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, // Prepare the map #ifdef _WIN32 - HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + data_size), NULL); + HANDLE fm = CreateFileMappingA (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + data_size) >> 32), (DWORD) (data_idx + data_size), NULL); if (fm == NULL) { throw pcl::IOException("[pcl::PCDWriter::writeBinary] Error during memory map creation ()!"); - return (-1); } char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size)); + if (map == NULL) + { + CloseHandle (fm); + throw pcl::IOException("[pcl::PCDWriter::writeBinary] Error mapping view of file!"); + } CloseHandle (fm); #else @@ -182,7 +183,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, data_idx + data_size, allocate_res, errno, strerror (errno)); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during raw_fallocate ()!"); - return (-1); } char *map = static_cast (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0)); @@ -191,7 +191,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!"); - return (-1); } #endif @@ -225,7 +224,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!"); - return (-1); } #endif // Close file @@ -247,25 +245,22 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, { PCL_WARN ("[pcl::PCDWriter::writeBinaryCompressed] Input point cloud has no data!\n"); } - int data_idx = 0; std::ostringstream oss; oss << generateHeader (cloud) << "DATA binary_compressed\n"; oss.flush (); - data_idx = static_cast (oss.tellp ()); + const auto data_idx = static_cast (oss.tellp ()); #ifdef _WIN32 HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); if (h_native_file == INVALID_HANDLE_VALUE) { throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during CreateFile!"); - return (-1); } #else int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH); if (fd < 0) { throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during open!"); - return (-1); } #endif @@ -392,7 +387,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, compressed_final_size, allocate_res, errno, strerror (errno)); throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during raw_fallocate ()!"); - return (-1); } char *map = static_cast (::mmap (nullptr, compressed_final_size, PROT_WRITE, MAP_SHARED, fd, 0)); @@ -401,7 +395,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during mmap ()!"); - return (-1); } #endif @@ -425,7 +418,6 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinaryCompressed] Error during munmap ()!"); - return (-1); } #endif @@ -455,7 +447,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud< if (cloud.width * cloud.height != cloud.size ()) { throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!"); - return (-1); } std::ofstream fs; @@ -464,7 +455,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PointCloud< if (!fs.is_open () || fs.fail ()) { throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!"); - return (-1); } // Mandatory lock file @@ -625,25 +615,22 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, { PCL_WARN ("[pcl::PCDWriter::writeBinary] Input point cloud has no data or empty indices given!\n"); } - int data_idx = 0; std::ostringstream oss; oss << generateHeader (cloud, static_cast (indices.size ())) << "DATA binary\n"; oss.flush (); - data_idx = static_cast (oss.tellp ()); + const auto data_idx = static_cast (oss.tellp ()); #ifdef _WIN32 HANDLE h_native_file = CreateFileA (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); if (h_native_file == INVALID_HANDLE_VALUE) { throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during CreateFile!"); - return (-1); } #else int fd = io::raw_open (file_name.c_str (), O_RDWR | O_CREAT | O_TRUNC, S_IRUSR | S_IWUSR | S_IRGRP | S_IROTH); if (fd < 0) { throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during open!"); - return (-1); } #endif // Mandatory lock file @@ -672,7 +659,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, // Prepare the map #ifdef _WIN32 - HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_idx + data_size, NULL); + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + data_size) >> 32), (DWORD) (data_idx + data_size), NULL); char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + data_size)); CloseHandle (fm); @@ -687,7 +674,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, data_idx + data_size, allocate_res, errno, strerror (errno)); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during raw_fallocate ()!"); - return (-1); } char *map = static_cast (::mmap (nullptr, data_idx + data_size, PROT_WRITE, MAP_SHARED, fd, 0)); @@ -696,7 +682,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during mmap ()!"); - return (-1); } #endif @@ -730,7 +715,6 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, io::raw_close (fd); resetLockingPermissions (file_name, file_lock); throw pcl::IOException ("[pcl::PCDWriter::writeBinary] Error during munmap ()!"); - return (-1); } #endif // Close file @@ -759,7 +743,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, if (cloud.width * cloud.height != cloud.size ()) { throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Number of points different than width * height!"); - return (-1); } std::ofstream fs; @@ -767,7 +750,6 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, if (!fs.is_open () || fs.fail ()) { throw pcl::IOException ("[pcl::PCDWriter::writeASCII] Could not open file for writing!"); - return (-1); } // Mandatory lock file diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index 4cf8984f344..a5b396f5209 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -67,7 +67,7 @@ pcl::io::LZFImageWriter::saveImageBlob (const char* data, HANDLE h_native_file = CreateFile (filename.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); if (h_native_file == INVALID_HANDLE_VALUE) return (false); - HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, data_size, NULL); + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) (data_size >> 32), (DWORD) (data_size), NULL); char *map = static_cast (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_size)); CloseHandle (fm); std::copy(data, data + data_size, map); diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 04eedaa2abb..a026dca9dd3 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -1217,13 +1217,12 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl return (-1); } - std::streamoff data_idx = 0; std::ostringstream oss; oss.imbue (std::locale::classic ()); oss << generateHeaderBinary (cloud, origin, orientation) << "DATA binary\n"; oss.flush(); - data_idx = static_cast (oss.tellp ()); + const auto data_idx = static_cast (oss.tellp ()); #ifdef _WIN32 HANDLE h_native_file = CreateFile (file_name.c_str (), GENERIC_READ | GENERIC_WRITE, 0, NULL, CREATE_ALWAYS, FILE_ATTRIBUTE_NORMAL, NULL); @@ -1269,7 +1268,7 @@ pcl::PCDWriter::writeBinary (const std::string &file_name, const pcl::PCLPointCl #endif // Prepare the map #ifdef _WIN32 - HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, (DWORD) (data_idx + cloud.data.size ()), NULL); + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((data_idx + cloud.data.size ()) >> 32), (DWORD) (data_idx + cloud.data.size ()), NULL); char *map = static_cast(MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, data_idx + cloud.data.size ())); CloseHandle (fm); @@ -1494,7 +1493,7 @@ pcl::PCDWriter::writeBinaryCompressed (const std::string &file_name, const pcl:: // Prepare the map #ifdef _WIN32 - HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, 0, ostr.size (), NULL); + HANDLE fm = CreateFileMapping (h_native_file, NULL, PAGE_READWRITE, (DWORD) ((ostr.size ()) >> 32), (DWORD) (ostr.size ()), NULL); char *map = static_cast (MapViewOfFile (fm, FILE_MAP_READ | FILE_MAP_WRITE, 0, 0, ostr.size ())); CloseHandle (fm); From cd86558f05b138c8a343244ebfed789672e11296 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Tue, 16 May 2023 23:10:20 -0700 Subject: [PATCH 083/288] Part B of transition to support modernize-use-default-member-init (#5711) --- features/include/pcl/features/3dsc.h | 19 +++---- features/include/pcl/features/board.h | 20 +++---- features/include/pcl/features/crh.h | 7 +-- features/include/pcl/features/cvfh.h | 20 +++---- features/include/pcl/features/flare.h | 18 +++--- features/include/pcl/features/fpfh.h | 4 +- features/include/pcl/features/fpfh_omp.h | 4 +- features/include/pcl/features/gfpfh.h | 7 +-- .../impl/moment_of_inertia_estimation.hpp | 9 +-- .../impl/multiscale_feature_persistence.hpp | 3 +- .../pcl/features/impl/rops_estimation.hpp | 6 +- .../include/pcl/features/impl/spin_image.hpp | 3 +- .../include/pcl/features/integral_image2D.h | 13 ++--- .../pcl/features/integral_image_normal.h | 57 +++++++------------ .../include/pcl/features/intensity_gradient.h | 4 +- .../include/pcl/features/intensity_spin.h | 8 +-- .../features/linear_least_squares_normal.h | 11 ++-- .../features/moment_of_inertia_estimation.h | 14 ++--- .../features/multiscale_feature_persistence.h | 4 +- features/include/pcl/features/narf.h | 12 ++-- .../include/pcl/features/narf_descriptor.h | 8 +-- features/include/pcl/features/normal_3d.h | 10 +--- .../pcl/features/normal_based_signature.h | 11 +--- .../pcl/features/organized_edge_detection.h | 23 +++----- features/include/pcl/features/our_cvfh.h | 16 +++--- features/include/pcl/features/pfh.h | 9 ++- features/include/pcl/features/pfhrgb.h | 4 +- .../features/range_image_border_extractor.h | 38 ++++++------- features/include/pcl/features/rift.h | 6 +- .../include/pcl/features/rops_estimation.h | 10 ++-- features/include/pcl/features/rsd.h | 8 +-- features/include/pcl/features/shot.h | 28 ++++----- features/include/pcl/features/spin_image.h | 8 +-- features/include/pcl/features/usc.h | 18 +++--- features/include/pcl/features/vfh.h | 19 +++---- features/src/narf.cpp | 8 +-- features/src/range_image_border_extractor.cpp | 5 +- .../include/pcl/sample_consensus/sac_model.h | 4 +- 38 files changed, 194 insertions(+), 282 deletions(-) diff --git a/features/include/pcl/features/3dsc.h b/features/include/pcl/features/3dsc.h index cf743a13d42..65bac7c1cf3 100644 --- a/features/include/pcl/features/3dsc.h +++ b/features/include/pcl/features/3dsc.h @@ -97,12 +97,7 @@ namespace pcl theta_divisions_(0), phi_divisions_(0), volume_lut_(0), - azimuth_bins_(12), - elevation_bins_(11), - radius_bins_(15), - min_radius_(0.1), - point_density_radius_(0.2), - descriptor_length_ (), + rng_dist_ (0.0f, 1.0f) { feature_name_ = "ShapeContext3DEstimation"; @@ -197,22 +192,22 @@ namespace pcl std::vector volume_lut_; /** \brief Bins along the azimuth dimension */ - std::size_t azimuth_bins_; + std::size_t azimuth_bins_{12}; /** \brief Bins along the elevation dimension */ - std::size_t elevation_bins_; + std::size_t elevation_bins_{11}; /** \brief Bins along the radius dimension */ - std::size_t radius_bins_; + std::size_t radius_bins_{15}; /** \brief Minimal radius value */ - double min_radius_; + double min_radius_{0.1}; /** \brief Point density radius */ - double point_density_radius_; + double point_density_radius_{0.2}; /** \brief Descriptor length */ - std::size_t descriptor_length_; + std::size_t descriptor_length_{}; /** \brief Random number generator algorithm. */ std::mt19937 rng_; diff --git a/features/include/pcl/features/board.h b/features/include/pcl/features/board.h index 2e323ca4775..2debbf0f24b 100644 --- a/features/include/pcl/features/board.h +++ b/features/include/pcl/features/board.h @@ -62,13 +62,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Constructor. */ - BOARDLocalReferenceFrameEstimation () : - tangent_radius_ (0.0f), - find_holes_ (false), - margin_thresh_ (0.85f), - check_margin_array_size_ (24), - hole_size_prob_thresh_ (0.2f), - steep_thresh_ (0.1f) + BOARDLocalReferenceFrameEstimation () { feature_name_ = "BOARDLocalReferenceFrameEstimation"; setCheckMarginArraySize (check_margin_array_size_); @@ -331,22 +325,22 @@ namespace pcl private: /** \brief Radius used to find tangent axis. */ - float tangent_radius_; + float tangent_radius_{0.0f}; /** \brief If true, check if support is complete or has missing regions because it is too near to mesh borders. */ - bool find_holes_; + bool find_holes_{false}; /** \brief Threshold that define if a support point is near the margins. */ - float margin_thresh_; + float margin_thresh_{0.85f}; /** \brief Number of slices that divide the support in order to determine if a missing region is present. */ - int check_margin_array_size_; + int check_margin_array_size_{24}; /** \brief Threshold used to determine a missing region */ - float hole_size_prob_thresh_; + float hole_size_prob_thresh_{0.2f}; /** \brief Threshold that defines if a missing region contains a point with the most different normal. */ - float steep_thresh_; + float steep_thresh_{0.1f}; std::vector check_margin_array_; std::vector margin_array_min_angle_; diff --git a/features/include/pcl/features/crh.h b/features/include/pcl/features/crh.h index 6f64c5cccd0..ceb583c4208 100644 --- a/features/include/pcl/features/crh.h +++ b/features/include/pcl/features/crh.h @@ -74,8 +74,7 @@ namespace pcl using PointCloudOut = typename Feature::PointCloudOut; /** \brief Constructor. */ - CRHEstimation () : - vpx_ (0), vpy_ (0), vpz_ (0), nbins_ (90) + CRHEstimation () { k_ = 1; feature_name_ = "CRHEstimation"; @@ -118,10 +117,10 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Number of bins, this should match the Output type */ - int nbins_; + int nbins_{90}; /** \brief Centroid to be used */ Eigen::Vector4f centroid_; diff --git a/features/include/pcl/features/cvfh.h b/features/include/pcl/features/cvfh.h index 98315b199c9..1c6b0ed3a73 100644 --- a/features/include/pcl/features/cvfh.h +++ b/features/include/pcl/features/cvfh.h @@ -79,13 +79,9 @@ namespace pcl /** \brief Empty constructor. */ CVFHEstimation () : - vpx_ (0), vpy_ (0), vpz_ (0), - leaf_size_ (0.005f), - normalize_bins_ (false), - curv_threshold_ (0.03f), + cluster_tolerance_ (leaf_size_ * 3), - eps_angle_threshold_ (0.125f), - min_points_ (50), + radius_normals_ (leaf_size_ * 3) { search_radius_ = 0; @@ -216,29 +212,29 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel * size of the training data or the normalize_bins_ flag must be set to true. */ - float leaf_size_; + float leaf_size_{0.005f}; /** \brief Whether to normalize the signatures or not. Default: false. */ - bool normalize_bins_; + bool normalize_bins_{false}; /** \brief Curvature threshold for removing normals. */ - float curv_threshold_; + float curv_threshold_{0.03f}; /** \brief allowed Euclidean distance between points to be added to the cluster. */ float cluster_tolerance_; /** \brief deviation of the normals between two points so they can be clustered together. */ - float eps_angle_threshold_; + float eps_angle_threshold_{0.125f}; /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH * computation. */ - std::size_t min_points_; + std::size_t min_points_{50}; /** \brief Radius for the normals computation. */ float radius_normals_; diff --git a/features/include/pcl/features/flare.h b/features/include/pcl/features/flare.h index be47ba868e6..d03acd3b845 100644 --- a/features/include/pcl/features/flare.h +++ b/features/include/pcl/features/flare.h @@ -90,13 +90,9 @@ namespace pcl public: /** \brief Constructor. */ FLARELocalReferenceFrameEstimation () : - tangent_radius_ (0.0f), - margin_thresh_ (0.85f), - min_neighbors_for_normal_axis_ (6), - min_neighbors_for_tangent_axis_ (6), + sampled_surface_ (), - sampled_tree_ (), - fake_sampled_surface_ (false) + sampled_tree_ () { feature_name_ = "FLARELocalReferenceFrameEstimation"; } @@ -253,16 +249,16 @@ namespace pcl private: /** \brief Radius used to find tangent axis. */ - float tangent_radius_; + float tangent_radius_{0.0f}; /** \brief Threshold that define if a support point is near the margins. */ - float margin_thresh_; + float margin_thresh_{0.85f}; /** \brief Min number of neighbours required for the computation of Z axis. Otherwise, feature point normal is used. */ - int min_neighbors_for_normal_axis_; + int min_neighbors_for_normal_axis_{6}; /** \brief Min number of neighbours required for the computation of X axis. Otherwise, a random X axis is set */ - int min_neighbors_for_tangent_axis_; + int min_neighbors_for_tangent_axis_{6}; /** \brief An input point cloud describing the surface that is to be used * for nearest neighbor searches for the estimation of X axis. @@ -279,7 +275,7 @@ namespace pcl std::vector signed_distances_from_highest_points_; /** \brief If no sampled_surface_ is given, we use surface_ as the sampled surface. */ - bool fake_sampled_surface_; + bool fake_sampled_surface_{false}; }; diff --git a/features/include/pcl/features/fpfh.h b/features/include/pcl/features/fpfh.h index f2e742750b9..ee04bfef7ca 100644 --- a/features/include/pcl/features/fpfh.h +++ b/features/include/pcl/features/fpfh.h @@ -93,7 +93,7 @@ namespace pcl /** \brief Empty constructor. */ FPFHEstimation () : - nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11), + d_pi_ (1.0f / (2.0f * static_cast (M_PI))) { feature_name_ = "FPFHEstimation"; @@ -197,7 +197,7 @@ namespace pcl computeFeature (PointCloudOut &output) override; /** \brief The number of subdivisions for each angular feature interval. */ - int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_; + int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11}; /** \brief Placeholder for the f1 histogram. */ Eigen::MatrixXf hist_f1_; diff --git a/features/include/pcl/features/fpfh_omp.h b/features/include/pcl/features/fpfh_omp.h index fd7e49a339f..2b7de4eaf96 100644 --- a/features/include/pcl/features/fpfh_omp.h +++ b/features/include/pcl/features/fpfh_omp.h @@ -94,7 +94,7 @@ namespace pcl /** \brief Initialize the scheduler and set the number of threads to use. * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic) */ - FPFHEstimationOMP (unsigned int nr_threads = 0) : nr_bins_f1_ (11), nr_bins_f2_ (11), nr_bins_f3_ (11) + FPFHEstimationOMP (unsigned int nr_threads = 0) { feature_name_ = "FPFHEstimationOMP"; @@ -118,7 +118,7 @@ namespace pcl public: /** \brief The number of subdivisions for each angular feature interval. */ - int nr_bins_f1_, nr_bins_f2_, nr_bins_f3_; + int nr_bins_f1_{11}, nr_bins_f2_{11}, nr_bins_f3_{11}; private: /** \brief The number of threads the scheduler should use. */ unsigned int threads_; diff --git a/features/include/pcl/features/gfpfh.h b/features/include/pcl/features/gfpfh.h index 64426f4e616..dedcc41a4ea 100644 --- a/features/include/pcl/features/gfpfh.h +++ b/features/include/pcl/features/gfpfh.h @@ -82,8 +82,7 @@ namespace pcl /** \brief Empty constructor. */ GFPFHEstimation () : - octree_leaf_size_ (0.01), - number_of_classes_ (16), + descriptor_size_ (PointOutT::descriptorSize ()) { feature_name_ = "GFPFHEstimation"; @@ -162,10 +161,10 @@ namespace pcl private: /** \brief Size of octree leaves. */ - double octree_leaf_size_; + double octree_leaf_size_{0.01}; /** \brief Number of possible classes/labels. */ - std::uint32_t number_of_classes_; + std::uint32_t number_of_classes_{16}; /** \brief Dimension of the descriptors. */ int descriptor_size_; diff --git a/features/include/pcl/features/impl/moment_of_inertia_estimation.hpp b/features/include/pcl/features/impl/moment_of_inertia_estimation.hpp index 009443e666b..51f7f9e098e 100644 --- a/features/include/pcl/features/impl/moment_of_inertia_estimation.hpp +++ b/features/include/pcl/features/impl/moment_of_inertia_estimation.hpp @@ -48,17 +48,12 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pcl::MomentOfInertiaEstimation::MomentOfInertiaEstimation () : - is_valid_ (false), - step_ (10.0f), - point_mass_ (0.0001f), - normalize_ (true), + mean_value_ (0.0f, 0.0f, 0.0f), major_axis_ (0.0f, 0.0f, 0.0f), middle_axis_ (0.0f, 0.0f, 0.0f), minor_axis_ (0.0f, 0.0f, 0.0f), - major_value_ (0.0f), - middle_value_ (0.0f), - minor_value_ (0.0f), + aabb_min_point_ (), aabb_max_point_ (), obb_min_point_ (), diff --git a/features/include/pcl/features/impl/multiscale_feature_persistence.hpp b/features/include/pcl/features/impl/multiscale_feature_persistence.hpp index a44ec8b148c..5563efecbe5 100644 --- a/features/include/pcl/features/impl/multiscale_feature_persistence.hpp +++ b/features/include/pcl/features/impl/multiscale_feature_persistence.hpp @@ -45,8 +45,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////// template pcl::MultiscaleFeaturePersistence::MultiscaleFeaturePersistence () : - alpha_ (0), - distance_metric_ (L1), + feature_estimator_ (), features_at_scale_ (), feature_representation_ () diff --git a/features/include/pcl/features/impl/rops_estimation.hpp b/features/include/pcl/features/impl/rops_estimation.hpp index ef80b346e26..510153637df 100644 --- a/features/include/pcl/features/impl/rops_estimation.hpp +++ b/features/include/pcl/features/impl/rops_estimation.hpp @@ -49,11 +49,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pcl::ROPSEstimation ::ROPSEstimation () : - number_of_bins_ (5), - number_of_rotations_ (3), - support_radius_ (1.0f), - sqr_support_radius_ (1.0f), - step_ (22.5f), + triangles_ (0), triangles_of_the_point_ (0) { diff --git a/features/include/pcl/features/impl/spin_image.hpp b/features/include/pcl/features/impl/spin_image.hpp index 1741ec48375..0cc6671f802 100644 --- a/features/include/pcl/features/impl/spin_image.hpp +++ b/features/include/pcl/features/impl/spin_image.hpp @@ -52,8 +52,7 @@ template pcl::SpinImageEstimation::SpinImageEstimation ( unsigned int image_width, double support_angle_cos, unsigned int min_pts_neighb) : input_normals_ (), rotation_axes_cloud_ (), - is_angular_ (false), rotation_axis_ (), use_custom_axis_(false), use_custom_axes_cloud_ (false), - is_radial_ (false), support_angle_cos_ (support_angle_cos), + rotation_axis_ (), support_angle_cos_ (support_angle_cos), min_pts_neighb_ (min_pts_neighb) { if (0.0 > support_angle_cos || support_angle_cos > 1.0) { // may be permit negative cosine? diff --git a/features/include/pcl/features/integral_image2D.h b/features/include/pcl/features/integral_image2D.h index 5d4e778494b..92f0e53df05 100644 --- a/features/include/pcl/features/integral_image2D.h +++ b/features/include/pcl/features/integral_image2D.h @@ -121,8 +121,7 @@ namespace pcl IntegralImage2D (bool compute_second_order_integral_images) : first_order_integral_image_ (), second_order_integral_image_ (), - width_ (1), - height_ (1), + compute_second_order_integral_images_ (compute_second_order_integral_images) { } @@ -218,9 +217,9 @@ namespace pcl std::vector finite_values_integral_image_; /** \brief The width of the 2d input data array */ - unsigned width_; + unsigned width_{1}; /** \brief The height of the 2d input data array */ - unsigned height_; + unsigned height_{1}; /** \brief Indicates whether second order integral images are available **/ bool compute_second_order_integral_images_; @@ -247,7 +246,7 @@ namespace pcl first_order_integral_image_ (), second_order_integral_image_ (), - width_ (1), height_ (1), + compute_second_order_integral_images_ (compute_second_order_integral_images) { } @@ -337,9 +336,9 @@ namespace pcl std::vector finite_values_integral_image_; /** \brief The width of the 2d input data array */ - unsigned width_; + unsigned width_{1}; /** \brief The height of the 2d input data array */ - unsigned height_; + unsigned height_{1}; /** \brief Indicates whether second order integral images are available **/ bool compute_second_order_integral_images_; diff --git a/features/include/pcl/features/integral_image_normal.h b/features/include/pcl/features/integral_image_normal.h index e4baa843a9a..36289dbaa2d 100644 --- a/features/include/pcl/features/integral_image_normal.h +++ b/features/include/pcl/features/integral_image_normal.h @@ -107,28 +107,11 @@ namespace pcl IntegralImageNormalEstimation () : normal_estimation_method_(AVERAGE_3D_GRADIENT) , border_policy_ (BORDER_POLICY_IGNORE) - , rect_width_ (0), rect_width_2_ (0), rect_width_4_ (0) - , rect_height_ (0), rect_height_2_ (0), rect_height_4_ (0) - , distance_threshold_ (0) - , integral_image_DX_ (false) + , integral_image_DX_ (false) , integral_image_DY_ (false) , integral_image_depth_ (false) , integral_image_XYZ_ (true) - , diff_x_ (nullptr) - , diff_y_ (nullptr) - , depth_data_ (nullptr) - , distance_map_ (nullptr) - , use_depth_dependent_smoothing_ (false) , max_depth_change_factor_ (20.0f*0.001f) - , normal_smoothing_size_ (10.0f) - , init_covariance_matrix_ (false) - , init_average_3d_gradient_ (false) - , init_simple_3d_gradient_ (false) - , init_depth_change_ (false) - , vpx_ (0.0f) - , vpy_ (0.0f) - , vpz_ (0.0f) - , use_sensor_origin_ (true) { feature_name_ = "IntegralImagesNormalEstimation"; tree_.reset (); @@ -385,16 +368,16 @@ namespace pcl BorderPolicy border_policy_; /** The width of the neighborhood region used for computing the normal. */ - int rect_width_; - int rect_width_2_; - int rect_width_4_; + int rect_width_{0}; + int rect_width_2_{0}; + int rect_width_4_{0}; /** The height of the neighborhood region used for computing the normal. */ - int rect_height_; - int rect_height_2_; - int rect_height_4_; + int rect_height_{0}; + int rect_height_2_{0}; + int rect_height_4_{0}; /** the threshold used to detect depth discontinuities */ - float distance_threshold_; + float distance_threshold_{0}; /** integral image in x-direction */ IntegralImage2D integral_image_DX_; @@ -406,43 +389,43 @@ namespace pcl IntegralImage2D integral_image_XYZ_; /** derivatives in x-direction */ - float *diff_x_; + float *diff_x_{nullptr}; /** derivatives in y-direction */ - float *diff_y_; + float *diff_y_{nullptr}; /** depth data */ - float *depth_data_; + float *depth_data_{nullptr}; /** distance map */ - float *distance_map_; + float *distance_map_{nullptr}; /** \brief Smooth data based on depth (true/false). */ - bool use_depth_dependent_smoothing_; + bool use_depth_dependent_smoothing_{false}; /** \brief Threshold for detecting depth discontinuities */ float max_depth_change_factor_; /** \brief */ - float normal_smoothing_size_; + float normal_smoothing_size_{10.0f}; /** \brief True when a dataset has been received and the covariance_matrix data has been initialized. */ - bool init_covariance_matrix_; + bool init_covariance_matrix_{false}; /** \brief True when a dataset has been received and the average 3d gradient data has been initialized. */ - bool init_average_3d_gradient_; + bool init_average_3d_gradient_{false}; /** \brief True when a dataset has been received and the simple 3d gradient data has been initialized. */ - bool init_simple_3d_gradient_; + bool init_simple_3d_gradient_{false}; /** \brief True when a dataset has been received and the depth change data has been initialized. */ - bool init_depth_change_; + bool init_depth_change_{false}; /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/ - bool use_sensor_origin_; + bool use_sensor_origin_{true}; /** \brief This method should get called before starting the actual computation. */ bool diff --git a/features/include/pcl/features/intensity_gradient.h b/features/include/pcl/features/intensity_gradient.h index 768fb71a6c0..d12d01e2d75 100644 --- a/features/include/pcl/features/intensity_gradient.h +++ b/features/include/pcl/features/intensity_gradient.h @@ -69,7 +69,7 @@ namespace pcl using PointCloudOut = typename Feature::PointCloudOut; /** \brief Empty constructor. */ - IntensityGradientEstimation () : intensity_ (), threads_ (0) + IntensityGradientEstimation () : intensity_ () { feature_name_ = "IntensityGradientEstimation"; }; @@ -108,7 +108,7 @@ namespace pcl ///intensity field accessor structure IntensitySelectorT intensity_; ///number of threads to be used, default 0 (auto) - unsigned int threads_; + unsigned int threads_{0}; }; } diff --git a/features/include/pcl/features/intensity_spin.h b/features/include/pcl/features/intensity_spin.h index 6af285a1474..5f66a4a6f2a 100644 --- a/features/include/pcl/features/intensity_spin.h +++ b/features/include/pcl/features/intensity_spin.h @@ -74,7 +74,7 @@ namespace pcl using PointCloudOut = typename Feature::PointCloudOut; /** \brief Empty constructor. */ - IntensitySpinEstimation () : nr_distance_bins_ (4), nr_intensity_bins_ (5), sigma_ (1.0) + IntensitySpinEstimation () { feature_name_ = "IntensitySpinEstimation"; }; @@ -135,13 +135,13 @@ namespace pcl computeFeature (PointCloudOut &output) override; /** \brief The number of distance bins in the descriptor. */ - int nr_distance_bins_; + int nr_distance_bins_{4}; /** \brief The number of intensity bins in the descriptor. */ - int nr_intensity_bins_; + int nr_intensity_bins_{5}; /** \brief The standard deviation of the Gaussian smoothing kernel used to construct the spin images. */ - float sigma_; + float sigma_{1.0}; }; } diff --git a/features/include/pcl/features/linear_least_squares_normal.h b/features/include/pcl/features/linear_least_squares_normal.h index bf2ce2e1794..115e07d4b53 100644 --- a/features/include/pcl/features/linear_least_squares_normal.h +++ b/features/include/pcl/features/linear_least_squares_normal.h @@ -59,10 +59,7 @@ namespace pcl using Feature::k_; /** \brief Constructor */ - LinearLeastSquaresNormalEstimation () : - use_depth_dependent_smoothing_(false), - max_depth_change_factor_(1.0f), - normal_smoothing_size_(9.0f) + LinearLeastSquaresNormalEstimation () { feature_name_ = "LinearLeastSquaresNormalEstimation"; tree_.reset (); @@ -131,13 +128,13 @@ namespace pcl //float distance_threshold_; /** \brief Smooth data based on depth (true/false). */ - bool use_depth_dependent_smoothing_; + bool use_depth_dependent_smoothing_{false}; /** \brief Threshold for detecting depth discontinuities */ - float max_depth_change_factor_; + float max_depth_change_factor_{1.0f}; /** \brief */ - float normal_smoothing_size_; + float normal_smoothing_size_{9.0f}; }; } diff --git a/features/include/pcl/features/moment_of_inertia_estimation.h b/features/include/pcl/features/moment_of_inertia_estimation.h index f827771151e..9d96d407157 100644 --- a/features/include/pcl/features/moment_of_inertia_estimation.h +++ b/features/include/pcl/features/moment_of_inertia_estimation.h @@ -291,16 +291,16 @@ namespace pcl /** \brief Indicates if the stored values (eccentricity, moment of inertia, AABB etc.) * are valid when accessed with the get methods. */ - bool is_valid_; + bool is_valid_{false}; /** \brief Stores the angle step */ - float step_; + float step_{10.0f}; /** \brief Stores the mass of point in the cloud */ - float point_mass_; + float point_mass_{0.0001f}; /** \brief Stores the flag for mass normalization */ - bool normalize_; + bool normalize_{true}; /** \brief Stores the mean value (center of mass) of the cloud */ Eigen::Vector3f mean_value_; @@ -315,13 +315,13 @@ namespace pcl Eigen::Vector3f minor_axis_; /** \brief Major eigen value */ - float major_value_; + float major_value_{0.0f}; /** \brief Middle eigen value */ - float middle_value_; + float middle_value_{0.0f}; /** \brief Minor eigen value */ - float minor_value_; + float minor_value_{0.0f}; /** \brief Stores calculated moments of inertia */ std::vector moment_of_inertia_; diff --git a/features/include/pcl/features/multiscale_feature_persistence.h b/features/include/pcl/features/multiscale_feature_persistence.h index 417d29e507d..3d13dd36a88 100644 --- a/features/include/pcl/features/multiscale_feature_persistence.h +++ b/features/include/pcl/features/multiscale_feature_persistence.h @@ -180,10 +180,10 @@ namespace pcl std::vector scale_values_; /** \brief Parameter that determines if a feature is to be considered unique or not */ - float alpha_; + float alpha_{0}; /** \brief Parameter that determines which distance metric is to be usedto calculate the difference between feature vectors */ - NormType distance_metric_; + NormType distance_metric_{L1}; /** \brief the feature estimator that will be used to determine the feature set at each scale level */ FeatureEstimatorPtr feature_estimator_; diff --git a/features/include/pcl/features/narf.h b/features/include/pcl/features/narf.h index 45dda48a9af..83015b970d0 100644 --- a/features/include/pcl/features/narf.h +++ b/features/include/pcl/features/narf.h @@ -277,12 +277,12 @@ namespace pcl // =====PROTECTED MEMBER VARIABLES===== Eigen::Vector3f position_; Eigen::Affine3f transformation_; - float* surface_patch_; - int surface_patch_pixel_size_; - float surface_patch_world_size_; - float surface_patch_rotation_; - float* descriptor_; - int descriptor_size_; + float* surface_patch_{nullptr}; + int surface_patch_pixel_size_{0}; + float surface_patch_world_size_{}; + float surface_patch_rotation_{}; + float* descriptor_{nullptr}; + int descriptor_size_{0}; // =====STATIC PROTECTED===== diff --git a/features/include/pcl/features/narf_descriptor.h b/features/include/pcl/features/narf_descriptor.h index 9dc2e92660c..af46bb941f7 100644 --- a/features/include/pcl/features/narf_descriptor.h +++ b/features/include/pcl/features/narf_descriptor.h @@ -63,9 +63,9 @@ namespace pcl // =====STRUCTS/CLASSES===== struct Parameters { - Parameters() : support_size(-1.0f), rotation_invariant(true) {} - float support_size; - bool rotation_invariant; + Parameters() = default; + float support_size{-1.0f}; + bool rotation_invariant{true}; }; // =====CONSTRUCTOR & DESTRUCTOR===== @@ -90,7 +90,7 @@ namespace pcl protected: // =====PROTECTED MEMBER VARIABLES===== - const RangeImage* range_image_; + const RangeImage* range_image_{}; Parameters parameters_; // =====PROTECTED METHODS===== diff --git a/features/include/pcl/features/normal_3d.h b/features/include/pcl/features/normal_3d.h index 44aecf6e3d4..49f2417c95d 100644 --- a/features/include/pcl/features/normal_3d.h +++ b/features/include/pcl/features/normal_3d.h @@ -258,11 +258,7 @@ namespace pcl using PointCloudConstPtr = typename Feature::PointCloudConstPtr; /** \brief Empty constructor. */ - NormalEstimation () - : vpx_ (0) - , vpy_ (0) - , vpz_ (0) - , use_sensor_origin_ (true) + NormalEstimation () { feature_name_ = "NormalEstimation"; }; @@ -403,7 +399,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */ EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_; @@ -412,7 +408,7 @@ namespace pcl Eigen::Vector4f xyz_centroid_; /** whether the sensor origin of the input cloud or a user given viewpoint should be used.*/ - bool use_sensor_origin_; + bool use_sensor_origin_{true}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/features/include/pcl/features/normal_based_signature.h b/features/include/pcl/features/normal_based_signature.h index a3576b4460c..9931ae2402d 100644 --- a/features/include/pcl/features/normal_based_signature.h +++ b/features/include/pcl/features/normal_based_signature.h @@ -75,12 +75,7 @@ namespace pcl /** \brief Empty constructor, initializes the internal parameters to the default values */ NormalBasedSignatureEstimation () - : FeatureFromNormals (), - scale_h_ (), - N_ (36), - M_ (8), - N_prime_ (4), - M_prime_ (3) + : FeatureFromNormals () { } @@ -152,8 +147,8 @@ namespace pcl computeFeature (FeatureCloud &output) override; private: - float scale_h_; - std::size_t N_, M_, N_prime_, M_prime_; + float scale_h_{}; + std::size_t N_{36}, M_{8}, N_prime_{4}, M_prime_{3}; }; } diff --git a/features/include/pcl/features/organized_edge_detection.h b/features/include/pcl/features/organized_edge_detection.h index ed5230f4ad3..fee39a76e15 100644 --- a/features/include/pcl/features/organized_edge_detection.h +++ b/features/include/pcl/features/organized_edge_detection.h @@ -74,9 +74,8 @@ namespace pcl /** \brief Constructor for OrganizedEdgeBase */ OrganizedEdgeBase () - : th_depth_discon_ (0.02f) - , max_search_neighbors_ (50) - , detecting_edge_types_ (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED) + : + detecting_edge_types_ (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED) { } @@ -168,10 +167,10 @@ namespace pcl /** \brief The tolerance in meters for the relative difference in depth values between neighboring points * (The default value is set for .02 meters and is adapted with respect to depth value linearly. * e.g. If a point has a depth (z) value of 2.0 meters, a neighboring point is discontinuous if its depth differs by > 2.0 * th. */ - float th_depth_discon_; + float th_depth_discon_{0.02f}; /** \brief The max search distance for deciding occluding and occluded edges */ - int max_search_neighbors_; + int max_search_neighbors_{50}; /** \brief The bit encoded value that represents edge types to detect */ int detecting_edge_types_; @@ -202,8 +201,6 @@ namespace pcl /** \brief Constructor for OrganizedEdgeFromRGB */ OrganizedEdgeFromRGB () : OrganizedEdgeBase () - , th_rgb_canny_low_ (40.0) - , th_rgb_canny_high_ (100.0) { this->setEdgeType (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED | EDGELABEL_RGB_CANNY); } @@ -255,10 +252,10 @@ namespace pcl extractEdges (pcl::PointCloud& labels) const; /** \brief The low threshold value for RGB Canny edge detection (default: 40.0) */ - float th_rgb_canny_low_; + float th_rgb_canny_low_{40.0}; /** \brief The high threshold value for RGB Canny edge detection (default: 100.0) */ - float th_rgb_canny_high_; + float th_rgb_canny_high_{100.0}; }; template @@ -291,9 +288,7 @@ namespace pcl OrganizedEdgeFromNormals () : OrganizedEdgeBase () , normals_ () - , th_hc_canny_low_ (0.4f) - , th_hc_canny_high_ (1.1f) - { + { this->setEdgeType (EDGELABEL_NAN_BOUNDARY | EDGELABEL_OCCLUDING | EDGELABEL_OCCLUDED | EDGELABEL_HIGH_CURVATURE); } @@ -363,10 +358,10 @@ namespace pcl PointCloudNConstPtr normals_; /** \brief The low threshold value for high curvature Canny edge detection (default: 0.4) */ - float th_hc_canny_low_; + float th_hc_canny_low_{0.4f}; /** \brief The high threshold value for high curvature Canny edge detection (default: 1.1) */ - float th_hc_canny_high_; + float th_hc_canny_high_{1.1f}; }; template diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index f1f42251641..38f17c34618 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -74,8 +74,8 @@ namespace pcl using PointInTPtr = typename pcl::PointCloud::Ptr; /** \brief Empty constructor. */ OURCVFHEstimation () : - vpx_ (0), vpy_ (0), vpz_ (0), leaf_size_ (0.005f), normalize_bins_ (false), curv_threshold_ (0.03f), cluster_tolerance_ (leaf_size_ * 3), - eps_angle_threshold_ (0.125f), min_points_ (50), radius_normals_ (leaf_size_ * 3) + cluster_tolerance_ (leaf_size_ * 3), + radius_normals_ (leaf_size_ * 3) { search_radius_ = 0; k_ = 1; @@ -324,29 +324,29 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel * size of the training data or the normalize_bins_ flag must be set to true. */ - float leaf_size_; + float leaf_size_{0.005f}; /** \brief Whether to normalize the signatures or not. Default: false. */ - bool normalize_bins_; + bool normalize_bins_{false}; /** \brief Curvature threshold for removing normals. */ - float curv_threshold_; + float curv_threshold_{0.03f}; /** \brief allowed Euclidean distance between points to be added to the cluster. */ float cluster_tolerance_; /** \brief deviation of the normals between two points so they can be clustered together. */ - float eps_angle_threshold_; + float eps_angle_threshold_{0.125f}; /** \brief Minimum amount of points in a clustered region to be considered stable for CVFH * computation. */ - std::size_t min_points_; + std::size_t min_points_{50}; /** \brief Radius for the normals computation. */ float radius_normals_; diff --git a/features/include/pcl/features/pfh.h b/features/include/pcl/features/pfh.h index 30df460353b..6b1a49cfd29 100644 --- a/features/include/pcl/features/pfh.h +++ b/features/include/pcl/features/pfh.h @@ -99,12 +99,11 @@ namespace pcl * Sets \a use_cache_ to false, \a nr_subdiv_ to 5, and the internal maximum cache size to 1GB. */ PFHEstimation () : - nr_subdiv_ (5), + d_pi_ (1.0f / (2.0f * static_cast (M_PI))), key_list_ (), // Default 1GB memory size. Need to set it to something more conservative. - max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair, Eigen::Vector4f>)), - use_cache_ (false) + max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair, Eigen::Vector4f>)) { feature_name_ = "PFHEstimation"; }; @@ -189,7 +188,7 @@ namespace pcl computeFeature (PointCloudOut &output) override; /** \brief The number of subdivisions for each angular feature interval. */ - int nr_subdiv_; + int nr_subdiv_{5}; /** \brief Placeholder for a point's PFH signature. */ Eigen::VectorXf pfh_histogram_; @@ -213,7 +212,7 @@ namespace pcl unsigned int max_cache_size_; /** \brief Set to true to use the internal cache for removing redundant computations. */ - bool use_cache_; + bool use_cache_{false}; }; } diff --git a/features/include/pcl/features/pfhrgb.h b/features/include/pcl/features/pfhrgb.h index 60d702f7590..f42f26e11b4 100644 --- a/features/include/pcl/features/pfhrgb.h +++ b/features/include/pcl/features/pfhrgb.h @@ -59,7 +59,7 @@ namespace pcl PFHRGBEstimation () - : nr_subdiv_ (5), d_pi_ (1.0f / (2.0f * static_cast (M_PI))) + : d_pi_ (1.0f / (2.0f * static_cast (M_PI))) { feature_name_ = "PFHRGBEstimation"; } @@ -79,7 +79,7 @@ namespace pcl private: /** \brief The number of subdivisions for each angular feature interval. */ - int nr_subdiv_; + int nr_subdiv_{5}; /** \brief Placeholder for a point's PFHRGB signature. */ Eigen::VectorXf pfhrgb_histogram_; diff --git a/features/include/pcl/features/range_image_border_extractor.h b/features/include/pcl/features/range_image_border_extractor.h index 29ef75c0f3a..a24ea3d3e5a 100644 --- a/features/include/pcl/features/range_image_border_extractor.h +++ b/features/include/pcl/features/range_image_border_extractor.h @@ -64,8 +64,7 @@ namespace pcl //! Stores some information extracted from the neighborhood of a point struct LocalSurface { - LocalSurface () : - max_neighbor_distance_squared () {} + LocalSurface () = default; Eigen::Vector3f normal; Eigen::Vector3f neighborhood_mean; @@ -73,27 +72,26 @@ namespace pcl Eigen::Vector3f normal_no_jumps; Eigen::Vector3f neighborhood_mean_no_jumps; Eigen::Vector3f eigen_values_no_jumps; - float max_neighbor_distance_squared; + float max_neighbor_distance_squared{}; }; //! Stores the indices of the shadow border corresponding to obstacle borders struct ShadowBorderIndices { - ShadowBorderIndices () : left (-1), right (-1), top (-1), bottom (-1) {} - int left, right, top, bottom; + ShadowBorderIndices () = default; + int left{-1}, right{-1}, top{-1}, bottom{-1}; }; //! Parameters used in this class struct Parameters { - Parameters () : max_no_of_threads(1), pixel_radius_borders (3), pixel_radius_plane_extraction (2), pixel_radius_border_direction (2), - minimum_border_probability (0.8f), pixel_radius_principal_curvature (2) {} - int max_no_of_threads; - int pixel_radius_borders; - int pixel_radius_plane_extraction; - int pixel_radius_border_direction; - float minimum_border_probability; - int pixel_radius_principal_curvature; + Parameters () = default; + int max_no_of_threads{1}; + int pixel_radius_borders{3}; + int pixel_radius_plane_extraction{2}; + int pixel_radius_border_direction{2}; + float minimum_border_probability{0.8f}; + int pixel_radius_principal_curvature{2}; }; // =====STATIC METHODS===== @@ -181,16 +179,16 @@ namespace pcl // =====PROTECTED MEMBER VARIABLES===== Parameters parameters_; const RangeImage* range_image_; - int range_image_size_during_extraction_; + int range_image_size_during_extraction_{0}; std::vector border_scores_left_, border_scores_right_; std::vector border_scores_top_, border_scores_bottom_; - LocalSurface** surface_structure_; - PointCloudOut* border_descriptions_; - ShadowBorderIndices** shadow_border_informations_; - Eigen::Vector3f** border_directions_; + LocalSurface** surface_structure_{nullptr}; + PointCloudOut* border_descriptions_{nullptr}; + ShadowBorderIndices** shadow_border_informations_{nullptr}; + Eigen::Vector3f** border_directions_{nullptr}; - float* surface_change_scores_; - Eigen::Vector3f* surface_change_directions_; + float* surface_change_scores_{nullptr}; + Eigen::Vector3f* surface_change_directions_{nullptr}; // =====PROTECTED METHODS===== diff --git a/features/include/pcl/features/rift.h b/features/include/pcl/features/rift.h index 061b262eaeb..84d4ca95f6c 100644 --- a/features/include/pcl/features/rift.h +++ b/features/include/pcl/features/rift.h @@ -80,7 +80,7 @@ namespace pcl /** \brief Empty constructor. */ - RIFTEstimation () : gradient_ (), nr_distance_bins_ (4), nr_gradient_bins_ (8) + RIFTEstimation () : gradient_ () { feature_name_ = "RIFTEstimation"; }; @@ -144,10 +144,10 @@ namespace pcl PointCloudGradientConstPtr gradient_; /** \brief The number of distance bins in the descriptor. */ - int nr_distance_bins_; + int nr_distance_bins_{4}; /** \brief The number of gradient orientation bins in the descriptor. */ - int nr_gradient_bins_; + int nr_gradient_bins_{8}; }; } diff --git a/features/include/pcl/features/rops_estimation.h b/features/include/pcl/features/rops_estimation.h index 6d5cb347405..a34e09fc941 100644 --- a/features/include/pcl/features/rops_estimation.h +++ b/features/include/pcl/features/rops_estimation.h @@ -202,19 +202,19 @@ namespace pcl private: /** \brief Stores the number of partition bins that is used for distribution matrix calculation. */ - unsigned int number_of_bins_; + unsigned int number_of_bins_{5}; /** \brief Stores number of rotations. Central moments are calculated for every rotation. */ - unsigned int number_of_rotations_; + unsigned int number_of_rotations_{3}; /** \brief Support radius that is used to crop the local surface of the point. */ - float support_radius_; + float support_radius_{1.0f}; /** \brief Stores the squared support radius. Used to improve performance. */ - float sqr_support_radius_; + float sqr_support_radius_{1.0f}; /** \brief Stores the angle step. Step is calculated with respect to number of rotations. */ - float step_; + float step_{22.5f}; /** \brief Stores the set of triangles representing the mesh. */ std::vector triangles_; diff --git a/features/include/pcl/features/rsd.h b/features/include/pcl/features/rsd.h index 9eafe82b4d6..eadd0d95d25 100644 --- a/features/include/pcl/features/rsd.h +++ b/features/include/pcl/features/rsd.h @@ -148,7 +148,7 @@ namespace pcl /** \brief Empty constructor. */ - RSDEstimation () : nr_subdiv_ (5), plane_radius_ (0.2), save_histograms_ (false) + RSDEstimation () { feature_name_ = "RadiusSurfaceDescriptor"; }; @@ -220,13 +220,13 @@ namespace pcl private: /** \brief The number of subdivisions for the considered distance interval. */ - int nr_subdiv_; + int nr_subdiv_{5}; /** \brief The maximum radius, above which everything can be considered planar. */ - double plane_radius_; + double plane_radius_{0.2}; /** \brief Signals whether the full distance-angle histograms are being saved. */ - bool save_histograms_; + bool save_histograms_{false}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/features/include/pcl/features/shot.h b/features/include/pcl/features/shot.h index f4672bda483..804c8776627 100644 --- a/features/include/pcl/features/shot.h +++ b/features/include/pcl/features/shot.h @@ -91,12 +91,7 @@ namespace pcl * \param[in] nr_shape_bins the number of bins in the shape histogram */ SHOTEstimationBase (int nr_shape_bins = 10) : - nr_shape_bins_ (nr_shape_bins), - lrf_radius_ (0), - sqradius_ (0), radius3_4_ (0), radius1_4_ (0), radius1_2_ (0), - nr_grid_sector_ (32), - maxAngularSectors_ (32), - descLength_ (0) + nr_shape_bins_ (nr_shape_bins) { feature_name_ = "SHOTEstimation"; }; @@ -170,28 +165,28 @@ namespace pcl int nr_shape_bins_; /** \brief The radius used for the LRF computation */ - float lrf_radius_; + float lrf_radius_{0}; /** \brief The squared search radius. */ - double sqradius_; + double sqradius_{0}; /** \brief 3/4 of the search radius. */ - double radius3_4_; + double radius3_4_{0}; /** \brief 1/4 of the search radius. */ - double radius1_4_; + double radius1_4_{0}; /** \brief 1/2 of the search radius. */ - double radius1_2_; + double radius1_2_{0}; /** \brief Number of azimuthal sectors. */ - const int nr_grid_sector_; + const int nr_grid_sector_{32}; /** \brief ... */ - const int maxAngularSectors_; + const int maxAngularSectors_{32}; /** \brief One SHOT length. */ - int descLength_; + int descLength_{0}; }; /** \brief SHOTEstimation estimates the Signature of Histograms of OrienTations (SHOT) descriptor for @@ -326,8 +321,7 @@ namespace pcl bool describe_color = true) : SHOTEstimationBase (10), b_describe_shape_ (describe_shape), - b_describe_color_ (describe_color), - nr_color_bins_ (30) + b_describe_color_ (describe_color) { feature_name_ = "SHOTColorEstimation"; }; @@ -382,7 +376,7 @@ namespace pcl bool b_describe_color_; /** \brief The number of bins in each color histogram. */ - int nr_color_bins_; + int nr_color_bins_{30}; public: /** \brief Converts RGB triplets to CIELab space. diff --git a/features/include/pcl/features/spin_image.h b/features/include/pcl/features/spin_image.h index e8418b88700..21fff6c0aab 100644 --- a/features/include/pcl/features/spin_image.h +++ b/features/include/pcl/features/spin_image.h @@ -287,13 +287,13 @@ namespace pcl PointCloudNConstPtr input_normals_; PointCloudNConstPtr rotation_axes_cloud_; - bool is_angular_; + bool is_angular_{false}; PointNT rotation_axis_; - bool use_custom_axis_; - bool use_custom_axes_cloud_; + bool use_custom_axis_{false}; + bool use_custom_axes_cloud_{false}; - bool is_radial_; + bool is_radial_{false}; unsigned int image_width_; double support_angle_cos_; diff --git a/features/include/pcl/features/usc.h b/features/include/pcl/features/usc.h index fed3fe8eb3a..0ad9cd2089c 100644 --- a/features/include/pcl/features/usc.h +++ b/features/include/pcl/features/usc.h @@ -83,9 +83,7 @@ namespace pcl /** \brief Constructor. */ UniqueShapeContext () : - radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0), - azimuth_bins_(14), elevation_bins_(14), radius_bins_(10), - min_radius_(0.1), point_density_radius_(0.1), descriptor_length_ (), local_radius_ (2.0) + radii_interval_(0), theta_divisions_(0), phi_divisions_(0), volume_lut_(0) { feature_name_ = "UniqueShapeContext"; search_radius_ = 2.0; @@ -167,25 +165,25 @@ namespace pcl std::vector volume_lut_; /** \brief Bins along the azimuth dimension. */ - std::size_t azimuth_bins_; + std::size_t azimuth_bins_{14}; /** \brief Bins along the elevation dimension. */ - std::size_t elevation_bins_; + std::size_t elevation_bins_{14}; /** \brief Bins along the radius dimension. */ - std::size_t radius_bins_; + std::size_t radius_bins_{10}; /** \brief Minimal radius value. */ - double min_radius_; + double min_radius_{0.1}; /** \brief Point density radius. */ - double point_density_radius_; + double point_density_radius_{0.1}; /** \brief Descriptor length. */ - std::size_t descriptor_length_; + std::size_t descriptor_length_{}; /** \brief Radius to compute local RF. */ - double local_radius_; + double local_radius_{2.0}; }; } diff --git a/features/include/pcl/features/vfh.h b/features/include/pcl/features/vfh.h index d3dae278674..9a8f60b4f39 100644 --- a/features/include/pcl/features/vfh.h +++ b/features/include/pcl/features/vfh.h @@ -88,10 +88,7 @@ namespace pcl /** \brief Empty constructor. */ VFHEstimation () : - nr_bins_f_ ({45, 45, 45, 45}), nr_bins_vp_ (128), - vpx_ (0), vpy_ (0), vpz_ (0), - use_given_normal_ (false), use_given_centroid_ (false), - normalize_bins_ (true), normalize_distances_ (false), size_component_ (false), + nr_bins_f_ ({45, 45, 45, 45}), d_pi_ (1.0f / (2.0f * static_cast (M_PI))) { for (int i = 0; i < 4; ++i) @@ -215,12 +212,12 @@ namespace pcl /** \brief The number of subdivisions for each feature interval. */ std::array nr_bins_f_; - int nr_bins_vp_; + int nr_bins_vp_{128}; /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit * from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Estimate the Viewpoint Feature Histograms (VFH) descriptors at a set of points given by * using the surface in setSearchSurface () and the spatial locator in @@ -248,15 +245,15 @@ namespace pcl // VFH configuration parameters because CVFH instantiates it. See constructor for default values. /** \brief Use the normal_to_use_ */ - bool use_given_normal_; + bool use_given_normal_{false}; /** \brief Use the centroid_to_use_ */ - bool use_given_centroid_; + bool use_given_centroid_{false}; /** \brief Normalize bins by the number the total number of points. */ - bool normalize_bins_; + bool normalize_bins_{true}; /** \brief Normalize the shape distribution component of VFH */ - bool normalize_distances_; + bool normalize_distances_{false}; /** \brief Activate or deactivate the size component of VFH */ - bool size_component_; + bool size_component_{false}; private: /** \brief Float constant = 1.0 / (2.0 * M_PI) */ diff --git a/features/src/narf.cpp b/features/src/narf.cpp index 8e07b71270d..54ab40463d8 100644 --- a/features/src/narf.cpp +++ b/features/src/narf.cpp @@ -55,10 +55,7 @@ namespace pcl int Narf::max_no_of_threads = 1; ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// -Narf::Narf() : - surface_patch_ (nullptr), - surface_patch_pixel_size_ (0), surface_patch_world_size_ (), - surface_patch_rotation_ (), descriptor_ (nullptr), descriptor_size_ (0) +Narf::Narf() { reset(); } @@ -604,8 +601,7 @@ Narf::loadBinary (const std::string& filename) ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// -NarfDescriptor::NarfDescriptor (const RangeImage* range_image, const pcl::Indices* indices) : - range_image_ () +NarfDescriptor::NarfDescriptor (const RangeImage* range_image, const pcl::Indices* indices) { setRangeImage (range_image, indices); } diff --git a/features/src/range_image_border_extractor.cpp b/features/src/range_image_border_extractor.cpp index d44521990b2..6590b57aa45 100644 --- a/features/src/range_image_border_extractor.cpp +++ b/features/src/range_image_border_extractor.cpp @@ -49,10 +49,7 @@ namespace pcl { /////////////////////////////////////////////////////////////////////////////////////////////////////////////// -RangeImageBorderExtractor::RangeImageBorderExtractor(const RangeImage* range_image) : - range_image_(range_image), range_image_size_during_extraction_(0), - surface_structure_(nullptr), border_descriptions_(nullptr), shadow_border_informations_(nullptr), border_directions_(nullptr), - surface_change_scores_(nullptr), surface_change_directions_(nullptr) +RangeImageBorderExtractor::RangeImageBorderExtractor(const RangeImage* range_image) : range_image_(range_image) { } diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model.h b/sample_consensus/include/pcl/sample_consensus/sac_model.h index 88fa2e9b98a..a1f3a91980a 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model.h @@ -618,7 +618,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Empty constructor for base SampleConsensusModelFromNormals. */ - SampleConsensusModelFromNormals () : normal_distance_weight_ (0.0), normals_ () {}; + SampleConsensusModelFromNormals () : normals_ () {}; /** \brief Destructor. */ virtual ~SampleConsensusModelFromNormals () = default; @@ -662,7 +662,7 @@ namespace pcl /** \brief The relative weight (between 0 and 1) to give to the angular * distance (0 to pi/2) between point normals and the plane normal. */ - double normal_distance_weight_; + double normal_distance_weight_{0.0}; /** \brief A pointer to the input dataset that contains the point normals * of the XYZ dataset. From ba220d9788c5992abf485dcf60ef2f3697334618 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 18 May 2023 11:49:10 +0200 Subject: [PATCH 084/288] Improve spinOnce documentation --- visualization/include/pcl/visualization/pcl_visualizer.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 577a2d3c25a..62e80ba99e3 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -288,6 +288,8 @@ namespace pcl * \param[in] time - How long (in ms) should the visualization loop be allowed to run. * \param[in] force_redraw - if false it might return without doing anything if the * interactor's framerate does not require a redraw yet. + * \note This function may not return immediately after the specified time has elapsed, for example if + * the user continues to interact with the visualizer, meaning that there are still events to process. */ void spinOnce (int time = 1, bool force_redraw = false); From 60ca30c80f0d7e1fbbdb32c1e83226e7d712008b Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 22 May 2023 09:00:59 +0200 Subject: [PATCH 085/288] Else the if below would always be false, which ruled out SSE_FLAGS, AVX_FLAGS and settings about OpenMP. --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b383dd895ba..8aef351b5af 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -146,7 +146,6 @@ endif() if(CMAKE_COMPILER_IS_MSVC) add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX -DPCL_ONLY_CORE_POINT_TYPES ${SSE_DEFINITIONS}") - string(APPEND CMAKE_CXX_FLAGS " /bigobj") if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS}") @@ -203,6 +202,7 @@ if(CMAKE_COMPILER_IS_MSVC) endif() endif() endif() + string(APPEND CMAKE_CXX_FLAGS " /bigobj") if(CMAKE_GENERATOR STREQUAL "Ninja") string(APPEND CMAKE_C_FLAGS " /FS") From 788c53eab2123df25e5eb34f45d2ed7dfe6cb48b Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 23 May 2023 19:55:13 +0200 Subject: [PATCH 086/288] Avoid accessing vectors with zero length, by checking data sizes. (#5708) * Avoid accessing vectors with zero length, by checking data sizes. * Use empty rather than size() > 0. * Update per review suggestions. Remove setting info fields in pcd_io.h but instead check for msg.data.size in fromPCLPointCloud2, where fields are set. Remove unnecessary check in readHeader. * Use msg width and height to determine if there are points. Readd warning in PCDReader::readHeader. * Return after resizing output cloud. Use .data instead of acquiring address of index 0. --- common/include/pcl/conversions.h | 15 +++++-- io/include/pcl/io/pcd_io.h | 1 + io/src/pcd_io.cpp | 76 +++++++++++++++++--------------- 3 files changed, 54 insertions(+), 38 deletions(-) diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 6acb023e73b..631b7443c68 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -169,9 +169,18 @@ namespace pcl cloud.height = msg.height; cloud.is_dense = msg.is_dense == 1; - // Copy point data + // Resize cloud cloud.resize (msg.width * msg.height); - std::uint8_t* cloud_data = reinterpret_cast(&cloud[0]); + + // check if there is data to copy + if (msg.width * msg.height == 0) + { + PCL_WARN("[pcl::fromPCLPointCloud2] No data to copy.\n"); + return; + } + + // Copy point data + std::uint8_t* cloud_data = reinterpret_cast(cloud.data()); // Check if we can copy adjacent points in a single memcpy. We can do so if there // is exactly one field to copy and it is the same size as the source and destination @@ -272,7 +281,7 @@ namespace pcl msg.data.resize (data_size); if (data_size) { - memcpy(&msg.data[0], &cloud[0], data_size); + memcpy(msg.data.data(), cloud.data(), data_size); } // Fill fields metadata diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index cc6cb2a8768..0131b5bf9d4 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -284,6 +284,7 @@ namespace pcl // If no error, convert the data if (res == 0) pcl::fromPCLPointCloud2 (blob, cloud); + return (res); } diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index a026dca9dd3..7cd5be9cf15 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -341,9 +341,9 @@ pcl::PCDReader::readHeader (std::istream &fs, pcl::PCLPointCloud2 &cloud, if (nr_points == 0) { - PCL_WARN ("[pcl::PCDReader::readHeader] No points to read\n"); + PCL_WARN("[pcl::PCDReader::readHeader] number of points is zero.\n"); } - + // Compatibility with older PCD file versions if (!width_read && !height_read) { @@ -557,6 +557,11 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c } auto data_size = static_cast (cloud.data.size ()); + if (data_size == 0) + { + PCL_WARN("[pcl::PCDReader::read] Binary compressed file has data size of zero.\n"); + return 0; + } std::vector buf (data_size); // The size of the uncompressed data better be the same as what we stored in the header unsigned int tmp_size = pcl::lzfDecompress (&map[data_idx + 8], compressed_size, buf.data(), data_size); @@ -1369,42 +1374,43 @@ pcl::PCDWriter::writeBinaryCompressed (std::ostream &os, const pcl::PCLPointClou return (-2); } - ////////////////////////////////////////////////////////////////////// - // Empty array holding only the valid data - // data_size = nr_points * point_size - // = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n) - // = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... sizeof_field_n * nr_points - std::vector only_valid_data (data_size); - - // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For - // this, we need a vector of fields.size () (4 in this case), which points to - // each individual plane: - // pters[0] = &only_valid_data[offset_of_plane_x]; - // pters[1] = &only_valid_data[offset_of_plane_y]; - // pters[2] = &only_valid_data[offset_of_plane_z]; - // pters[3] = &only_valid_data[offset_of_plane_RGB]; - // - std::vector pters (fields.size ()); - std::size_t toff = 0; - for (std::size_t i = 0; i < pters.size (); ++i) - { - pters[i] = &only_valid_data[toff]; - toff += fields_sizes[i] * cloud.width * cloud.height; - } + std::vector temp_buf (data_size * 3 / 2 + 8); + if (data_size != 0) { - // Go over all the points, and copy the data in the appropriate places - for (uindex_t i = 0; i < cloud.width * cloud.height; ++i) - { - for (std::size_t j = 0; j < pters.size (); ++j) - { - memcpy (pters[j], &cloud.data[i * cloud.point_step + fields[j].offset], fields_sizes[j]); - // Increment the pointer - pters[j] += fields_sizes[j]; + ////////////////////////////////////////////////////////////////////// + // Empty array holding only the valid data + // data_size = nr_points * point_size + // = nr_points * (sizeof_field_1 + sizeof_field_2 + ... sizeof_field_n) + // = sizeof_field_1 * nr_points + sizeof_field_2 * nr_points + ... + // sizeof_field_n * nr_points + std::vector only_valid_data(data_size); + + // Convert the XYZRGBXYZRGB structure to XXYYZZRGBRGB to aid compression. For + // this, we need a vector of fields.size () (4 in this case), which points to + // each individual plane: + // pters[0] = &only_valid_data[offset_of_plane_x]; + // pters[1] = &only_valid_data[offset_of_plane_y]; + // pters[2] = &only_valid_data[offset_of_plane_z]; + // pters[3] = &only_valid_data[offset_of_plane_RGB]; + // + std::vector pters(fields.size()); + std::size_t toff = 0; + for (std::size_t i = 0; i < pters.size(); ++i) { + pters[i] = &only_valid_data[toff]; + toff += fields_sizes[i] * cloud.width * cloud.height; + } + + // Go over all the points, and copy the data in the appropriate places + for (uindex_t i = 0; i < cloud.width * cloud.height; ++i) { + for (std::size_t j = 0; j < pters.size(); ++j) { + memcpy(pters[j], + &cloud.data[i * cloud.point_step + fields[j].offset], + fields_sizes[j]); + // Increment the pointer + pters[j] += fields_sizes[j]; + } } - } - std::vector temp_buf (data_size * 3 / 2 + 8); - if (data_size != 0) { // Compress the valid data unsigned int compressed_size = pcl::lzfCompress (&only_valid_data.front (), static_cast (data_size), From 348bf9cb09204f801bbdd48faa10805f317b288c Mon Sep 17 00:00:00 2001 From: Kilian van Berlo Date: Tue, 23 May 2023 19:03:36 +0000 Subject: [PATCH 087/288] Fix bug for tracking object rotation (#5538) * Fix bug for tracking object rotation The current object tracking particle filter fails to track full circle Hence, for each iteration we have to: 1. Convert angles to Cartesian coords and average x and y separately 2. Convert back to the angles using the arctangent Now PCL is able to track objects in full 360 rotation * Fix bug for tracking object rotation The current object tracking particle filter fails to track full circle Hence, for each iteration we have to: 1. Convert angles to Cartesian coords and average x and y separately 2. Convert back to the angles using the arctangent Now PCL is able to track objects in full 360 rotation * Weighted average function with specializations for particle pose * Removed empty lines for code formatting * Added empty lines in the end for code formatting * Formatting complies with the patch file * Formatting complies with the 2nd patch file * Formatting complies with the 3rd patch file * Formatting complies with the 4th patch file * Formatting complies with the 5th patch file * Implement WeightedAverage specializations as struct member functions * Implement correct WeightedAverage struct member functions * Adjusted weighted average calculations according to particle definitions * Small cosine calculation optimisation * Minor code quality adjustments * Resolved type definition confusion * Update tracking/include/pcl/tracking/impl/particle_filter.hpp Earlier on the .points has been used but its bad design to expose the internal data structure, so we do not want to use .points directly. Co-authored-by: Lars Glud --------- Co-authored-by: Markus Vieth Co-authored-by: Lars Glud --- .../pcl/tracking/impl/particle_filter.hpp | 6 +- .../include/pcl/tracking/impl/tracking.hpp | 105 ++++++++++++++++++ tracking/include/pcl/tracking/tracking.h | 3 + 3 files changed, 110 insertions(+), 4 deletions(-) diff --git a/tracking/include/pcl/tracking/impl/particle_filter.hpp b/tracking/include/pcl/tracking/impl/particle_filter.hpp index ab55443d3b1..3fbd503b99b 100644 --- a/tracking/include/pcl/tracking/impl/particle_filter.hpp +++ b/tracking/include/pcl/tracking/impl/particle_filter.hpp @@ -365,13 +365,11 @@ template void ParticleFilterTracker::update() { - StateT orig_representative = representative_state_; representative_state_.zero(); representative_state_.weight = 0.0; - for (const auto& p : *particles_) { - representative_state_ = representative_state_ + p * p.weight; - } + representative_state_ = + StateT::weightedAverage(particles_->begin(), particles_->end()); representative_state_.weight = 1.0f / static_cast(particles_->size()); motion_ = representative_state_ - orig_representative; } diff --git a/tracking/include/pcl/tracking/impl/tracking.hpp b/tracking/include/pcl/tracking/impl/tracking.hpp index 5ef653a121d..1c5a2a73736 100644 --- a/tracking/include/pcl/tracking/impl/tracking.hpp +++ b/tracking/include/pcl/tracking/impl/tracking.hpp @@ -129,6 +129,30 @@ struct EIGEN_ALIGN16 ParticleXYZRPY : public _ParticleXYZRPY { return {trans_x, trans_y, trans_z, trans_roll, trans_pitch, trans_yaw}; } + template + static ParticleXYZRPY + weightedAverage(InputIterator first, InputIterator last) + { + ParticleXYZRPY wa; + float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0, + wa_yaw_sin = 0.0, wa_yaw_cos = 0.0; + for (auto point = first; point != last; ++point) { + wa.x += point->x * point->weight; + wa.y += point->y * point->weight; + wa.z += point->z * point->weight; + wa_pitch_cos = std::cos(point->pitch); + wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight; + wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight; + wa_pitch_sin += std::sin(point->pitch) * point->weight; + wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight; + wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight; + } + wa.roll = std::atan2(wa_roll_sin, wa_roll_cos); + wa.pitch = std::asin(wa_pitch_sin); + wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos); + return wa; + } + // a[i] inline float operator[](unsigned int i) @@ -295,6 +319,24 @@ struct EIGEN_ALIGN16 ParticleXYZR : public _ParticleXYZR { return {trans_x, trans_y, trans_z, 0, trans_pitch, 0}; } + template + static ParticleXYZR + weightedAverage(InputIterator first, InputIterator last) + { + ParticleXYZR wa; + float wa_pitch_sin = 0.0; + for (auto point = first; point != last; ++point) { + wa.x += point->x * point->weight; + wa.y += point->y * point->weight; + wa.z += point->z * point->weight; + wa_pitch_sin += std::sin(point->pitch) * point->weight; + } + wa.roll = 0.0; + wa.pitch = std::asin(wa_pitch_sin); + wa.yaw = 0.0; + return wa; + } + // a[i] inline float operator[](unsigned int i) @@ -461,6 +503,30 @@ struct EIGEN_ALIGN16 ParticleXYRPY : public _ParticleXYRPY { return {trans_x, 0, trans_z, trans_roll, trans_pitch, trans_yaw}; } + template + static ParticleXYRPY + weightedAverage(InputIterator first, InputIterator last) + { + ParticleXYRPY wa; + float wa_roll_sin = 0.0, wa_roll_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0, + wa_yaw_sin = 0.0, wa_yaw_cos = 0.0; + for (auto point = first; point != last; ++point) { + wa.x += point->x * point->weight; + wa.z += point->z * point->weight; + wa_pitch_cos = std::cos(point->pitch); + wa_roll_sin += wa_pitch_cos * std::sin(point->roll) * point->weight; + wa_roll_cos += wa_pitch_cos * std::cos(point->roll) * point->weight; + wa_pitch_sin += std::sin(point->pitch) * point->weight; + wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight; + wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight; + } + wa.y = 0; + wa.roll = std::atan2(wa_roll_sin, wa_roll_cos); + wa.pitch = std::asin(wa_pitch_sin); + wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos); + return wa; + } + // a[i] inline float operator[](unsigned int i) @@ -627,6 +693,27 @@ struct EIGEN_ALIGN16 ParticleXYRP : public _ParticleXYRP { return {trans_x, 0, trans_z, 0, trans_pitch, trans_yaw}; } + template + static ParticleXYRP + weightedAverage(InputIterator first, InputIterator last) + { + ParticleXYRP wa; + float wa_yaw_sin = 0.0, wa_yaw_cos = 0.0, wa_pitch_sin = 0.0, wa_pitch_cos = 0.0; + for (auto point = first; point != last; ++point) { + wa.x += point->x * point->weight; + wa.z += point->z * point->weight; + wa_pitch_cos = std::cos(point->pitch); + wa_pitch_sin += std::sin(point->pitch) * point->weight; + wa_yaw_sin += wa_pitch_cos * std::sin(point->yaw) * point->weight; + wa_yaw_cos += wa_pitch_cos * std::cos(point->yaw) * point->weight; + } + wa.y = 0.0; + wa.roll = 0.0; + wa.pitch = std::asin(wa_pitch_sin); + wa.yaw = std::atan2(wa_yaw_sin, wa_yaw_cos); + return wa; + } + // a[i] inline float operator[](unsigned int i) @@ -793,6 +880,24 @@ struct EIGEN_ALIGN16 ParticleXYR : public _ParticleXYR { return {trans_x, 0, trans_z, 0, trans_pitch, 0}; } + template + static ParticleXYR + weightedAverage(InputIterator first, InputIterator last) + { + ParticleXYR wa; + float wa_pitch_sin = 0.0; + for (auto point = first; point != last; ++point) { + wa.x += point->x * point->weight; + wa.z += point->z * point->weight; + wa_pitch_sin += std::sin(point->pitch) * point->weight; + } + wa.y = 0.0; + wa.roll = 0.0; + wa.pitch = std::asin(wa_pitch_sin); + wa.yaw = 0.0; + return wa; + } + // a[i] inline float operator[](unsigned int i) diff --git a/tracking/include/pcl/tracking/tracking.h b/tracking/include/pcl/tracking/tracking.h index 4ae65ab4a37..15514de9c05 100644 --- a/tracking/include/pcl/tracking/tracking.h +++ b/tracking/include/pcl/tracking/tracking.h @@ -45,7 +45,10 @@ namespace pcl { namespace tracking { /* state definition */ struct ParticleXYZRPY; +struct ParticleXYRPY; +struct ParticleXYRP; struct ParticleXYR; +struct ParticleXYZR; /* \brief return the value of normal distribution */ PCL_EXPORTS double From dd07da01df06348bf4142c159355837154f093a0 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 26 May 2023 09:00:29 +0200 Subject: [PATCH 088/288] Add SortIncludes: CaseInsensitive, so includes get sorted alphetically without considering lower/upper case. --- .clang-format | 1 + 1 file changed, 1 insertion(+) diff --git a/.clang-format b/.clang-format index c921cd9a5e9..42e50cdb1e2 100644 --- a/.clang-format +++ b/.clang-format @@ -22,6 +22,7 @@ PointerAlignment: Left Standard: c++14 TabWidth: 2 UseTab: Never +SortIncludes: CaseInsensitive IncludeBlocks: Regroup IncludeCategories: # Main PCL includes of common module should be sorted at end of PCL includes From 28e75bfb86c2f0f4e46c5ca7c171044a5f94b372 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 26 May 2023 13:21:28 +0200 Subject: [PATCH 089/288] Update includes per new rule. --- apps/modeler/include/pcl/apps/modeler/cloud_mesh.h | 2 +- apps/modeler/src/channel_actor_item.cpp | 2 +- apps/modeler/src/render_window.cpp | 2 +- apps/src/feature_matching.cpp | 2 +- apps/src/manual_registration/manual_registration.cpp | 2 +- apps/src/openni_passthrough.cpp | 2 +- apps/src/organized_segmentation_demo.cpp | 2 +- apps/src/pcd_video_player/pcd_video_player.cpp | 2 +- apps/src/render_views_tesselated_sphere.cpp | 2 +- geometry/include/pcl/geometry/mesh_conversion.h | 2 +- geometry/include/pcl/geometry/planar_polygon.h | 2 +- .../include/pcl/gpu/segmentation/gpu_extract_clusters.h | 2 +- .../include/pcl/gpu/segmentation/gpu_extract_labeled_clusters.h | 2 +- .../include/pcl/gpu/segmentation/gpu_seeded_hue_segmentation.h | 2 +- simulation/include/pcl/simulation/model.h | 2 +- 15 files changed, 15 insertions(+), 15 deletions(-) diff --git a/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h b/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h index aa1ee3a490d..1823fdf15a8 100755 --- a/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h +++ b/apps/modeler/include/pcl/apps/modeler/cloud_mesh.h @@ -36,9 +36,9 @@ #pragma once -#include #include #include +#include #include diff --git a/apps/modeler/src/channel_actor_item.cpp b/apps/modeler/src/channel_actor_item.cpp index fb254279d49..6f383853cae 100755 --- a/apps/modeler/src/channel_actor_item.cpp +++ b/apps/modeler/src/channel_actor_item.cpp @@ -41,9 +41,9 @@ #include #include #include -#include #include #include +#include ////////////////////////////////////////////////////////////////////////////////////////////// pcl::modeler::ChannelActorItem::ChannelActorItem( diff --git a/apps/modeler/src/render_window.cpp b/apps/modeler/src/render_window.cpp index 9be04f77ce3..b63629b6ba1 100755 --- a/apps/modeler/src/render_window.cpp +++ b/apps/modeler/src/render_window.cpp @@ -43,9 +43,9 @@ #include #include #include -#include #include #include +#include #include ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/apps/src/feature_matching.cpp b/apps/src/feature_matching.cpp index 1ff0784410a..394ae3eef0d 100644 --- a/apps/src/feature_matching.cpp +++ b/apps/src/feature_matching.cpp @@ -19,8 +19,8 @@ #include #include #include -#include #include // for pcl::dynamic_pointer_cast +#include #include #include diff --git a/apps/src/manual_registration/manual_registration.cpp b/apps/src/manual_registration/manual_registration.cpp index fde1a6f189f..b7cf5d8a009 100644 --- a/apps/src/manual_registration/manual_registration.cpp +++ b/apps/src/manual_registration/manual_registration.cpp @@ -58,8 +58,8 @@ #include #include -#include #include +#include using namespace pcl; using namespace pcl::visualization; diff --git a/apps/src/openni_passthrough.cpp b/apps/src/openni_passthrough.cpp index b516e68e59f..862ee8b499d 100644 --- a/apps/src/openni_passthrough.cpp +++ b/apps/src/openni_passthrough.cpp @@ -44,8 +44,8 @@ #include #include -#include #include +#include #include diff --git a/apps/src/organized_segmentation_demo.cpp b/apps/src/organized_segmentation_demo.cpp index e4ce56193aa..480817345a4 100644 --- a/apps/src/organized_segmentation_demo.cpp +++ b/apps/src/organized_segmentation_demo.cpp @@ -12,8 +12,8 @@ #include #include -#include #include +#include // #include // for boost::filesystem::directory_iterator #include // for boost::signals2::connection diff --git a/apps/src/pcd_video_player/pcd_video_player.cpp b/apps/src/pcd_video_player/pcd_video_player.cpp index 527a1872e08..aa6157e3678 100644 --- a/apps/src/pcd_video_player/pcd_video_player.cpp +++ b/apps/src/pcd_video_player/pcd_video_player.cpp @@ -55,8 +55,8 @@ #include #include -#include #include +#include #include #include diff --git a/apps/src/render_views_tesselated_sphere.cpp b/apps/src/render_views_tesselated_sphere.cpp index ac248ac0ff9..896b101544e 100644 --- a/apps/src/render_views_tesselated_sphere.cpp +++ b/apps/src/render_views_tesselated_sphere.cpp @@ -20,8 +20,8 @@ #include #include #include -#include #include +#include #include #include #include diff --git a/geometry/include/pcl/geometry/mesh_conversion.h b/geometry/include/pcl/geometry/mesh_conversion.h index 68125dad5a5..227447afa53 100644 --- a/geometry/include/pcl/geometry/mesh_conversion.h +++ b/geometry/include/pcl/geometry/mesh_conversion.h @@ -40,8 +40,8 @@ #pragma once -#include #include +#include namespace pcl { namespace geometry { diff --git a/geometry/include/pcl/geometry/planar_polygon.h b/geometry/include/pcl/geometry/planar_polygon.h index fe3e9eb2ca5..72728adaf55 100644 --- a/geometry/include/pcl/geometry/planar_polygon.h +++ b/geometry/include/pcl/geometry/planar_polygon.h @@ -39,8 +39,8 @@ #pragma once -#include #include +#include #include #include 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 9f61338dc6e..388436c9f2d 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h @@ -41,10 +41,10 @@ #include #include -#include #include #include #include +#include namespace pcl { namespace gpu { 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 c262e50dcc7..b81ff9b58d3 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 @@ -40,10 +40,10 @@ #pragma once #include -#include #include #include #include +#include namespace pcl { namespace gpu { 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 47b44568a82..01de70a2817 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 @@ -39,10 +39,10 @@ #pragma once -#include #include #include #include +#include namespace pcl { namespace gpu { diff --git a/simulation/include/pcl/simulation/model.h b/simulation/include/pcl/simulation/model.h index 829915c6f0d..5514de52238 100644 --- a/simulation/include/pcl/simulation/model.h +++ b/simulation/include/pcl/simulation/model.h @@ -1,12 +1,12 @@ #pragma once #include -#include #include #include #include #include // for PointCloud #include +#include #if defined(_WIN32) && !defined(APIENTRY) && !defined(__CYGWIN__) #define WIN32_LEAN_AND_MEAN 1 From c1581718ea4f117e9f9618330ab552be2609bb58 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 29 May 2023 13:12:49 +0200 Subject: [PATCH 090/288] OrganizedNeighbor: add additional check to make sure the cloud is suitable --- search/include/pcl/search/impl/organized.hpp | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/search/include/pcl/search/impl/organized.hpp b/search/include/pcl/search/impl/organized.hpp index 704ac1c6094..fc5ce6cfda7 100644 --- a/search/include/pcl/search/impl/organized.hpp +++ b/search/include/pcl/search/impl/organized.hpp @@ -358,10 +358,11 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () } double residual_sqr = pcl::estimateProjectionMatrix (input_, projection_matrix_, indices); + PCL_DEBUG_STREAM("[pcl::" << this->getName () << "::estimateProjectionMatrix] projection matrix=" << std::endl << projection_matrix_ << std::endl << "residual_sqr=" << residual_sqr << std::endl); if (std::abs (residual_sqr) > eps_ * static_cast(indices.size ())) { - PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %f, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ()); + PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %g, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ()); return; } @@ -371,6 +372,19 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () // precalculate KR * KR^T needed by calculations during nn-search KR_KRT_ = KR_ * KR_.transpose (); + + // final test: project a few points at known image coordinates and test if the projected coordinates are close + for(std::size_t i=0; i<11; ++i) { + const std::size_t test_index = input_->size()*i/11u; + if (!mask_[test_index]) + continue; + const auto& test_point = (*input_)[test_index]; + pcl::PointXY q; + if (!projectPoint(test_point, q) || std::abs(q.x-test_index%input_->width)>1 || std::abs(q.y-test_index/input_->width)>1) { + PCL_WARN ("[pcl::%s::estimateProjectionMatrix] Input dataset does not seem to be from a projective device! (point %zu (%g,%g,%g) projected to pixel coordinates (%g,%g), but actual pixel coordinates are (%zu,%zu))\n", + this->getName ().c_str (), test_index, test_point.x, test_point.y, test_point.z, q.x, q.y, static_cast(test_index%input_->width), static_cast(test_index/input_->width)); + } + } } ////////////////////////////////////////////////////////////////////////////////////////////// From 4d8f60706c5d97c4a5b3b3da65f107cc7716ce1e Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Tue, 30 May 2023 03:13:16 -0700 Subject: [PATCH 091/288] Part C of transition to support modernize-use-default-member-init (#5722) * Part C of transition to support modernize-use-default-member-init * Fixed merge issues after rebase * Fixed issues flagged by review * Made more default initializations explicit * Made default initializations explicit per review --- 2d/include/pcl/2d/edge.h | 8 ++-- common/include/pcl/range_image/range_image.h | 8 ++-- features/include/pcl/features/crh.h | 3 +- .../pcl/features/integral_image_normal.h | 2 +- .../include/pcl/features/intensity_gradient.h | 2 +- .../include/pcl/features/intensity_spin.h | 2 +- .../features/linear_least_squares_normal.h | 2 +- .../features/multiscale_feature_persistence.h | 2 +- features/include/pcl/features/normal_3d.h | 2 +- features/include/pcl/features/our_cvfh.h | 2 +- features/include/pcl/features/pfh.h | 4 +- features/include/pcl/features/rift.h | 6 +-- features/include/pcl/features/rsd.h | 2 +- features/include/pcl/features/shot.h | 14 +++--- features/include/pcl/features/vfh.h | 2 +- .../pcl/filters/approximate_voxel_grid.h | 22 +++++----- filters/include/pcl/filters/bilateral.h | 8 ++-- .../include/pcl/filters/conditional_removal.h | 18 ++++---- filters/include/pcl/filters/convolution.h | 6 +-- filters/include/pcl/filters/crop_hull.h | 8 ++-- filters/include/pcl/filters/fast_bilateral.h | 12 ++---- filters/include/pcl/filters/filter_indices.h | 14 +++--- filters/include/pcl/filters/frustum_culling.h | 30 +++++-------- .../include/pcl/filters/impl/convolution.hpp | 3 -- filters/include/pcl/filters/local_maximum.h | 5 +-- filters/include/pcl/filters/median_filter.h | 9 ++-- filters/include/pcl/filters/project_inliers.h | 14 +++--- filters/include/pcl/filters/pyramid.h | 11 ++--- .../pcl/filters/radius_outlier_removal.h | 15 +++---- .../pcl/filters/sampling_surface_normal.h | 9 ++-- filters/include/pcl/filters/shadowpoints.h | 5 +-- .../pcl/filters/statistical_outlier_removal.h | 15 +++---- .../include/pcl/filters/uniform_sampling.h | 9 ++-- filters/include/pcl/filters/voxel_grid.h | 43 +++++++------------ .../pcl/filters/voxel_grid_covariance.h | 12 ++---- .../gpu/segmentation/gpu_extract_clusters.h | 2 +- .../gpu_extract_labeled_clusters.h | 2 +- .../gpu_seeded_hue_segmentation.h | 2 +- .../include/pcl/kdtree/impl/kdtree_flann.hpp | 5 +-- kdtree/include/pcl/kdtree/kdtree.h | 6 +-- kdtree/include/pcl/kdtree/kdtree_flann.h | 6 +-- .../pcl/visualization/point_picking_event.h | 2 +- 42 files changed, 148 insertions(+), 206 deletions(-) diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index 61c9f2844fd..23368155c9e 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -119,10 +119,10 @@ class Edge { bool non_maximal_suppression_{false}; bool hysteresis_thresholding_{false}; - float hysteresis_threshold_low_{20}; - float hysteresis_threshold_high_{80}; - float non_max_suppression_radius_x_{3}; - float non_max_suppression_radius_y_{3}; + float hysteresis_threshold_low_{20.0f}; + float hysteresis_threshold_high_{80.0f}; + float non_max_suppression_radius_x_{3.0f}; + float non_max_suppression_radius_y_{3.0f}; public: Edge() : output_type_(OUTPUT_X), detector_kernel_type_(SOBEL) {} diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index a80322c4f11..051979fe91f 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -767,11 +767,11 @@ namespace pcl // =====PROTECTED MEMBER VARIABLES===== Eigen::Affine3f to_range_image_system_; /**< Inverse of to_world_system_ */ Eigen::Affine3f to_world_system_; /**< Inverse of to_range_image_system_ */ - float angular_resolution_x_{0}; /**< Angular resolution of the range image in x direction in radians per pixel */ - float angular_resolution_y_{0}; /**< Angular resolution of the range image in y direction in radians per pixel */ - float angular_resolution_x_reciprocal_{0}; /**< 1.0/angular_resolution_x_ - provided for better performance of + float angular_resolution_x_{0.0f}; /**< Angular resolution of the range image in x direction in radians per pixel */ + float angular_resolution_y_{0.0f}; /**< Angular resolution of the range image in y direction in radians per pixel */ + float angular_resolution_x_reciprocal_{0.0f}; /**< 1.0/angular_resolution_x_ - provided for better performance of * multiplication compared to division */ - float angular_resolution_y_reciprocal_{0}; /**< 1.0/angular_resolution_y_ - provided for better performance of + float angular_resolution_y_reciprocal_{0.0f}; /**< 1.0/angular_resolution_y_ - provided for better performance of * multiplication compared to division */ int image_offset_x_{0}, image_offset_y_{0}; /**< Position of the top left corner of the range image compared to * an image of full size (360x180 degrees) */ diff --git a/features/include/pcl/features/crh.h b/features/include/pcl/features/crh.h index ceb583c4208..6a8d072e4c9 100644 --- a/features/include/pcl/features/crh.h +++ b/features/include/pcl/features/crh.h @@ -79,7 +79,6 @@ namespace pcl k_ = 1; feature_name_ = "CRHEstimation"; } - ; /** \brief Set the viewpoint. * \param[in] vpx the X coordinate of the viewpoint @@ -117,7 +116,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Number of bins, this should match the Output type */ int nbins_{90}; diff --git a/features/include/pcl/features/integral_image_normal.h b/features/include/pcl/features/integral_image_normal.h index 36289dbaa2d..8dc1249bd92 100644 --- a/features/include/pcl/features/integral_image_normal.h +++ b/features/include/pcl/features/integral_image_normal.h @@ -377,7 +377,7 @@ namespace pcl int rect_height_4_{0}; /** the threshold used to detect depth discontinuities */ - float distance_threshold_{0}; + float distance_threshold_{0.0f}; /** integral image in x-direction */ IntegralImage2D integral_image_DX_; diff --git a/features/include/pcl/features/intensity_gradient.h b/features/include/pcl/features/intensity_gradient.h index d12d01e2d75..b0f2d75fdb9 100644 --- a/features/include/pcl/features/intensity_gradient.h +++ b/features/include/pcl/features/intensity_gradient.h @@ -72,7 +72,7 @@ namespace pcl IntensityGradientEstimation () : intensity_ () { feature_name_ = "IntensityGradientEstimation"; - }; + } /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) diff --git a/features/include/pcl/features/intensity_spin.h b/features/include/pcl/features/intensity_spin.h index 5f66a4a6f2a..3872ec2f0bf 100644 --- a/features/include/pcl/features/intensity_spin.h +++ b/features/include/pcl/features/intensity_spin.h @@ -77,7 +77,7 @@ namespace pcl IntensitySpinEstimation () { feature_name_ = "IntensitySpinEstimation"; - }; + } /** \brief Estimate the intensity-domain spin image descriptor for a given point based on its spatial * neighborhood of 3D points and their intensities. diff --git a/features/include/pcl/features/linear_least_squares_normal.h b/features/include/pcl/features/linear_least_squares_normal.h index 115e07d4b53..00f9a79eac6 100644 --- a/features/include/pcl/features/linear_least_squares_normal.h +++ b/features/include/pcl/features/linear_least_squares_normal.h @@ -64,7 +64,7 @@ namespace pcl feature_name_ = "LinearLeastSquaresNormalEstimation"; tree_.reset (); k_ = 1; - }; + } /** \brief Destructor */ ~LinearLeastSquaresNormalEstimation () override; diff --git a/features/include/pcl/features/multiscale_feature_persistence.h b/features/include/pcl/features/multiscale_feature_persistence.h index 3d13dd36a88..8a0ea5023cd 100644 --- a/features/include/pcl/features/multiscale_feature_persistence.h +++ b/features/include/pcl/features/multiscale_feature_persistence.h @@ -180,7 +180,7 @@ namespace pcl std::vector scale_values_; /** \brief Parameter that determines if a feature is to be considered unique or not */ - float alpha_{0}; + float alpha_{0.0f}; /** \brief Parameter that determines which distance metric is to be usedto calculate the difference between feature vectors */ NormType distance_metric_{L1}; diff --git a/features/include/pcl/features/normal_3d.h b/features/include/pcl/features/normal_3d.h index 49f2417c95d..6a8b96fbd91 100644 --- a/features/include/pcl/features/normal_3d.h +++ b/features/include/pcl/features/normal_3d.h @@ -399,7 +399,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit * from NormalEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */ EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_; diff --git a/features/include/pcl/features/our_cvfh.h b/features/include/pcl/features/our_cvfh.h index 38f17c34618..969470622b7 100644 --- a/features/include/pcl/features/our_cvfh.h +++ b/features/include/pcl/features/our_cvfh.h @@ -324,7 +324,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel * size of the training data or the normalize_bins_ flag must be set to true. diff --git a/features/include/pcl/features/pfh.h b/features/include/pcl/features/pfh.h index 6b1a49cfd29..d8f3eecfef7 100644 --- a/features/include/pcl/features/pfh.h +++ b/features/include/pcl/features/pfh.h @@ -98,7 +98,7 @@ namespace pcl /** \brief Empty constructor. * Sets \a use_cache_ to false, \a nr_subdiv_ to 5, and the internal maximum cache size to 1GB. */ - PFHEstimation () : + PFHEstimation () : d_pi_ (1.0f / (2.0f * static_cast (M_PI))), key_list_ (), @@ -106,7 +106,7 @@ namespace pcl max_cache_size_ ((1ul*1024ul*1024ul*1024ul) / sizeof (std::pair, Eigen::Vector4f>)) { feature_name_ = "PFHEstimation"; - }; + } /** \brief Set the maximum internal cache size. Defaults to 2GB worth of entries. * \param[in] cache_size maximum cache size diff --git a/features/include/pcl/features/rift.h b/features/include/pcl/features/rift.h index 84d4ca95f6c..7d47ba95000 100644 --- a/features/include/pcl/features/rift.h +++ b/features/include/pcl/features/rift.h @@ -80,10 +80,10 @@ namespace pcl /** \brief Empty constructor. */ - RIFTEstimation () : gradient_ () + RIFTEstimation () { feature_name_ = "RIFTEstimation"; - }; + } /** \brief Provide a pointer to the input gradient data * \param[in] gradient a pointer to the input gradient data @@ -141,7 +141,7 @@ namespace pcl computeFeature (PointCloudOut &output) override; /** \brief The intensity gradient of the input point cloud data*/ - PointCloudGradientConstPtr gradient_; + PointCloudGradientConstPtr gradient_{nullptr}; /** \brief The number of distance bins in the descriptor. */ int nr_distance_bins_{4}; diff --git a/features/include/pcl/features/rsd.h b/features/include/pcl/features/rsd.h index eadd0d95d25..e5351daa544 100644 --- a/features/include/pcl/features/rsd.h +++ b/features/include/pcl/features/rsd.h @@ -151,7 +151,7 @@ namespace pcl RSDEstimation () { feature_name_ = "RadiusSurfaceDescriptor"; - }; + } /** \brief Set the number of subdivisions for the considered distance interval. * \param[in] nr_subdiv the number of subdivisions diff --git a/features/include/pcl/features/shot.h b/features/include/pcl/features/shot.h index 804c8776627..d278076b29f 100644 --- a/features/include/pcl/features/shot.h +++ b/features/include/pcl/features/shot.h @@ -94,7 +94,7 @@ namespace pcl nr_shape_bins_ (nr_shape_bins) { feature_name_ = "SHOTEstimation"; - }; + } public: @@ -165,19 +165,19 @@ namespace pcl int nr_shape_bins_; /** \brief The radius used for the LRF computation */ - float lrf_radius_{0}; + float lrf_radius_{0.0f}; /** \brief The squared search radius. */ - double sqradius_{0}; + double sqradius_{0.0}; /** \brief 3/4 of the search radius. */ - double radius3_4_{0}; + double radius3_4_{0.0}; /** \brief 1/4 of the search radius. */ - double radius1_4_{0}; + double radius1_4_{0.0}; /** \brief 1/2 of the search radius. */ - double radius1_2_{0}; + double radius1_2_{0.0}; /** \brief Number of azimuthal sectors. */ const int nr_grid_sector_{32}; @@ -324,7 +324,7 @@ namespace pcl b_describe_color_ (describe_color) { feature_name_ = "SHOTColorEstimation"; - }; + } /** \brief Empty destructor */ ~SHOTColorEstimation () override = default; diff --git a/features/include/pcl/features/vfh.h b/features/include/pcl/features/vfh.h index 9a8f60b4f39..01379f334f0 100644 --- a/features/include/pcl/features/vfh.h +++ b/features/include/pcl/features/vfh.h @@ -217,7 +217,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). For per point viewpoints, inherit * from VFHEstimation and provide your own computeFeature (). By default, the viewpoint is set to 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Estimate the Viewpoint Feature Histograms (VFH) descriptors at a set of points given by * using the surface in setSearchSurface () and the spatial locator in diff --git a/filters/include/pcl/filters/approximate_voxel_grid.h b/filters/include/pcl/filters/approximate_voxel_grid.h index 916144c2ab5..4e1b6319513 100644 --- a/filters/include/pcl/filters/approximate_voxel_grid.h +++ b/filters/include/pcl/filters/approximate_voxel_grid.h @@ -49,8 +49,8 @@ namespace pcl xNdCopyEigenPointFunctor (const Eigen::VectorXf &p1, PointT &p2) : p1_ (p1), - p2_ (reinterpret_cast(p2)), - f_idx_ (0) { } + p2_ (reinterpret_cast(p2)) + { } template inline void operator() () { @@ -63,7 +63,7 @@ namespace pcl private: const Eigen::VectorXf &p1_; Pod &p2_; - int f_idx_; + int f_idx_{0}; }; /** \brief Helper functor structure for copying data between an Eigen::VectorXf and a PointT. */ @@ -73,7 +73,7 @@ namespace pcl using Pod = typename traits::POD::type; xNdCopyPointEigenFunctor (const PointT &p1, Eigen::VectorXf &p2) - : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } + : p1_ (reinterpret_cast(p1)), p2_ (p2) { } template inline void operator() () { @@ -86,7 +86,7 @@ namespace pcl private: const Pod &p1_; Eigen::VectorXf &p2_; - int f_idx_; + int f_idx_{0}; }; /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. @@ -109,9 +109,9 @@ namespace pcl private: struct he { - he () : ix (), iy (), iz (), count (0) {} - int ix, iy, iz; - int count; + he () = default; + int ix{0}, iy{0}, iz{0}; + int count{0}; Eigen::VectorXf centroid; }; @@ -126,7 +126,7 @@ namespace pcl pcl::Filter (), leaf_size_ (Eigen::Vector3f::Ones ()), inverse_leaf_size_ (Eigen::Array3f::Ones ()), - downsample_all_data_ (true), histsize_ (512), + history_ (new he[histsize_]) { filter_name_ = "ApproximateVoxelGrid"; @@ -218,10 +218,10 @@ namespace pcl Eigen::Array3f inverse_leaf_size_; /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ - bool downsample_all_data_; + bool downsample_all_data_{true}; /** \brief history buffer size, power of 2 */ - std::size_t histsize_; + std::size_t histsize_{512}; /** \brief history buffer */ struct he* history_; diff --git a/filters/include/pcl/filters/bilateral.h b/filters/include/pcl/filters/bilateral.h index e1065797f84..06b0c59909d 100644 --- a/filters/include/pcl/filters/bilateral.h +++ b/filters/include/pcl/filters/bilateral.h @@ -68,9 +68,7 @@ namespace pcl /** \brief Constructor. * Sets sigma_s_ to 0 and sigma_r_ to MAXDBL */ - BilateralFilter () : sigma_s_ (0), - sigma_r_ (std::numeric_limits::max ()), - tree_ () + BilateralFilter () : tree_ () { } /** \brief Compute the intensity average for a single point @@ -130,9 +128,9 @@ namespace pcl { return (std::exp (- (x*x)/(2*sigma*sigma))); } /** \brief The half size of the Gaussian bilateral filter window (e.g., spatial extents in Euclidean). */ - double sigma_s_; + double sigma_s_{0.0}; /** \brief The standard deviation of the bilateral filter (e.g., standard deviation in intensity). */ - double sigma_r_; + double sigma_r_{std::numeric_limits::max ()}; /** \brief A pointer to the spatial search object. */ KdTreePtr tree_; diff --git a/filters/include/pcl/filters/conditional_removal.h b/filters/include/pcl/filters/conditional_removal.h index 350e8214ae3..d5e7b7ccaaa 100644 --- a/filters/include/pcl/filters/conditional_removal.h +++ b/filters/include/pcl/filters/conditional_removal.h @@ -93,7 +93,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Constructor. */ - ComparisonBase () : capable_ (false), offset_ (), op_ () {} + ComparisonBase () = default; /** \brief Destructor. */ virtual ~ComparisonBase () = default; @@ -111,16 +111,16 @@ namespace pcl protected: /** \brief True if capable. */ - bool capable_; + bool capable_{false}; /** \brief Field name to compare data on. */ std::string field_name_; /** \brief The data offset. */ - std::uint32_t offset_; + std::uint32_t offset_{0}; /** \brief The comparison operator type. */ - ComparisonOps::CompareOp op_; + ComparisonOps::CompareOp op_{ComparisonOps::GT}; }; ////////////////////////////////////////////////////////////////////////////////////////// @@ -455,7 +455,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Constructor. */ - ConditionBase () : capable_ (true), comparisons_ (), conditions_ () + ConditionBase () : comparisons_ (), conditions_ () { } @@ -489,7 +489,7 @@ namespace pcl protected: /** \brief True if capable. */ - bool capable_; + bool capable_{true}; /** \brief The collection of all comparisons that need to be verified. */ std::vector comparisons_; @@ -617,7 +617,7 @@ namespace pcl * \param extract_removed_indices extract filtered indices from indices vector */ ConditionalRemoval (int extract_removed_indices = false) : - Filter::Filter (extract_removed_indices), capable_ (false), keep_organized_ (false), condition_ (), + Filter::Filter (extract_removed_indices), condition_ (), user_filter_value_ (std::numeric_limits::quiet_NaN ()) { filter_name_ = "ConditionalRemoval"; @@ -671,12 +671,12 @@ namespace pcl applyFilter (PointCloud &output) override; /** \brief True if capable. */ - bool capable_; + bool capable_{false}; /** \brief Keep the structure of the data organized, by setting the * filtered points to the a user given value (NaN by default). */ - bool keep_organized_; + bool keep_organized_{false}; /** \brief The condition to use for filtering */ ConditionBasePtr condition_; diff --git a/filters/include/pcl/filters/convolution.h b/filters/include/pcl/filters/convolution.h index b60904f6751..3a817bbc087 100644 --- a/filters/include/pcl/filters/convolution.h +++ b/filters/include/pcl/filters/convolution.h @@ -213,12 +213,12 @@ namespace pcl /// convolution kernel Eigen::ArrayXf kernel_; /// half kernel size - int half_width_; + int half_width_{}; /// kernel size - 1 - int kernel_width_; + int kernel_width_{}; protected: /** \brief The number of threads the scheduler should use. */ - unsigned int threads_; + unsigned int threads_{1}; void makeInfinite (PointOut& p) diff --git a/filters/include/pcl/filters/crop_hull.h b/filters/include/pcl/filters/crop_hull.h index 141dd6e0cc1..081c2f5d38e 100644 --- a/filters/include/pcl/filters/crop_hull.h +++ b/filters/include/pcl/filters/crop_hull.h @@ -66,9 +66,7 @@ namespace pcl /** \brief Empty Constructor. */ CropHull () : - hull_cloud_(), - dim_(3), - crop_outside_(true) + hull_cloud_() { filter_name_ = "CropHull"; } @@ -199,12 +197,12 @@ namespace pcl PointCloudPtr hull_cloud_; /** \brief The dimensionality of the hull to be used. */ - int dim_; + int dim_{3}; /** \brief If true, the filter will remove points outside the hull. If * false, those inside will be removed. */ - bool crop_outside_; + bool crop_outside_{true}; }; } // namespace pcl diff --git a/filters/include/pcl/filters/fast_bilateral.h b/filters/include/pcl/filters/fast_bilateral.h index d71879fdd3f..683a9da62e9 100644 --- a/filters/include/pcl/filters/fast_bilateral.h +++ b/filters/include/pcl/filters/fast_bilateral.h @@ -65,11 +65,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Empty constructor. */ - FastBilateralFilter () - : sigma_s_ (15.0f) - , sigma_r_ (0.05f) - , early_division_ (false) - { } + FastBilateralFilter () = default; /** \brief Empty destructor */ ~FastBilateralFilter () override = default; @@ -108,9 +104,9 @@ namespace pcl applyFilter (PointCloud &output) override; protected: - float sigma_s_; - float sigma_r_; - bool early_division_; + float sigma_s_{15.0f}; + float sigma_r_{0.05f}; + bool early_division_{false}; class Array3D { diff --git a/filters/include/pcl/filters/filter_indices.h b/filters/include/pcl/filters/filter_indices.h index a5bdfb75f41..4fc61243717 100644 --- a/filters/include/pcl/filters/filter_indices.h +++ b/filters/include/pcl/filters/filter_indices.h @@ -86,8 +86,7 @@ namespace pcl */ FilterIndices (bool extract_removed_indices = false) : Filter (extract_removed_indices), - negative_ (false), - keep_organized_ (false), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) { } @@ -165,10 +164,10 @@ namespace pcl using Filter::removed_indices_; /** \brief False = normal filter behavior (default), true = inverted behavior. */ - bool negative_; + bool negative_{false}; /** \brief False = remove points (default), true = redefine points, keep structure. */ - bool keep_organized_; + bool keep_organized_{false}; /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */ float user_filter_value_; @@ -203,8 +202,7 @@ namespace pcl */ FilterIndices (bool extract_removed_indices = false) : Filter (extract_removed_indices), - negative_ (false), - keep_organized_ (false), + user_filter_value_ (std::numeric_limits::quiet_NaN ()) { } @@ -268,10 +266,10 @@ namespace pcl protected: /** \brief False = normal filter behavior (default), true = inverted behavior. */ - bool negative_; + bool negative_{false}; /** \brief False = remove points (default), true = redefine points, keep structure. */ - bool keep_organized_; + bool keep_organized_{false}; /** \brief The user given value that the filtered point dimensions should be set to (default = NaN). */ float user_filter_value_; diff --git a/filters/include/pcl/filters/frustum_culling.h b/filters/include/pcl/filters/frustum_culling.h index 13c11aabe58..707b849342f 100644 --- a/filters/include/pcl/filters/frustum_culling.h +++ b/filters/include/pcl/filters/frustum_culling.h @@ -90,16 +90,6 @@ namespace pcl FrustumCulling (bool extract_removed_indices = false) : FilterIndices (extract_removed_indices) , camera_pose_ (Eigen::Matrix4f::Identity ()) - , fov_left_bound_ (-30.0f) - , fov_right_bound_ (30.0f) - , fov_lower_bound_ (-30.0f) - , fov_upper_bound_ (30.0f) - , np_dist_ (0.1f) - , fp_dist_ (5.0f) - , roi_x_ (0.5f) - , roi_y_ (0.5f) - , roi_w_ (1.0f) - , roi_h_ (1.0f) { filter_name_ = "FrustumCulling"; } @@ -363,25 +353,25 @@ namespace pcl /** \brief The camera pose */ Eigen::Matrix4f camera_pose_; /** \brief The left bound of horizontal field of view */ - float fov_left_bound_; + float fov_left_bound_{-30.0f}; /** \brief The right bound of horizontal field of view */ - float fov_right_bound_; + float fov_right_bound_{30.0f}; /** \brief The lower bound of vertical field of view */ - float fov_lower_bound_; + float fov_lower_bound_{-30.0f}; /** \brief The upper bound of vertical field of view */ - float fov_upper_bound_; + float fov_upper_bound_{30.0f}; /** \brief Near plane distance */ - float np_dist_; + float np_dist_{0.1f}; /** \brief Far plane distance */ - float fp_dist_; + float fp_dist_{5.0f}; /** \brief Region of interest x center position (normalized)*/ - float roi_x_; + float roi_x_{0.5f}; /** \brief Region of interest y center position (normalized)*/ - float roi_y_; + float roi_y_{0.5f}; /** \brief Region of interest width (normalized)*/ - float roi_w_; + float roi_w_{1.0f}; /** \brief Region of interest height (normalized)*/ - float roi_h_; + float roi_h_{1.0f}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/filters/include/pcl/filters/impl/convolution.hpp b/filters/include/pcl/filters/impl/convolution.hpp index 3ee170e5ae6..087fa9001f0 100644 --- a/filters/include/pcl/filters/impl/convolution.hpp +++ b/filters/include/pcl/filters/impl/convolution.hpp @@ -55,9 +55,6 @@ Convolution::Convolution () : borders_policy_ (BORDERS_POLICY_IGNORE) , distance_threshold_ (std::numeric_limits::infinity ()) , input_ () - , half_width_ () - , kernel_width_ () - , threads_ (1) {} template void diff --git a/filters/include/pcl/filters/local_maximum.h b/filters/include/pcl/filters/local_maximum.h index 741bf3b87bc..90755be55e7 100644 --- a/filters/include/pcl/filters/local_maximum.h +++ b/filters/include/pcl/filters/local_maximum.h @@ -67,8 +67,7 @@ namespace pcl /** \brief Empty constructor. */ LocalMaximum (bool extract_removed_indices = false) : FilterIndices::FilterIndices (extract_removed_indices), - searcher_ (), - radius_ (1) + searcher_ () { filter_name_ = "LocalMaximum"; } @@ -120,7 +119,7 @@ namespace pcl SearcherPtr searcher_; /** \brief The radius to use to determine if a point is the local max. */ - float radius_; + float radius_{1.0f}; }; } diff --git a/filters/include/pcl/filters/median_filter.h b/filters/include/pcl/filters/median_filter.h index 8e08e508096..614b34ea610 100644 --- a/filters/include/pcl/filters/median_filter.h +++ b/filters/include/pcl/filters/median_filter.h @@ -64,10 +64,7 @@ namespace pcl public: /** \brief Empty constructor. */ - MedianFilter () - : window_size_ (5) - , max_allowed_movement_ (std::numeric_limits::max ()) - { } + MedianFilter () = default; /** \brief Set the window size of the filter. * \param[in] window_size the new window size @@ -104,8 +101,8 @@ namespace pcl applyFilter (PointCloud &output) override; protected: - int window_size_; - float max_allowed_movement_; + int window_size_{5}; + float max_allowed_movement_{std::numeric_limits::max ()}; }; } diff --git a/filters/include/pcl/filters/project_inliers.h b/filters/include/pcl/filters/project_inliers.h index 6a7c36f6ad3..cc02be447fa 100644 --- a/filters/include/pcl/filters/project_inliers.h +++ b/filters/include/pcl/filters/project_inliers.h @@ -71,7 +71,7 @@ namespace pcl /** \brief Empty constructor. */ - ProjectInliers () : sacmodel_ (), model_type_ (), copy_all_data_ (false) + ProjectInliers () : sacmodel_ () { filter_name_ = "ProjectInliers"; } @@ -142,10 +142,10 @@ namespace pcl SampleConsensusModelPtr sacmodel_; /** \brief The type of model to use (user given parameter). */ - int model_type_; + int model_type_{0}; /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */ - bool copy_all_data_; + bool copy_all_data_{false}; /** \brief Initialize the Sample Consensus model and set its parameters. * \param model_type the type of SAC model that is to be used @@ -174,7 +174,7 @@ namespace pcl public: /** \brief Empty constructor. */ - ProjectInliers () : model_type_ (), copy_all_data_ (false), copy_all_fields_ (true) + ProjectInliers () { filter_name_ = "ProjectInliers"; } @@ -247,13 +247,13 @@ namespace pcl } protected: /** \brief The type of model to use (user given parameter). */ - int model_type_; + int model_type_{0}; /** \brief True if all data will be returned, false if only the projected inliers. Default: false. */ - bool copy_all_data_; + bool copy_all_data_{false}; /** \brief True if all fields will be returned, false if only XYZ. Default: true. */ - bool copy_all_fields_; + bool copy_all_fields_{true}; /** \brief A pointer to the vector of model coefficients. */ ModelCoefficientsConstPtr model_; diff --git a/filters/include/pcl/filters/pyramid.h b/filters/include/pcl/filters/pyramid.h index 8077eac8a34..107c83000c4 100644 --- a/filters/include/pcl/filters/pyramid.h +++ b/filters/include/pcl/filters/pyramid.h @@ -69,10 +69,7 @@ namespace pcl Pyramid (int levels = 4) : levels_ (levels) - , large_ (false) , name_ ("Pyramid") - , threshold_ (0.01) - , threads_ (0) { } @@ -148,17 +145,17 @@ namespace pcl /// \brief The input point cloud dataset. PointCloudConstPtr input_; /// \brief number of pyramid levels - int levels_; + int levels_{4}; /// \brief use large smoothing kernel - bool large_; + bool large_{false}; /// \brief filter name std::string name_; /// \brief smoothing kernel Eigen::MatrixXf kernel_; /// Threshold distance between adjacent points - float threshold_; + float threshold_{0.01f}; /// \brief number of threads - unsigned int threads_; + unsigned int threads_{0}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/filters/include/pcl/filters/radius_outlier_removal.h b/filters/include/pcl/filters/radius_outlier_removal.h index 62a65031f1d..677284df29a 100644 --- a/filters/include/pcl/filters/radius_outlier_removal.h +++ b/filters/include/pcl/filters/radius_outlier_removal.h @@ -87,9 +87,7 @@ namespace pcl */ RadiusOutlierRemoval (bool extract_removed_indices = false) : FilterIndices (extract_removed_indices), - searcher_ (), - search_radius_ (0.0), - min_pts_radius_ (1) + searcher_ () { filter_name_ = "RadiusOutlierRemoval"; } @@ -169,10 +167,10 @@ namespace pcl SearcherPtr searcher_; /** \brief The nearest neighbors search radius for each point. */ - double search_radius_; + double search_radius_{0.0}; /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered an inlier. */ - int min_pts_radius_; + int min_pts_radius_{1}; }; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -200,8 +198,7 @@ namespace pcl public: /** \brief Empty constructor. */ RadiusOutlierRemoval (bool extract_removed_indices = false) : - FilterIndices::FilterIndices (extract_removed_indices), - search_radius_ (0.0), min_pts_radius_ (1) + FilterIndices::FilterIndices (extract_removed_indices) { filter_name_ = "RadiusOutlierRemoval"; } @@ -243,12 +240,12 @@ namespace pcl protected: /** \brief The nearest neighbors search radius for each point. */ - double search_radius_; + double search_radius_{0.0}; /** \brief The minimum number of neighbors that a point needs to have in the given search radius to be considered * an inlier. */ - int min_pts_radius_; + int min_pts_radius_{1}; /** \brief A pointer to the spatial search object. */ KdTreePtr searcher_; diff --git a/filters/include/pcl/filters/sampling_surface_normal.h b/filters/include/pcl/filters/sampling_surface_normal.h index ea0a68bc417..3c2e8397404 100644 --- a/filters/include/pcl/filters/sampling_surface_normal.h +++ b/filters/include/pcl/filters/sampling_surface_normal.h @@ -69,8 +69,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Empty constructor. */ - SamplingSurfaceNormal () : - sample_ (10), seed_ (static_cast (time (nullptr))), ratio_ () + SamplingSurfaceNormal () { filter_name_ = "SamplingSurfaceNormal"; srand (seed_); @@ -128,11 +127,11 @@ namespace pcl protected: /** \brief Maximum number of samples in each grid. */ - unsigned int sample_; + unsigned int sample_{10}; /** \brief Random number seed. */ - unsigned int seed_; + unsigned int seed_{static_cast (time (nullptr))}; /** \brief Ratio of points to be sampled in each grid */ - float ratio_; + float ratio_{0.0f}; /** \brief Sample of point indices into a separate PointCloud * \param[out] output the resultant point cloud diff --git a/filters/include/pcl/filters/shadowpoints.h b/filters/include/pcl/filters/shadowpoints.h index 5e2fe6ad6a4..af926bd1a5d 100644 --- a/filters/include/pcl/filters/shadowpoints.h +++ b/filters/include/pcl/filters/shadowpoints.h @@ -72,8 +72,7 @@ namespace pcl /** \brief Empty constructor. */ ShadowPoints (bool extract_removed_indices = false) : FilterIndices (extract_removed_indices), - input_normals_ (), - threshold_ (0.1f) + input_normals_ () { filter_name_ = "ShadowPoints"; } @@ -119,7 +118,7 @@ namespace pcl /** \brief Threshold for shadow point rejection */ - float threshold_; + float threshold_{0.1f}; }; } diff --git a/filters/include/pcl/filters/statistical_outlier_removal.h b/filters/include/pcl/filters/statistical_outlier_removal.h index 70b450dea12..3c55dc0a25f 100644 --- a/filters/include/pcl/filters/statistical_outlier_removal.h +++ b/filters/include/pcl/filters/statistical_outlier_removal.h @@ -96,9 +96,7 @@ namespace pcl */ StatisticalOutlierRemoval (bool extract_removed_indices = false) : FilterIndices (extract_removed_indices), - searcher_ (), - mean_k_ (1), - std_mul_ (0.0) + searcher_ () { filter_name_ = "StatisticalOutlierRemoval"; } @@ -173,11 +171,11 @@ namespace pcl SearcherPtr searcher_; /** \brief The number of points to use for mean distance estimation. */ - int mean_k_; + int mean_k_{1}; /** \brief Standard deviations threshold (i.e., points outside of * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */ - double std_mul_; + double std_mul_{0.0}; }; /** \brief @b StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more @@ -208,8 +206,7 @@ namespace pcl public: /** \brief Empty constructor. */ StatisticalOutlierRemoval (bool extract_removed_indices = false) : - FilterIndices::FilterIndices (extract_removed_indices), mean_k_ (2), - std_mul_ (0.0) + FilterIndices::FilterIndices (extract_removed_indices) { filter_name_ = "StatisticalOutlierRemoval"; } @@ -251,12 +248,12 @@ namespace pcl protected: /** \brief The number of points to use for mean distance estimation. */ - int mean_k_; + int mean_k_{2}; /** \brief Standard deviations threshold (i.e., points outside of * \f$ \mu \pm \sigma \cdot std\_mul \f$ will be marked as outliers). */ - double std_mul_; + double std_mul_{0.0}; /** \brief A pointer to the spatial search object. */ KdTreePtr tree_; diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index 896d7b6e927..39d0815d32a 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -82,8 +82,7 @@ namespace pcl min_b_ (Eigen::Vector4i::Zero ()), max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), - divb_mul_ (Eigen::Vector4i::Zero ()), - search_radius_ (0) + divb_mul_ (Eigen::Vector4i::Zero ()) { filter_name_ = "UniformSampling"; } @@ -113,8 +112,8 @@ namespace pcl /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */ struct Leaf { - Leaf () : idx (-1) { } - int idx; + Leaf () = default; + int idx{-1}; }; /** \brief The 3D grid leaves. */ @@ -130,7 +129,7 @@ namespace pcl Eigen::Vector4i min_b_, max_b_, div_b_, divb_mul_; /** \brief The nearest neighbors search radius for each point. */ - double search_radius_; + double search_radius_{0.0}; /** \brief Downsample a Point Cloud using a voxelized grid approach * \param[out] output the resultant point cloud message diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 517c4d11bae..24615c43e7f 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -196,17 +196,10 @@ namespace pcl VoxelGrid () : leaf_size_ (Eigen::Vector4f::Zero ()), inverse_leaf_size_ (Eigen::Array4f::Zero ()), - downsample_all_data_ (true), - save_leaf_layout_ (false), min_b_ (Eigen::Vector4i::Zero ()), max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), - divb_mul_ (Eigen::Vector4i::Zero ()), - - filter_limit_min_ (std::numeric_limits::lowest()), - filter_limit_max_ (std::numeric_limits::max()), - filter_limit_negative_ (false), - min_points_per_voxel_ (0) + divb_mul_ (Eigen::Vector4i::Zero ()) { filter_name_ = "VoxelGrid"; } @@ -460,10 +453,10 @@ namespace pcl Eigen::Array4f inverse_leaf_size_; /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ - bool downsample_all_data_; + bool downsample_all_data_{true}; /** \brief Set to true if leaf layout information needs to be saved in \a leaf_layout_. */ - bool save_leaf_layout_; + bool save_leaf_layout_{false}; /** \brief The leaf layout information for fast access to cells relative to current position **/ std::vector leaf_layout_; @@ -475,16 +468,16 @@ namespace pcl std::string filter_field_name_; /** \brief The minimum allowed filter value a point will be considered from. */ - double filter_limit_min_; + double filter_limit_min_{std::numeric_limits::lowest()}; /** \brief The maximum allowed filter value a point will be considered from. */ - double filter_limit_max_; + double filter_limit_max_{std::numeric_limits::max()}; /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ - bool filter_limit_negative_; + bool filter_limit_negative_{false}; /** \brief Minimum number of points per voxel for the centroid to be computed */ - unsigned int min_points_per_voxel_; + unsigned int min_points_per_voxel_{0}; using FieldList = typename pcl::traits::fieldList::type; @@ -522,17 +515,11 @@ namespace pcl VoxelGrid () : leaf_size_ (Eigen::Vector4f::Zero ()), inverse_leaf_size_ (Eigen::Array4f::Zero ()), - downsample_all_data_ (true), - save_leaf_layout_ (false), + min_b_ (Eigen::Vector4i::Zero ()), max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), - divb_mul_ (Eigen::Vector4i::Zero ()), - - filter_limit_min_ (std::numeric_limits::lowest()), - filter_limit_max_ (std::numeric_limits::max()), - filter_limit_negative_ (false), - min_points_per_voxel_ (0) + divb_mul_ (Eigen::Vector4i::Zero ()) { filter_name_ = "VoxelGrid"; } @@ -808,12 +795,12 @@ namespace pcl Eigen::Array4f inverse_leaf_size_; /** \brief Set to true if all fields need to be downsampled, or false if just XYZ. */ - bool downsample_all_data_; + bool downsample_all_data_{true}; /** \brief Set to true if leaf layout information needs to be saved in \a * leaf_layout. */ - bool save_leaf_layout_; + bool save_leaf_layout_{false}; /** \brief The leaf layout information for fast access to cells relative * to current position @@ -829,16 +816,16 @@ namespace pcl std::string filter_field_name_; /** \brief The minimum allowed filter value a point will be considered from. */ - double filter_limit_min_; + double filter_limit_min_{std::numeric_limits::lowest()}; /** \brief The maximum allowed filter value a point will be considered from. */ - double filter_limit_max_; + double filter_limit_max_{std::numeric_limits::max()}; /** \brief Set to true if we want to return the data outside (\a filter_limit_min_;\a filter_limit_max_). Default: false. */ - bool filter_limit_negative_; + bool filter_limit_negative_{false}; /** \brief Minimum number of points per voxel for the centroid to be computed */ - unsigned int min_points_per_voxel_; + unsigned int min_points_per_voxel_{0}; /** \brief Downsample a Point Cloud using a voxelized grid approach * \param[out] output the resultant point cloud diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index 536d18aaba1..d2f69e788a0 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -94,7 +94,6 @@ namespace pcl * Sets \ref nr_points, \ref cov_, \ref icov_, \ref mean_ and \ref evals_ to 0 and \ref evecs_ to the identity matrix */ Leaf () : - nr_points (0), mean_ (Eigen::Vector3d::Zero ()), cov_ (Eigen::Matrix3d::Zero ()), icov_ (Eigen::Matrix3d::Zero ()), @@ -160,7 +159,7 @@ namespace pcl } /** \brief Number of points contained by voxel */ - int nr_points; + int nr_points{0}; /** \brief 3D voxel centroid */ Eigen::Vector3d mean_; @@ -196,9 +195,6 @@ namespace pcl * Sets \ref leaf_size_ to 0 and \ref searchable_ to false. */ VoxelGridCovariance () : - searchable_ (true), - min_points_per_voxel_ (6), - min_covar_eigvalue_mult_ (0.01), leaves_ (), voxel_centroids_ (), kdtree_ () @@ -568,13 +564,13 @@ namespace pcl void applyFilter (PointCloud &output) override; /** \brief Flag to determine if voxel structure is searchable. */ - bool searchable_; + bool searchable_{true}; /** \brief Minimum points contained with in a voxel to allow it to be usable. */ - int min_points_per_voxel_; + int min_points_per_voxel_{6}; /** \brief Minimum allowable ratio between eigenvalues to prevent singular covariance matrices. */ - double min_covar_eigvalue_mult_; + double min_covar_eigvalue_mult_{0.01}; /** \brief Voxel structure containing all leaf nodes (includes voxels with less than a sufficient number of points). */ std::map leaves_; 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 9f61338dc6e..72280498047 100644 --- a/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h +++ b/gpu/segmentation/include/pcl/gpu/segmentation/gpu_extract_clusters.h @@ -191,7 +191,7 @@ class EuclideanClusterExtraction { GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_{0}; + double cluster_tolerance_{0.0}; /** \brief The minimum number of points that a cluster needs to contain in order to be * considered valid (default = 1). */ 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 c262e50dcc7..b5fa646d9b6 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 @@ -185,7 +185,7 @@ class EuclideanLabeledClusterExtraction { GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_{0}; + double cluster_tolerance_{0.0}; /** \brief The minimum number of points that a cluster needs to contain in order to be * considered valid (default = 1). */ 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 47b44568a82..f8d0df2ae39 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 @@ -155,7 +155,7 @@ class SeededHueSegmentation { GPUTreePtr tree_; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_{0}; + double cluster_tolerance_{0.0}; /** \brief The allowed difference on the hue*/ float delta_hue_{0.0}; diff --git a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp index 5c777594111..f92017189a6 100644 --- a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp +++ b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp @@ -49,9 +49,8 @@ template pcl::KdTreeFLANN::KdTreeFLANN (bool sorted) : pcl::KdTree (sorted) , flann_index_ () - , identity_mapping_ (false) - , dim_ (0), total_nr_points_ (0) - , param_k_ (::flann::SearchParams (-1 , epsilon_)) + , + param_k_ (::flann::SearchParams (-1 , epsilon_)) , param_radius_ (::flann::SearchParams (-1, epsilon_, sorted)) { if (!std::is_same::value) { diff --git a/kdtree/include/pcl/kdtree/kdtree.h b/kdtree/include/pcl/kdtree/kdtree.h index 3a72725ee01..d8d4e4bdd26 100644 --- a/kdtree/include/pcl/kdtree/kdtree.h +++ b/kdtree/include/pcl/kdtree/kdtree.h @@ -72,7 +72,7 @@ namespace pcl * \param[in] sorted set to true if the application that the tree will be used for requires sorted nearest neighbor indices (default). False otherwise. */ KdTree (bool sorted = true) : input_(), - epsilon_(0.0f), min_pts_(1), sorted_(sorted), + sorted_(sorted), point_representation_ (new DefaultPointRepresentation) { }; @@ -339,10 +339,10 @@ namespace pcl IndicesConstPtr indices_; /** \brief Epsilon precision (error bound) for nearest neighbors searches. */ - float epsilon_; + float epsilon_{0.0f}; /** \brief Minimum allowed number of k nearest neighbors points that a viable result must contain. */ - int min_pts_; + int min_pts_{1}; /** \brief Return the radius search neighbours sorted **/ bool sorted_; diff --git a/kdtree/include/pcl/kdtree/kdtree_flann.h b/kdtree/include/pcl/kdtree/kdtree_flann.h index 92659038a9b..4396cb8b717 100644 --- a/kdtree/include/pcl/kdtree/kdtree_flann.h +++ b/kdtree/include/pcl/kdtree/kdtree_flann.h @@ -296,14 +296,14 @@ class KdTreeFLANN : public pcl::KdTree { std::vector index_mapping_; /** \brief whether the mapping between internal and external indices is identity */ - bool identity_mapping_; + bool identity_mapping_{false}; /** \brief Tree dimensionality (i.e. the number of dimensions per point). */ - int dim_; + int dim_{0}; /** \brief The total size of the data (either equal to the number of points in the * input cloud or to the number of indices - if passed). */ - uindex_t total_nr_points_; + uindex_t total_nr_points_{0}; /** \brief The KdTree search parameters for K-nearest neighbors. */ ::flann::SearchParams param_k_; diff --git a/visualization/include/pcl/visualization/point_picking_event.h b/visualization/include/pcl/visualization/point_picking_event.h index bfcdd7f9546..bbddda91d60 100644 --- a/visualization/include/pcl/visualization/point_picking_event.h +++ b/visualization/include/pcl/visualization/point_picking_event.h @@ -83,7 +83,7 @@ namespace pcl private: - float x_{0}, y_{0}, z_{0}; + float x_{0.0f}, y_{0.0f}, z_{0.0f}; pcl::index_t idx_{pcl::UNAVAILABLE}; bool pick_first_{false}; const vtkActor* actor_{nullptr}; From 68904fc0259d5bde4410991b8f33e86d25e56d82 Mon Sep 17 00:00:00 2001 From: Alessio Stella Date: Thu, 1 Jun 2023 12:09:54 +0200 Subject: [PATCH 092/288] function computeCentroidAndOBB (#5690) * function computeCentroidAndOBB * function computeCentroidAndOBB with more eigen use for the implementation * function computeCentroidAndOBB with more eigen use for the implementation + minor fix * function computeCentroidAndOBB with more eigen use for the implementation + minor fix * function computeCentroidAndOBB with more eigen use for the implementation + minor fix * function computeCentroidAndOBB with more eigen use in the implementation + ref in moment of inertia tutorial * bug fix * minor refinements * added const to some variables * minor formatting refinements --- common/include/pcl/common/centroid.h | 55 ++++ common/include/pcl/common/impl/centroid.hpp | 310 ++++++++++++++++++-- doc/tutorials/content/moment_of_inertia.rst | 3 +- test/common/test_centroid.cpp | 134 +++++++++ 4 files changed, 481 insertions(+), 21 deletions(-) diff --git a/common/include/pcl/common/centroid.h b/common/include/pcl/common/centroid.h index cb88773fc49..c3a32300a31 100644 --- a/common/include/pcl/common/centroid.h +++ b/common/include/pcl/common/centroid.h @@ -589,6 +589,61 @@ namespace pcl return (computeCovarianceMatrix (cloud, indices, covariance_matrix)); } + + /** \brief Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points. + * OBB is oriented like the three axes (major, middle and minor) with + * major_axis = obb_rotational_matrix.col(0) + * middle_axis = obb_rotational_matrix.col(1) + * minor_axis = obb_rotational_matrix.col(2) + * one way to visualize OBB when Scalar is float: + * Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2)); + * Eigen::Quaternionf quat(obb_rotational_matrix); + * viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....); + * \param[in] cloud the input point cloud + * \param[out] centroid the centroid (mean value of the XYZ coordinates) of the set of points in the cloud + * \param[out] obb_center position of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric) + * \param[out] obb_dimensions (width, height and depth) of the OBB + * \param[out] obb_rotational_matrix rotational matrix of the OBB + * \return number of valid points used to determine the output. + * In case of dense point clouds, this is the same as the size of the input cloud. + * \ingroup common + */ + template inline unsigned int + computeCentroidAndOBB(const pcl::PointCloud& cloud, + Eigen::Matrix& centroid, + Eigen::Matrix& obb_center, + Eigen::Matrix& obb_dimensions, + Eigen::Matrix& obb_rotational_matrix); + + + /** \brief Compute centroid, OBB (Oriented Bounding Box), PCA axes of a given set of points. + * OBB is oriented like the three axes (major, middle and minor) with + * major_axis = obb_rotational_matrix.col(0) + * middle_axis = obb_rotational_matrix.col(1) + * minor_axis = obb_rotational_matrix.col(2) + * one way to visualize OBB when Scalar is float: + * Eigen::Vector3f position(obb_position(0), obb_position(1), obb_position(2)); + * Eigen::Quaternionf quat(obb_rotational_matrix); + * viewer->addCube(position, quat, obb_dimensions(0), obb_dimensions(1), obb_dimensions(2), .....); + * \param[in] cloud the input point cloud + * \param[in] indices subset of points given by their indices + * \param[out] centroid the centroid (mean value of the XYZ coordinates) of the set of points in the cloud + * \param[out] obb_center position of the center of the OBB (it is the same as centroid if the cloud is centrally symmetric) + * \param[out] obb_dimensions (width, height and depth) of the OBB + * \param[out] obb_rotational_matrix rotational matrix of the OBB + * \return number of valid points used to determine the output. + * In case of dense point clouds, this is the same as the size of the input cloud. + * \ingroup common + */ + template inline unsigned int + computeCentroidAndOBB(const pcl::PointCloud& cloud, + const Indices &indices, + Eigen::Matrix& centroid, + Eigen::Matrix& obb_center, + Eigen::Matrix& obb_dimensions, + Eigen::Matrix& obb_rotational_matrix); + + /** \brief Subtract a centroid from a point cloud and return the de-meaned representation * \param[in] cloud_iterator an iterator over the input point cloud * \param[in] centroid the centroid of the point cloud diff --git a/common/include/pcl/common/impl/centroid.hpp b/common/include/pcl/common/impl/centroid.hpp index f83b12ca2be..36d4317a14e 100644 --- a/common/include/pcl/common/impl/centroid.hpp +++ b/common/include/pcl/common/impl/centroid.hpp @@ -43,6 +43,7 @@ #include #include #include // for pcl::isFinite +#include // for EigenSolver #include // for boost::fusion::filter_if #include // for boost::fusion::for_each @@ -560,17 +561,17 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, if (point_count != 0) { accu /= static_cast (point_count); - centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z(); + centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();//effective mean E[P=(x,y,z)] centroid[3] = 1; - covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6]; - covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7]; - covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8]; - covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7]; - covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8]; - covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8]; - covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); - covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); - covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); + covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];//(0,0)xx : E[(x-E[x])^2]=E[x^2]-E[x]^2=E[(x-Kx)^2]-E[x-Kx]^2 + covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];//(0,1)xy : E[(x-E[x])(y-E[y])]=E[xy]-E[x]E[y]=E[(x-Kx)(y-Ky)]-E[x-Kx]E[y-Ky] + covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];//(0,2)xz + covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];//(1,1)yy + covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];//(1,2)yz + covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];//(2,2)zz + covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); //(1,0)yx + covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); //(2,0)zx + covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); //(2,1)zy } return (static_cast (point_count)); } @@ -633,17 +634,17 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, if (point_count != 0) { accu /= static_cast (point_count); - centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z(); + centroid[0] = accu[6] + K.x(); centroid[1] = accu[7] + K.y(); centroid[2] = accu[8] + K.z();//effective mean E[P=(x,y,z)] centroid[3] = 1; - covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6]; - covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7]; - covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8]; - covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7]; - covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8]; - covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8]; - covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); - covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); - covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); + covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];//(0,0)xx : E[(x-E[x])^2]=E[x^2]-E[x]^2=E[(x-Kx)^2]-E[x-Kx]^2 + covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];//(0,1)xy : E[(x-E[x])(y-E[y])]=E[xy]-E[x]E[y]=E[(x-Kx)(y-Ky)]-E[x-Kx]E[y-Ky] + covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];//(0,2)xz + covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];//(1,1)yy + covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];//(1,2)yz + covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];//(2,2)zz + covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1); //(1,0)yx + covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2); //(2,0)zx + covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5); //(2,1)zy } return (static_cast (point_count)); } @@ -658,6 +659,275 @@ computeMeanAndCovarianceMatrix (const pcl::PointCloud &cloud, return (computeMeanAndCovarianceMatrix (cloud, indices.indices, covariance_matrix, centroid)); } +template inline unsigned int +computeCentroidAndOBB (const pcl::PointCloud &cloud, + Eigen::Matrix ¢roid, + Eigen::Matrix &obb_center, + Eigen::Matrix &obb_dimensions, + Eigen::Matrix &obb_rotational_matrix) +{ + Eigen::Matrix covariance_matrix; + Eigen::Matrix centroid4; + const auto point_count = computeMeanAndCovarianceMatrix(cloud, covariance_matrix, centroid4); + if (!point_count) + return (0); + centroid(0) = centroid4(0); + centroid(1) = centroid4(1); + centroid(2) = centroid4(2); + + const Eigen::SelfAdjointEigenSolver> evd(covariance_matrix); + const Eigen::Matrix eigenvectors_ = evd.eigenvectors(); + const Eigen::Matrix minor_axis = eigenvectors_.col(0);//the eigenvectors do not need to be normalized (they are already) + const Eigen::Matrix middle_axis = eigenvectors_.col(1); + // Enforce right hand rule: + const Eigen::Matrix major_axis = middle_axis.cross(minor_axis); + + obb_rotational_matrix << + major_axis(0), middle_axis(0), minor_axis(0), + major_axis(1), middle_axis(1), minor_axis(1), + major_axis(2), middle_axis(2), minor_axis(2); + //obb_rotational_matrix.col(0)==major_axis + //obb_rotational_matrix.col(1)==middle_axis + //obb_rotational_matrix.col(2)==minor_axis + + //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference + //with homogeneous matrix + //[R^t , -R^t*Centroid ] + //[0 , 1 ] + Eigen::Matrix transform = Eigen::Matrix::Identity(); + transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose(); + transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid; + + //when Scalar==double on a Windows 10 machine and MSVS: + //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse + Scalar obb_min_pointx, obb_min_pointy, obb_min_pointz; + Scalar obb_max_pointx, obb_max_pointy, obb_max_pointz; + obb_min_pointx = obb_min_pointy = obb_min_pointz = std::numeric_limits::max(); + obb_max_pointx = obb_max_pointy = obb_max_pointz = std::numeric_limits::min(); + + if (cloud.is_dense) + { + const auto& point = cloud[0]; + Eigen::Matrix P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + obb_min_pointx = obb_max_pointx = P(0); + obb_min_pointy = obb_max_pointy = P(1); + obb_min_pointz = obb_max_pointz = P(2); + + for (size_t i=1; i P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + if (P(0) < obb_min_pointx) + obb_min_pointx = P(0); + else if (P(0) > obb_max_pointx) + obb_max_pointx = P(0); + if (P(1) < obb_min_pointy) + obb_min_pointy = P(1); + else if (P(1) > obb_max_pointy) + obb_max_pointy = P(1); + if (P(2) < obb_min_pointz) + obb_min_pointz = P(2); + else if (P(2) > obb_max_pointz) + obb_max_pointz = P(2); + } + } + else + { + size_t i = 0; + for (; i < cloud.size(); ++i) + { + const auto& point = cloud[i]; + if (!isFinite(point)) + continue; + Eigen::Matrix P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + obb_min_pointx = obb_max_pointx = P(0); + obb_min_pointy = obb_max_pointy = P(1); + obb_min_pointz = obb_max_pointz = P(2); + ++i; + break; + } + + for (; i P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + if (P(0) < obb_min_pointx) + obb_min_pointx = P(0); + else if (P(0) > obb_max_pointx) + obb_max_pointx = P(0); + if (P(1) < obb_min_pointy) + obb_min_pointy = P(1); + else if (P(1) > obb_max_pointy) + obb_max_pointy = P(1); + if (P(2) < obb_min_pointz) + obb_min_pointz = P(2); + else if (P(2) > obb_max_pointz) + obb_max_pointz = P(2); + } + + } + + const Eigen::Matrix //shift between point cloud centroid and OBB center (position of the OBB center relative to (p.c.centroid, major_axis, middle_axis, minor_axis)) + shift((obb_max_pointx + obb_min_pointx) / 2.0f, + (obb_max_pointy + obb_min_pointy) / 2.0f, + (obb_max_pointz + obb_min_pointz) / 2.0f); + + obb_dimensions(0) = obb_max_pointx - obb_min_pointx; + obb_dimensions(1) = obb_max_pointy - obb_min_pointy; + obb_dimensions(2) = obb_max_pointz - obb_min_pointz; + + obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud + + return (point_count); +} + + +template inline unsigned int +computeCentroidAndOBB (const pcl::PointCloud &cloud, + const Indices &indices, + Eigen::Matrix ¢roid, + Eigen::Matrix &obb_center, + Eigen::Matrix &obb_dimensions, + Eigen::Matrix &obb_rotational_matrix) +{ + Eigen::Matrix covariance_matrix; + Eigen::Matrix centroid4; + const auto point_count = computeMeanAndCovarianceMatrix(cloud, indices, covariance_matrix, centroid4); + if (!point_count) + return (0); + centroid(0) = centroid4(0); + centroid(1) = centroid4(1); + centroid(2) = centroid4(2); + + const Eigen::SelfAdjointEigenSolver> evd(covariance_matrix); + const Eigen::Matrix eigenvectors_ = evd.eigenvectors(); + const Eigen::Matrix minor_axis = eigenvectors_.col(0);//the eigenvectors do not need to be normalized (they are already) + const Eigen::Matrix middle_axis = eigenvectors_.col(1); + // Enforce right hand rule: + const Eigen::Matrix major_axis = middle_axis.cross(minor_axis); + + obb_rotational_matrix << + major_axis(0), middle_axis(0), minor_axis(0), + major_axis(1), middle_axis(1), minor_axis(1), + major_axis(2), middle_axis(2), minor_axis(2); + //obb_rotational_matrix.col(0)==major_axis + //obb_rotational_matrix.col(1)==middle_axis + //obb_rotational_matrix.col(2)==minor_axis + + //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference + //with homogeneous matrix + //[R^t , -R^t*Centroid ] + //[0 , 1 ] + Eigen::Matrix transform = Eigen::Matrix::Identity(); + transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose(); + transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid; + + //when Scalar==double on a Windows 10 machine and MSVS: + //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse + Scalar obb_min_pointx, obb_min_pointy, obb_min_pointz; + Scalar obb_max_pointx, obb_max_pointy, obb_max_pointz; + obb_min_pointx = obb_min_pointy = obb_min_pointz = std::numeric_limits::max(); + obb_max_pointx = obb_max_pointy = obb_max_pointz = std::numeric_limits::min(); + + if (cloud.is_dense) + { + const auto& point = cloud[indices[0]]; + Eigen::Matrix P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + obb_min_pointx = obb_max_pointx = P(0); + obb_min_pointy = obb_max_pointy = P(1); + obb_min_pointz = obb_max_pointz = P(2); + + for (size_t i=1; i P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + if (P(0) < obb_min_pointx) + obb_min_pointx = P(0); + else if (P(0) > obb_max_pointx) + obb_max_pointx = P(0); + if (P(1) < obb_min_pointy) + obb_min_pointy = P(1); + else if (P(1) > obb_max_pointy) + obb_max_pointy = P(1); + if (P(2) < obb_min_pointz) + obb_min_pointz = P(2); + else if (P(2) > obb_max_pointz) + obb_max_pointz = P(2); + } + } + else + { + size_t i = 0; + for (; i P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + obb_min_pointx = obb_max_pointx = P(0); + obb_min_pointy = obb_max_pointy = P(1); + obb_min_pointz = obb_max_pointz = P(2); + ++i; + break; + } + + for (; i P0(static_cast(point.x), static_cast(point.y) , static_cast(point.z), 1.0); + Eigen::Matrix P = transform * P0; + + if (P(0) < obb_min_pointx) + obb_min_pointx = P(0); + else if (P(0) > obb_max_pointx) + obb_max_pointx = P(0); + if (P(1) < obb_min_pointy) + obb_min_pointy = P(1); + else if (P(1) > obb_max_pointy) + obb_max_pointy = P(1); + if (P(2) < obb_min_pointz) + obb_min_pointz = P(2); + else if (P(2) > obb_max_pointz) + obb_max_pointz = P(2); + } + + } + + const Eigen::Matrix //shift between point cloud centroid and OBB center (position of the OBB center relative to (p.c.centroid, major_axis, middle_axis, minor_axis)) + shift((obb_max_pointx + obb_min_pointx) / 2.0f, + (obb_max_pointy + obb_min_pointy) / 2.0f, + (obb_max_pointz + obb_min_pointz) / 2.0f); + + obb_dimensions(0) = obb_max_pointx - obb_min_pointx; + obb_dimensions(1) = obb_max_pointy - obb_min_pointy; + obb_dimensions(2) = obb_max_pointz - obb_min_pointz; + + obb_center = centroid + obb_rotational_matrix * shift;//position of the OBB center in the same reference Oxyz of the point cloud + + return (point_count); +} + + template void demeanPointCloud (ConstCloudIterator &cloud_iterator, diff --git a/doc/tutorials/content/moment_of_inertia.rst b/doc/tutorials/content/moment_of_inertia.rst index a50834e286a..0735f9fe869 100644 --- a/doc/tutorials/content/moment_of_inertia.rst +++ b/doc/tutorials/content/moment_of_inertia.rst @@ -5,7 +5,8 @@ Moment of inertia and eccentricity based descriptors In this tutorial we will learn how to use the `pcl::MomentOfInertiaEstimation` class in order to obtain descriptors based on eccentricity and moment of inertia. This class also allows to extract axis aligned and oriented bounding boxes of the cloud. -But keep in mind that extracted OBB is not the minimal possible bounding box. +But keep in mind that extracted OBB is not the minimal possible bounding box. Users who only need the OBB or AABB, but not the descriptors, +should use respectively computeCentroidAndOBB or getMinMax3D (faster). Theoretical Primer ------------------ diff --git a/test/common/test_centroid.cpp b/test/common/test_centroid.cpp index a87782a83d2..93e3b5a370c 100644 --- a/test/common/test_centroid.cpp +++ b/test/common/test_centroid.cpp @@ -837,6 +837,140 @@ TEST (PCL, computeMeanAndCovariance) EXPECT_EQ (covariance_matrix (2, 2), 1); } + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +TEST (PCL, computeCentroidAndOBB) +{ + PointCloud cloud; + PointXYZ point; + Indices indices; + Eigen::Vector3f centroid = Eigen::Vector3f::Random(); + Eigen::Vector3f major_axis; + Eigen::Vector3f middle_axis; + Eigen::Vector3f minor_axis; + Eigen::Matrix obb_position; + Eigen::Matrix obb_dimensions; + Eigen::Matrix3f obb_rotational_matrix= Eigen::Matrix3f::Random(); + + const Eigen::Vector3f old_centroid = centroid; + const Eigen::Matrix3f old_obb_rotational_matrix= obb_rotational_matrix; + + // test empty cloud which is dense + cloud.is_dense = true; + EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0); + EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged + EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged + + // test empty cloud non_dense + cloud.is_dense = false; + EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0); + EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged + EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged + + // test non-empty cloud non_dense with no valid points + point.x = point.y = point.z = std::numeric_limits::quiet_NaN (); + cloud.push_back (point); + EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0); + EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged + EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged + + // test non-empty cloud non_dense with no valid points + point.x = point.y = point.z = std::numeric_limits::quiet_NaN (); + cloud.push_back (point); + indices.push_back (1); + EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 0); + EXPECT_EQ (old_centroid, centroid); // centroid remains unchanged + EXPECT_EQ (old_obb_rotational_matrix, obb_rotational_matrix); // obb_rotational_matrix remains unchanged + + cloud.clear (); + indices.clear (); + // -1 -1 -1 / -1 -1 1 / -1 1 -1 / -1 1 1 / 1 -1 -1 / 1 -1 1 / 1 1 -1 / 1 1 1 + for (point.x = -1; point.x < 2; point.x += 2) + { + for (point.y = -1; point.y < 2; point.y += 2) + { + for (point.z = -1; point.z < 2; point.z += 2) + { + cloud.push_back (point); + } + } + } + cloud.is_dense = true; + + // eight points with (0, 0, 0) as centroid + + centroid [0] = -100; + centroid [1] = -101; + centroid [2] = -102; + EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 8); + EXPECT_EQ (centroid [0], 0); + EXPECT_EQ (centroid [1], 0); + EXPECT_EQ (centroid [2], 0); + EXPECT_NEAR (obb_position(0), 0, 0.01); + EXPECT_NEAR (obb_position(1), 0, 0.01); + EXPECT_NEAR (obb_position(2), 0, 0.01); + EXPECT_NEAR (obb_dimensions(0), 2, 0.01); + EXPECT_NEAR (obb_dimensions(1), 2, 0.01); + EXPECT_NEAR (obb_dimensions(2), 2, 0.01); + + + indices.resize (4); // only positive y values + indices [0] = 2; + indices [1] = 3; + indices [2] = 6; + indices [3] = 7; + centroid [0] = -100; + centroid [1] = -101; + centroid [2] = -102; + + EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 4); + EXPECT_EQ (centroid [0], 0); + EXPECT_NEAR (centroid [1], 1, 0.001); + EXPECT_EQ (centroid [2], 0); + EXPECT_NEAR (obb_position(0), 0, 0.01); + EXPECT_NEAR (obb_position(1), 1, 0.01); + EXPECT_NEAR (obb_position(2), 0, 0.01); + EXPECT_NEAR (obb_dimensions(0), 2, 0.01); + EXPECT_NEAR (obb_dimensions(1), 2, 0.01); + EXPECT_NEAR (obb_dimensions(2), 0, 0.01); + + + point.x = point.y = point.z = std::numeric_limits::quiet_NaN (); + cloud.push_back (point); + cloud.is_dense = false; + centroid [0] = -100; + centroid [1] = -101; + centroid [2] = -102; + EXPECT_EQ (computeCentroidAndOBB (cloud, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 8); + EXPECT_EQ (centroid [0], 0); + EXPECT_EQ (centroid [1], 0); + EXPECT_EQ (centroid [2], 0); + EXPECT_NEAR (obb_position(0), 0, 0.01); + EXPECT_NEAR (obb_position(1), 0, 0.01); + EXPECT_NEAR (obb_position(2), 0, 0.01); + EXPECT_NEAR (obb_dimensions(0), 2, 0.01); + EXPECT_NEAR (obb_dimensions(1), 2, 0.01); + EXPECT_NEAR (obb_dimensions(2), 2, 0.01); + + + indices.push_back (8); // add the NaN + centroid [0] = -100; + centroid [1] = -101; + centroid [2] = -102; + + EXPECT_EQ (computeCentroidAndOBB (cloud, indices, centroid, obb_position, obb_dimensions, obb_rotational_matrix), 4); + EXPECT_EQ (centroid [0], 0); + EXPECT_NEAR (centroid [1], 1, 0.001); + EXPECT_EQ (centroid [2], 0); + EXPECT_NEAR (obb_position(0), 0, 0.01); + EXPECT_NEAR (obb_position(1), 1, 0.01); + EXPECT_NEAR (obb_position(2), 0, 0.01); + EXPECT_NEAR (obb_dimensions(0), 2, 0.01); + EXPECT_NEAR (obb_dimensions(1), 2, 0.01); + EXPECT_NEAR (obb_dimensions(2), 0, 0.01); + +} + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, CentroidPoint) { From 14caf35822282ea5f7921b7011296531aed19855 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 10 Jun 2023 11:17:23 +0200 Subject: [PATCH 093/288] Ubuntu variety: update available package version --- .ci/azure-pipelines/ubuntu-variety.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml index 12ae9db0ccb..e085ba0346d 100644 --- a/.ci/azure-pipelines/ubuntu-variety.yaml +++ b/.ci/azure-pipelines/ubuntu-variety.yaml @@ -29,12 +29,12 @@ jobs: displayName: "BuildUbuntuVariety" steps: - script: | - POSSIBLE_VTK_VERSION=("7" "9") \ + POSSIBLE_VTK_VERSION=("9") \ POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \ POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \ - POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15") \ - POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15") \ - POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15") \ + POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \ + POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \ + POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16") \ CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \ dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \ echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs" From 053995b7ed94140a2acae62c8f12608a48d1311e Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 11 Jun 2023 11:56:23 +0200 Subject: [PATCH 094/288] Small fixes and code improvements - in PCLPointCloud2.h, a cast is necessary, otherwise the elements are printed as characters instead of numbers - in setNumberOfThreads, add debug output/warning if OpenMP is not available - resize is more efficient than substr - implicit_shape_model.hpp: move peak_counter increment inside if-statement. This does not change much in practice because all of the peak_densities are larger than -1.0, but it silences the warning that strongest_peak may be uninitialized - region_growing.hpp and region_growing_rgb.hpp: switch range-for-loop, while also fixing bug (i_point was used in nearestKSearch, but point_index should have been used instead) - pcl_visualizer.hpp: make sure that point and normals are finite, otherwise VTK displays strange things --- common/include/pcl/PCLPointCloud2.h | 2 +- common/include/pcl/impl/pcl_base.hpp | 1 + common/src/pcl_base.cpp | 1 + .../include/pcl/features/impl/normal_3d_omp.hpp | 11 +++++++---- io/include/pcl/io/io.h | 1 + io/src/lzf_image_io.cpp | 2 +- .../pcl/recognition/impl/implicit_shape_model.hpp | 2 +- .../pcl/segmentation/impl/region_growing.hpp | 13 +++++-------- .../pcl/segmentation/impl/region_growing_rgb.hpp | 6 ++---- .../pcl/visualization/impl/pcl_visualizer.hpp | 7 ++++++- 10 files changed, 26 insertions(+), 20 deletions(-) diff --git a/common/include/pcl/PCLPointCloud2.h b/common/include/pcl/PCLPointCloud2.h index cf78ad396b1..ec3f9562785 100644 --- a/common/include/pcl/PCLPointCloud2.h +++ b/common/include/pcl/PCLPointCloud2.h @@ -143,7 +143,7 @@ namespace pcl for (std::size_t i = 0; i < v.data.size (); ++i) { s << " data[" << i << "]: "; - s << " " << v.data[i] << std::endl; + s << " " << static_cast(v.data[i]) << std::endl; } s << "is_dense: "; s << " " << v.is_dense << std::endl; diff --git a/common/include/pcl/impl/pcl_base.hpp b/common/include/pcl/impl/pcl_base.hpp index 3caf96c4304..6e548958828 100644 --- a/common/include/pcl/impl/pcl_base.hpp +++ b/common/include/pcl/impl/pcl_base.hpp @@ -162,6 +162,7 @@ pcl::PCLBase::initCompute () catch (const std::bad_alloc&) { PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", input_->size ()); + return (false); } for (auto i = indices_size; i < indices_->size (); ++i) { (*indices_)[i] = static_cast(i); } } diff --git a/common/src/pcl_base.cpp b/common/src/pcl_base.cpp index 4b3f18da9a1..b53d0a87ead 100644 --- a/common/src/pcl_base.cpp +++ b/common/src/pcl_base.cpp @@ -124,6 +124,7 @@ pcl::PCLBase::initCompute () catch (const std::bad_alloc&) { PCL_ERROR ("[initCompute] Failed to allocate %lu indices.\n", (input_->width * input_->height)); + return (false); } if (indices_size < indices_->size ()) std::iota(indices_->begin () + indices_size, indices_->end (), indices_size); diff --git a/features/include/pcl/features/impl/normal_3d_omp.hpp b/features/include/pcl/features/impl/normal_3d_omp.hpp index b1a317598e6..a40b2bb2c2a 100644 --- a/features/include/pcl/features/impl/normal_3d_omp.hpp +++ b/features/include/pcl/features/impl/normal_3d_omp.hpp @@ -47,14 +47,17 @@ template void pcl::NormalEstimationOMP::setNumberOfThreads (unsigned int nr_threads) { - if (nr_threads == 0) #ifdef _OPENMP + if (nr_threads == 0) threads_ = omp_get_num_procs(); -#else - threads_ = 1; -#endif else threads_ = nr_threads; + PCL_DEBUG ("[pcl::NormalEstimationOMP::setNumberOfThreads] Setting number of threads to %u.\n", threads_); +#else + threads_ = 1; + if (nr_threads != 1) + PCL_WARN ("[pcl::NormalEstimationOMP::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n"); +#endif // _OPENMP } /////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/include/pcl/io/io.h b/io/include/pcl/io/io.h index ab579c77a80..62b3289daf4 100644 --- a/io/include/pcl/io/io.h +++ b/io/include/pcl/io/io.h @@ -38,5 +38,6 @@ */ #pragma once +#include // for PCL_DEPRECATED_HEADER PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/io.h directly.") #include diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index a5b396f5209..b3b61c638a2 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -135,7 +135,7 @@ pcl::io::LZFImageWriter::compress (const char* input, if (itype.size () > 16) { PCL_WARN ("[pcl::io::LZFImageWriter::compress] Image type should be a string of maximum 16 characters! Cutting %s to %s.\n", image_type.c_str (), image_type.substr (0, 15).c_str ()); - itype = itype.substr (0, 15); + itype.resize(16); } if (itype.size () < 16) itype.insert (itype.end (), 16 - itype.size (), ' '); diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index 2e736eb76ba..94afed0d52b 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -192,8 +192,8 @@ pcl::features::ISMVoteList::findStrongestPeaks ( best_density = peak_densities[i]; strongest_peak = peaks[i]; best_peak_ind = i; + ++peak_counter; } - ++peak_counter; } if( peak_counter == 0 ) diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index 754ecb14e98..be75d0cf7ba 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -342,30 +342,27 @@ pcl::RegionGrowing::prepareForSegmentation () template void pcl::RegionGrowing::findPointNeighbours () { - int point_number = static_cast (indices_->size ()); pcl::Indices neighbours; std::vector distances; point_neighbours_.resize (input_->size (), neighbours); if (input_->is_dense) { - for (int i_point = 0; i_point < point_number; i_point++) + for (const auto& point_index: (*indices_)) { - const auto point_index = (*indices_)[i_point]; neighbours.clear (); - search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); + search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances); point_neighbours_[point_index].swap (neighbours); } } else { - for (int i_point = 0; i_point < point_number; i_point++) + for (const auto& point_index: (*indices_)) { - neighbours.clear (); - const auto point_index = (*indices_)[i_point]; if (!pcl::isFinite ((*input_)[point_index])) continue; - search_->nearestKSearch (i_point, neighbour_number_, neighbours, distances); + neighbours.clear (); + search_->nearestKSearch (point_index, neighbour_number_, neighbours, distances); point_neighbours_[point_index].swap (neighbours); } } diff --git a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp index 9ea6cd9cd32..b53a704b09c 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp @@ -272,19 +272,17 @@ pcl::RegionGrowingRGB::prepareForSegmentation () template void pcl::RegionGrowingRGB::findPointNeighbours () { - int point_number = static_cast (indices_->size ()); pcl::Indices neighbours; std::vector distances; point_neighbours_.resize (input_->size (), neighbours); point_distances_.resize (input_->size (), distances); - for (int i_point = 0; i_point < point_number; i_point++) + for (const auto& point_index: (*indices_)) { - int point_index = (*indices_)[i_point]; neighbours.clear (); distances.clear (); - search_->nearestKSearch (i_point, region_neighbour_number_, neighbours, distances); + search_->nearestKSearch (point_index, region_neighbour_number_, neighbours, distances); point_neighbours_[point_index].swap (neighbours); point_distances_[point_index].swap (distances); } diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index 88cec70e390..0f746cabb83 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -906,6 +906,8 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( for (vtkIdType x = 0; x < normals->width; x += point_step) { PointT p = (*cloud)(x, y); + if (!pcl::isFinite(p) || !pcl::isNormalFinite((*normals)(x, y))) + continue; p.x += (*normals)(x, y).normal[0] * scale; p.y += (*normals)(x, y).normal[1] * scale; p.z += (*normals)(x, y).normal[2] * scale; @@ -928,8 +930,10 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( nr_normals = (cloud->size () - 1) / level + 1 ; pts = new float[2 * nr_normals * 3]; - for (vtkIdType i = 0, j = 0; j < nr_normals; j++, i = j * level) + for (vtkIdType i = 0, j = 0; (j < nr_normals) && (i < static_cast(cloud->size())); i += level) { + if (!pcl::isFinite((*cloud)[i]) || !pcl::isNormalFinite((*normals)[i])) + continue; PointT p = (*cloud)[i]; p.x += (*normals)[i].normal[0] * scale; p.y += (*normals)[i].normal[1] * scale; @@ -945,6 +949,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( lines->InsertNextCell (2); lines->InsertCellPoint (2 * j); lines->InsertCellPoint (2 * j + 1); + ++j; } } From 8fb956d28a96bb66716a86002ea3faf5e0de220b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 11 Jun 2023 16:01:53 +0200 Subject: [PATCH 095/288] Improve doc and tutorials - fix broken links - add missing include in tutorial - change `find_package(PCL ...)` call to search for all components, instead of only two components. This is easier and less error-prone for CMake beginners, who may copy the command without fully understanding it, and later wonder why link errors appear when they use classes from other modules. The tutorial later also shows how to request some components only. --- doc/tutorials/content/compiling_pcl_posix.rst | 9 ++++----- .../content/global_hypothesis_verification.rst | 2 +- doc/tutorials/content/moment_of_inertia.rst | 2 +- ...normal_estimation_using_integral_images.rst | 3 ++- doc/tutorials/content/registration_api.rst | 2 +- .../cluster_extraction/cluster_extraction.cpp | 2 +- .../implicit_shape_model.cpp | 2 +- doc/tutorials/content/using_pcl_pcl_config.rst | 6 +++--- doc/tutorials/content/walkthrough.rst | 18 +++++++++--------- .../pcl/segmentation/min_cut_segmentation.h | 1 + ...rganized_connected_component_segmentation.h | 1 + 11 files changed, 25 insertions(+), 23 deletions(-) diff --git a/doc/tutorials/content/compiling_pcl_posix.rst b/doc/tutorials/content/compiling_pcl_posix.rst index 3265435ef80..b77120c819a 100644 --- a/doc/tutorials/content/compiling_pcl_posix.rst +++ b/doc/tutorials/content/compiling_pcl_posix.rst @@ -89,14 +89,13 @@ The following code libraries are **required** for the compilation and usage of t +---------------------------------------------------------------+-----------------+-------------------------+-------------------+ | Logo | Library | Minimum version | Mandatory | +===============================================================+=================+=========================+===================+ -| .. image:: images/posix_building_pcl/boost_logo.png | Boost | | 1.40 (without OpenNI) | pcl_* | -| | | | 1.47 (with OpenNI) | | +| .. image:: images/posix_building_pcl/boost_logo.png | Boost | 1.65 | pcl_* | +---------------------------------------------------------------+-----------------+-------------------------+-------------------+ -| .. image:: images/posix_building_pcl/eigen_logo.png | Eigen | 3.0 | pcl_* | +| .. image:: images/posix_building_pcl/eigen_logo.png | Eigen | 3.3 | pcl_* | +---------------------------------------------------------------+-----------------+-------------------------+-------------------+ -| .. image:: images/posix_building_pcl/flann_logo.png | FLANN | 1.7.1 | pcl_* | +| .. image:: images/posix_building_pcl/flann_logo.png | FLANN | 1.9.1 | pcl_* | +---------------------------------------------------------------+-----------------+-------------------------+-------------------+ -| .. image:: images/posix_building_pcl/vtk_logo.png | VTK | 5.6 | pcl_visualization | +| .. image:: images/posix_building_pcl/vtk_logo.png | VTK | 6.2 | pcl_visualization | +---------------------------------------------------------------+-----------------+-------------------------+-------------------+ Optional diff --git a/doc/tutorials/content/global_hypothesis_verification.rst b/doc/tutorials/content/global_hypothesis_verification.rst index e0a41121352..d30b56cfba0 100644 --- a/doc/tutorials/content/global_hypothesis_verification.rst +++ b/doc/tutorials/content/global_hypothesis_verification.rst @@ -99,7 +99,7 @@ Take a look at the full pipeline: :lines: 245-374 :emphasize-lines: 6,9 -For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping `_. +For a full explanation of the above code see `3D Object Recognition based on Correspondence Grouping `_. Model-in-Scene Projection diff --git a/doc/tutorials/content/moment_of_inertia.rst b/doc/tutorials/content/moment_of_inertia.rst index a50834e286a..c21aad46728 100644 --- a/doc/tutorials/content/moment_of_inertia.rst +++ b/doc/tutorials/content/moment_of_inertia.rst @@ -33,7 +33,7 @@ The code -------- First of all you will need the point cloud for this tutorial. -`This `_ is the one presented on the screenshots. +`This `_ is the one presented on the screenshots. Next what you need to do is to create a file ``moment_of_inertia.cpp`` in any editor you prefer and copy the following code inside of it: .. literalinclude:: sources/moment_of_inertia/moment_of_inertia.cpp diff --git a/doc/tutorials/content/normal_estimation_using_integral_images.rst b/doc/tutorials/content/normal_estimation_using_integral_images.rst index 662bdbe117e..1ddb809a798 100644 --- a/doc/tutorials/content/normal_estimation_using_integral_images.rst +++ b/doc/tutorials/content/normal_estimation_using_integral_images.rst @@ -46,7 +46,8 @@ The following normal estimation methods are available: { COVARIANCE_MATRIX, AVERAGE_3D_GRADIENT, - AVERAGE_DEPTH_CHANGE + AVERAGE_DEPTH_CHANGE, + SIMPLE_3D_GRADIENT }; The COVARIANCE_MATRIX mode creates 9 integral images to compute the normal for diff --git a/doc/tutorials/content/registration_api.rst b/doc/tutorials/content/registration_api.rst index 1988e575cc6..94a3afedfbf 100644 --- a/doc/tutorials/content/registration_api.rst +++ b/doc/tutorials/content/registration_api.rst @@ -84,7 +84,7 @@ keypoints as well. The problem with "feeding two kinect datasets into a correspo Feature descriptors =================== -Based on the keypoints found we have to extract [features](http://www.pointclouds.org/documentation/tutorials/how_features_work.php), where we assemble the information and generate vectors to compare them with each other. Again there +Based on the keypoints found we have to extract `features `_, where we assemble the information and generate vectors to compare them with each other. Again there is a number of feature options to choose from, for example NARF, FPFH, BRIEF or SIFT. diff --git a/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp b/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp index d3cdee44b16..b5953e8f15b 100644 --- a/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp +++ b/doc/tutorials/content/sources/cluster_extraction/cluster_extraction.cpp @@ -9,7 +9,7 @@ #include #include #include - +#include // for setw, setfill int main () diff --git a/doc/tutorials/content/sources/implicit_shape_model/implicit_shape_model.cpp b/doc/tutorials/content/sources/implicit_shape_model/implicit_shape_model.cpp index 7343c9a11a2..cfd8b9f597e 100644 --- a/doc/tutorials/content/sources/implicit_shape_model/implicit_shape_model.cpp +++ b/doc/tutorials/content/sources/implicit_shape_model/implicit_shape_model.cpp @@ -11,7 +11,7 @@ int main (int argc, char** argv) { - if (argc == 0 || argc % 2 == 0) + if (argc < 5 || argc % 2 == 0) // needs at least one training cloud with class id, plus testing cloud with class id (plus name of executable) return (-1); unsigned int number_of_training_clouds = (argc - 3) / 2; diff --git a/doc/tutorials/content/using_pcl_pcl_config.rst b/doc/tutorials/content/using_pcl_pcl_config.rst index a138fd3c2f6..ae3fe9a1832 100644 --- a/doc/tutorials/content/using_pcl_pcl_config.rst +++ b/doc/tutorials/content/using_pcl_pcl_config.rst @@ -23,7 +23,7 @@ CMakeLists.txt that contains: cmake_minimum_required(VERSION 2.6 FATAL_ERROR) project(MY_GRAND_PROJECT) - find_package(PCL 1.3 REQUIRED COMPONENTS common io) + find_package(PCL 1.3 REQUIRED) include_directories(${PCL_INCLUDE_DIRS}) link_directories(${PCL_LIBRARY_DIRS}) add_definitions(${PCL_DEFINITIONS}) @@ -53,7 +53,7 @@ invoking cmake (MY_GRAND_PROJECT_BINARY_DIR). .. code-block:: cmake - find_package(PCL 1.3 REQUIRED COMPONENTS common io) + find_package(PCL 1.3 REQUIRED) We are requesting to find the PCL package at minimum version 1.3. We also say that it is ``REQUIRED`` meaning that cmake will fail @@ -204,4 +204,4 @@ before this one: .. code-block:: cmake - find_package(PCL 1.3 REQUIRED COMPONENTS common io) + find_package(PCL 1.3 REQUIRED) diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index d6da4390c32..971d9a8f78e 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -104,7 +104,7 @@ Features **Background** A theoretical primer explaining how features work in PCL can be found in the `3D Features tutorial - `_. + `_. The *features* library contains data structures and mechanisms for 3D feature estimation from point cloud data. 3D features are representations at certain 3D points, or positions, in space, which describe geometrical patterns based on the information available around the point. The data space selected around the query point is usually referred to as the *k-neighborhood*. @@ -247,7 +247,7 @@ Kd-tree **Background** - A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial `_. + A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial `_. The *kdtree* library provides the kd-tree data-structure, using `FLANN `_, that allows for fast `nearest neighbor searches `_. @@ -331,7 +331,7 @@ Segmentation The *segmentation* library contains algorithms for segmenting a point cloud into distinct clusters. These algorithms are best suited for processing a point cloud that is composed of a number of spatially isolated regions. In such cases, clustering is often used to break the cloud down into its constituent parts, which can then be processed independently. - A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial `_. + A theoretical primer explaining how clustering methods work can be found in the `cluster extraction tutorial `_. The two figures illustrate the results of plane model segmentation (left) and cylinder model segmentation (right). .. image:: images/plane_model_seg.jpg @@ -378,7 +378,7 @@ Sample Consensus 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 `_ + A theoretical primer explaining how sample consensus algorithms work can be found in the `Random Sample Consensus tutorial `_ Some of the models implemented in this library include: lines, planes, cylinders, and spheres. Plane fitting is often applied to the task of detecting common indoor surfaces, such as walls, floors, and table tops. Other models can be used to detect and segment objects with common geometric structures (e.g., fitting a cylinder model to a mug). @@ -505,10 +505,10 @@ I/O The *io* library contains classes and functions for reading and writing point cloud data (PCD) files, as well as capturing point clouds from a variety of sensing devices. An introduction to some of these capabilities can be found in the following tutorials: - * `The PCD (Point Cloud Data) file format `_ - * `Reading PointCloud data from PCD files `_ - * `Writing PointCloud data to PCD files `_ - * `The OpenNI Grabber Framework in PCL `_ + * `The PCD (Point Cloud Data) file format `_ + * `Reading PointCloud data from PCD files `_ + * `Writing PointCloud data to PCD files `_ + * `The OpenNI Grabber Framework in PCL `_ | @@ -682,7 +682,7 @@ Binaries This section provides a quick reference for some of the common tools in PCL. - * ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial `_. + * ``pcl_viewer``: a quick way for visualizing PCD (Point Cloud Data) files. More information about PCD files can be found in the `PCD file format tutorial `_. **Syntax is: pcl_viewer . **, where options are: diff --git a/segmentation/include/pcl/segmentation/min_cut_segmentation.h b/segmentation/include/pcl/segmentation/min_cut_segmentation.h index 888cdc13f42..3059f9e517e 100644 --- a/segmentation/include/pcl/segmentation/min_cut_segmentation.h +++ b/segmentation/include/pcl/segmentation/min_cut_segmentation.h @@ -54,6 +54,7 @@ namespace pcl * The description can be found in the article: * "Min-Cut Based Segmentation of Point Clouds" * \author: Aleksey Golovinskiy and Thomas Funkhouser. + * \ingroup segmentation */ template class PCL_EXPORTS MinCutSegmentation : public pcl::PCLBase diff --git a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h index 30890706c57..8bf5c5ffe7e 100644 --- a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h @@ -53,6 +53,7 @@ namespace pcl * See OrganizedMultiPlaneSegmentation for an example application. * * \author Alex Trevor, Suat Gedikli + * \ingroup segmentation */ template class OrganizedConnectedComponentSegmentation : public PCLBase From cf46790f4e839d48f9bf62c75d4a037db566ff5b Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Mon, 12 Jun 2023 15:20:26 +0200 Subject: [PATCH 096/288] Make OpenMP available in downstream projects (#5744) * Make OpenMP available in downstream projects Previously, if a downstream project used PCL_NO_PRECOMPILE or if it used a PCL class which includes OpenMP code, but PCL does not make an instantiation of that class, OpenMP was not available. In other words, when PCL code using OpenMP was compiled when building PCL, OpenMP was available. However when PCL code using OpenMP was compiled in the downstream/user project (e.g. in the two mentioned cases), OpenMP was not available. The fix is to search for OpenMP again in PCLConfig.cmake * OpenMP as dep for more modules --- PCLConfig.cmake.in | 5 +++++ features/CMakeLists.txt | 2 +- filters/CMakeLists.txt | 2 +- io/CMakeLists.txt | 4 ++-- keypoints/CMakeLists.txt | 2 +- registration/CMakeLists.txt | 2 +- segmentation/CMakeLists.txt | 2 +- surface/CMakeLists.txt | 2 +- tracking/CMakeLists.txt | 2 +- 9 files changed, 14 insertions(+), 9 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index d3fa589a6d9..746e191d67f 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -303,6 +303,11 @@ function(find_external_library _component _lib _is_optional) find_package(Pcap) elseif("${_lib}" STREQUAL "png") find_package(PNG) + elseif("${_lib}" STREQUAL "OpenMP") + find_package(OpenMP COMPONENTS CXX) + # the previous find_package call sets OpenMP_CXX_LIBRARIES, but not OPENMP_LIBRARIES, which is used further down + # we can link to the CMake target OpenMP::OpenMP_CXX by setting the following: + set(OPENMP_LIBRARIES OpenMP::OpenMP_CXX) else() message(WARNING "${_lib} is not handled by find_external_library") endif() diff --git a/features/CMakeLists.txt b/features/CMakeLists.txt index e04bdab7276..b5f902aece8 100644 --- a/features/CMakeLists.txt +++ b/features/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common search kdtree octree filters 2d) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/filters/CMakeLists.txt b/filters/CMakeLists.txt index 5e9def6fd5b..f4541889fdf 100644 --- a/filters/CMakeLists.txt +++ b/filters/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common sample_consensus search kdtree octree) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index dcba298032d..e5fc2095192 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -6,9 +6,9 @@ set(SUBSYS_EXT_DEPS boost eigen) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) if(WIN32) - PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk rssdk2 pcap png vtk EXT_DEPS ${SUBSYS_EXT_DEPS}) + PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk rssdk2 pcap png vtk OpenMP EXT_DEPS ${SUBSYS_EXT_DEPS}) else() - PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk pcap png vtk libusb EXT_DEPS ${SUBSYS_EXT_DEPS}) + PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk pcap png vtk libusb OpenMP EXT_DEPS ${SUBSYS_EXT_DEPS}) endif() PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/keypoints/CMakeLists.txt b/keypoints/CMakeLists.txt index 92180e4062a..480e022f253 100644 --- a/keypoints/CMakeLists.txt +++ b/keypoints/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common search kdtree octree features filters) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/registration/CMakeLists.txt b/registration/CMakeLists.txt index a8c137e9f3f..7dce51a2f91 100644 --- a/registration/CMakeLists.txt +++ b/registration/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common octree kdtree search sample_consensus features filters) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/segmentation/CMakeLists.txt b/segmentation/CMakeLists.txt index 89bea126d82..1a8420fe964 100644 --- a/segmentation/CMakeLists.txt +++ b/segmentation/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common geometry search sample_consensus kdtree octree features f set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index c29105e6a67..761916ec7a9 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common search kdtree octree) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS qhull vtk) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS qhull vtk OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/tracking/CMakeLists.txt b/tracking/CMakeLists.txt index c0af2795316..985e4ce64dc 100644 --- a/tracking/CMakeLists.txt +++ b/tracking/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS common search kdtree filters octree) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) PCL_ADD_DOC("${SUBSYS_NAME}") From e1b34f7b4a0669b9c50439e61910c9f5af791728 Mon Sep 17 00:00:00 2001 From: Rasmus Diederichsen Date: Sun, 2 Jul 2023 10:11:42 +0200 Subject: [PATCH 097/288] ICP: remove possibly inappropriate default setting of rotation convergence threshold when user does not set it. --- registration/include/pcl/registration/impl/icp.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/registration/include/pcl/registration/impl/icp.hpp b/registration/include/pcl/registration/impl/icp.hpp index 23d715f86b5..2b48169f1b2 100644 --- a/registration/include/pcl/registration/impl/icp.hpp +++ b/registration/include/pcl/registration/impl/icp.hpp @@ -159,8 +159,6 @@ IterativeClosestPoint::computeTransformation( convergence_criteria_->setTranslationThreshold(transformation_epsilon_); if (transformation_rotation_epsilon_ > 0) convergence_criteria_->setRotationThreshold(transformation_rotation_epsilon_); - else - convergence_criteria_->setRotationThreshold(1.0 - transformation_epsilon_); // Repeat until convergence do { From 7a70069129d9203ddc744cde58917e8c12032c4f Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Fri, 7 Jul 2023 14:09:05 +0200 Subject: [PATCH 098/288] ApproximateProgressiveMorphologicalFilter: check for finite-ness (#5756) * ApproximateProgressiveMorphologicalFilter: check for finite-ness * Add additional tests, and only test finite-ness if cloud is not dense --- ...imate_progressive_morphological_filter.hpp | 50 ++++++++++++++----- 1 file changed, 38 insertions(+), 12 deletions(-) diff --git a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp index 81729e64c21..4a98b2e33bf 100644 --- a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -41,6 +41,7 @@ #include #include +#include // for isFinite #include #include #include @@ -122,26 +123,51 @@ pcl::ApproximateProgressiveMorphologicalFilter::extract (Indices& ground Eigen::MatrixXf Zf (rows, cols); Zf.setConstant (std::numeric_limits::quiet_NaN ()); + if (input_->is_dense) { #pragma omp parallel for \ default(none) \ shared(A, global_min) \ num_threads(threads_) - for (int i = 0; i < static_cast(input_->size ()); ++i) - { - // ...then test for lower points within the cell - PointT p = (*input_)[i]; - int row = std::floor((p.y - global_min.y ()) / cell_size_); - int col = std::floor((p.x - global_min.x ()) / cell_size_); - - if (p.z < A (row, col) || std::isnan (A (row, col))) - { - A (row, col) = p.z; + for (int i = 0; i < static_cast(input_->size ()); ++i) { + // ...then test for lower points within the cell + const PointT& p = (*input_)[i]; + int row = std::floor((p.y - global_min.y ()) / cell_size_); + int col = std::floor((p.x - global_min.x ()) / cell_size_); + + if (p.z < A (row, col) || std::isnan (A (row, col))) + A (row, col) = p.z; + } + } + else { +#pragma omp parallel for \ + default(none) \ + shared(A, global_min) \ + num_threads(threads_) + for (int i = 0; i < static_cast(input_->size ()); ++i) { + // ...then test for lower points within the cell + const PointT& p = (*input_)[i]; + if (!pcl::isFinite(p)) + continue; + int row = std::floor((p.y - global_min.y ()) / cell_size_); + int col = std::floor((p.x - global_min.x ()) / cell_size_); + + if (p.z < A (row, col) || std::isnan (A (row, col))) + A (row, col) = p.z; } } // Ground indices are initially limited to those points in the input cloud we // wish to process - ground = *indices_; + if (input_->is_dense) { + ground = *indices_; + } + else { + ground.clear(); + ground.reserve(indices_->size()); + for (const auto& index: *indices_) + if (pcl::isFinite((*input_)[index])) + ground.push_back(index); + } // Progressively filter ground returns using morphological open for (std::size_t i = 0; i < window_sizes.size (); ++i) @@ -229,7 +255,7 @@ pcl::ApproximateProgressiveMorphologicalFilter::extract (Indices& ground Indices pt_indices; for (std::size_t p_idx = 0; p_idx < ground.size (); ++p_idx) { - PointT p = (*cloud)[p_idx]; + const PointT& p = (*cloud)[p_idx]; int erow = static_cast (std::floor ((p.y - global_min.y ()) / cell_size_)); int ecol = static_cast (std::floor ((p.x - global_min.x ()) / cell_size_)); From c6fb0d7c487b520876e224d6d032d41f54eac19d Mon Sep 17 00:00:00 2001 From: Patrick Scheckenbach <124401292+ptrckschcknbch@users.noreply.github.com> Date: Thu, 13 Jul 2023 10:14:51 +0200 Subject: [PATCH 099/288] Eigen: switch to imported modules and NO_MODULE (#5613) * Eigen: switch to imported modules and NO_MODULE Use Eigens native cmake support to replace the custom FindEigen.cmake * Use target Eigen3::Eigen * Remove usage of Eigen3_INCLUDE_DIR * Print Eigens target properties * Temp: Hard code property list * Link Eigen to cuda_io * Revert "Temp: Hard code property list" This reverts commit 10ded79012f6a8c44c7f97ac13b04faabdb9ecbe. * Revert "Print Eigens target properties" This reverts commit 93a7b93e37fcd2ee920eb6af47ed4c2e6ac647d1. * Link common to cuda_io * Link common to cuda_features * Link common to cuda_segmentation * Link common to gpu_containers * Fix target name in PCLConfig.cmake.in * Make all in one installer independent of Eigen3 internals * Fix cmake errors * Append existing target_link_libraries --- CMakeLists.txt | 5 +-- PCLConfig.cmake.in | 13 +++---- cmake/Modules/FindEigen.cmake | 41 ------------------- cmake/pcl_all_in_one_installer.cmake | 54 +++++++++++++++++++++++++- common/CMakeLists.txt | 4 +- cuda/features/CMakeLists.txt | 1 + cuda/io/CMakeLists.txt | 1 + cuda/segmentation/CMakeLists.txt | 1 + doc/tutorials/content/building_pcl.rst | 12 +++--- gpu/containers/CMakeLists.txt | 1 + io/CMakeLists.txt | 2 +- 11 files changed, 71 insertions(+), 64 deletions(-) delete mode 100644 cmake/Modules/FindEigen.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 8aef351b5af..f1795cb72a9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -318,9 +318,8 @@ endif() # Threads (required) find_package(Threads REQUIRED) -# Eigen (required) -find_package(Eigen 3.3 REQUIRED) -include_directories(SYSTEM ${EIGEN_INCLUDE_DIRS}) +# Eigen3 (required) +find_package(Eigen3 3.3 REQUIRED NO_MODULE) # FLANN (required) find_package(FLANN 1.9.1 REQUIRED) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 746e191d67f..1a628a250c2 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -112,14 +112,11 @@ macro(find_boost) endif() endmacro() -#remove this as soon as eigen is shipped with FindEigen.cmake -macro(find_eigen) +macro(find_eigen3) if(PCL_ALL_IN_ONE_INSTALLER) - set(EIGEN_ROOT "${PCL_ROOT}/3rdParty/Eigen") - elseif(NOT EIGEN_ROOT) - get_filename_component(EIGEN_ROOT "@EIGEN_INCLUDE_DIRS@" ABSOLUTE) + set(Eigen3_DIR "${PCL_ROOT}/3rdParty/Eigen3/share/eigen3/cmake/") endif() - find_package(Eigen 3.3) + find_package(Eigen3 3.3 REQUIRED NO_MODULE) endmacro() #remove this as soon as qhull is shipped with FindQhull.cmake @@ -271,8 +268,8 @@ endmacro() function(find_external_library _component _lib _is_optional) if("${_lib}" STREQUAL "boost") find_boost() - elseif("${_lib}" STREQUAL "eigen") - find_eigen() + elseif("${_lib}" STREQUAL "eigen3") + find_eigen3() elseif("${_lib}" STREQUAL "flann") find_flann() elseif("${_lib}" STREQUAL "qhull") diff --git a/cmake/Modules/FindEigen.cmake b/cmake/Modules/FindEigen.cmake deleted file mode 100644 index e1fb6abe2f0..00000000000 --- a/cmake/Modules/FindEigen.cmake +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################### -# Find Eigen3 -# -# This sets the following variables: -# EIGEN_FOUND - True if Eigen was found. -# EIGEN_INCLUDE_DIRS - Directories containing the Eigen include files. -# EIGEN_DEFINITIONS - Compiler flags for Eigen. -# EIGEN_VERSION - Package version - -find_package(PkgConfig QUIET) -pkg_check_modules(PC_EIGEN eigen3) -set(EIGEN_DEFINITIONS ${PC_EIGEN_CFLAGS_OTHER}) - -find_path(EIGEN_INCLUDE_DIR Eigen/Core - HINTS "${EIGEN_ROOT}" "$ENV{EIGEN_ROOT}" ${PC_EIGEN_INCLUDEDIR} ${PC_EIGEN_INCLUDE_DIRS} - PATHS "$ENV{PROGRAMFILES}/Eigen" "$ENV{PROGRAMW6432}/Eigen" - "$ENV{PROGRAMFILES}/Eigen3" "$ENV{PROGRAMW6432}/Eigen3" - PATH_SUFFIXES eigen3 include/eigen3 include) - -if(EIGEN_INCLUDE_DIR) - file(READ "${EIGEN_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen_version_header) - - string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen_world_version_match "${_eigen_version_header}") - set(EIGEN_WORLD_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen_major_version_match "${_eigen_version_header}") - set(EIGEN_MAJOR_VERSION "${CMAKE_MATCH_1}") - string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen_minor_version_match "${_eigen_version_header}") - set(EIGEN_MINOR_VERSION "${CMAKE_MATCH_1}") - set(EIGEN_VERSION ${EIGEN_WORLD_VERSION}.${EIGEN_MAJOR_VERSION}.${EIGEN_MINOR_VERSION}) -endif() - -set(EIGEN_INCLUDE_DIRS ${EIGEN_INCLUDE_DIR}) - -include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Eigen DEFAULT_MSG EIGEN_INCLUDE_DIR) - -mark_as_advanced(EIGEN_INCLUDE_DIR) - -if(EIGEN_FOUND) - message(STATUS "Eigen found (include: ${EIGEN_INCLUDE_DIRS}, version: ${EIGEN_VERSION})") -endif() diff --git a/cmake/pcl_all_in_one_installer.cmake b/cmake/pcl_all_in_one_installer.cmake index 52309dc412b..22cf0948686 100644 --- a/cmake/pcl_all_in_one_installer.cmake +++ b/cmake/pcl_all_in_one_installer.cmake @@ -10,7 +10,6 @@ endif() # get root directory of each dependency libraries to be copied to PCL/3rdParty get_filename_component(BOOST_ROOT "${Boost_INCLUDE_DIR}" PATH) # ../Boost/include/boost-x_x/ -> ../Boost/include/ get_filename_component(BOOST_ROOT "${BOOST_ROOT}" PATH) # ../Boost/include/ -> ../Boost/ -get_filename_component(EIGEN_ROOT "${EIGEN_INCLUDE_DIRS}" PATH) # ../Eigen3/include/ -> ../Eigen3/ get_filename_component(QHULL_ROOT "${Qhull_DIR}" PATH) # ../qhull/lib/cmake/Qhull/ -> ../qhull/lib/cmake get_filename_component(QHULL_ROOT "${QHULL_ROOT}" PATH) # ../qhull/lib/cmake/ -> ../qhull/lib/ get_filename_component(QHULL_ROOT "${QHULL_ROOT}" PATH) # ../qhull/lib/ -> ../qhull/ @@ -19,7 +18,7 @@ get_filename_component(VTK_ROOT "${VTK_ROOT}" PATH) # ../VTK/lib/cma get_filename_component(VTK_ROOT "${VTK_ROOT}" PATH) # ../VTK/lib/ -> ../VTK/ set(PCL_3RDPARTY_COMPONENTS) -foreach(dep Eigen Boost Qhull FLANN VTK) +foreach(dep Boost Qhull FLANN VTK) string(TOUPPER ${dep} DEP) install( DIRECTORY "${${DEP}_ROOT}/" @@ -30,6 +29,57 @@ foreach(dep Eigen Boost Qhull FLANN VTK) list(APPEND PCL_3RDPARTY_COMPONENTS ${dep}) endforeach() +# Try to set EIGEN3_INCLUDE_DIR in case it is +# no longer exported by Eigen3 itself. +if (NOT EXISTS ${EIGEN3_INCLUDE_DIR}) + if (EXISTS ${EIGEN3_INCLUDE_DIRS}) + set(EIGEN3_INCLUDE_DIR ${EIGEN3_INCLUDE_DIRS}) + else() + set(EIGEN3_INCLUDE_DIR "${Eigen3_DIR}/../../../include/eigen3/") + endif() +endif() +if(NOT EXISTS ${EIGEN3_INCLUDE_DIR}) + message(FATAL_ERROR "EIGEN3_INCLUDE_DIR is not existing: ${EIGEN3_INCLUDE_DIR}") +endif() + +# Try to find EIGEN3_COMMON_ROOT_PATH, which is meant to hold +# the first common root folder of Eigen3_DIR and EIGEN3_INCLUDE_DIR. +# E.g. Eigen3_DIR = /usr/local/share/eigen3/cmake/ +# EIGEN3_INCLUDE_DIR = /usr/local/include/eigen3/ +# => EIGEN3_COMMON_ROOT_PATH = /usr/local/ +file(TO_CMAKE_PATH ${Eigen3_DIR} Eigen3_DIR) +file(TO_CMAKE_PATH ${EIGEN3_INCLUDE_DIR} EIGEN3_INCLUDE_DIR) +set(EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_DIR}) +set(PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP "INVALID") +while (NOT ${PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP} STREQUAL ${EIGEN3_INCLUDE_PATH_LOOP}) + if (${Eigen3_DIR} MATCHES ${EIGEN3_INCLUDE_PATH_LOOP}) + set(EIGEN3_COMMON_ROOT_PATH ${EIGEN3_INCLUDE_PATH_LOOP}) + break() + endif() + set(PREVIOUS_EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_PATH_LOOP}) + get_filename_component(EIGEN3_INCLUDE_PATH_LOOP ${EIGEN3_INCLUDE_PATH_LOOP} DIRECTORY) +endwhile() +if(NOT EXISTS ${EIGEN3_COMMON_ROOT_PATH}) + message(FATAL_ERROR "Could not copy Eigen3.") +endif() + +# Install Eigen3 to 3rdParty directory +string(LENGTH ${EIGEN3_COMMON_ROOT_PATH} LENGTH_OF_EIGEN3_COMMON_ROOT_PATH) +string(SUBSTRING ${Eigen3_DIR} ${LENGTH_OF_EIGEN3_COMMON_ROOT_PATH} -1 DESTINATION_EIGEN3_DIR) +string(SUBSTRING ${EIGEN3_INCLUDE_DIR} ${LENGTH_OF_EIGEN3_COMMON_ROOT_PATH} -1 DESTINATION_EIGEN3_INCLUDE_DIR) +set(dep_Eigen3 Eigen3) +install( + DIRECTORY "${Eigen3_DIR}/" + DESTINATION 3rdParty/${dep_Eigen3}${DESTINATION_EIGEN3_DIR} + COMPONENT ${dep_Eigen3} +) +install( + DIRECTORY "${EIGEN3_INCLUDE_DIR}/" + DESTINATION 3rdParty/${dep_Eigen3}${DESTINATION_EIGEN3_INCLUDE_DIR} + COMPONENT ${dep_Eigen3} +) +list(APPEND PCL_3RDPARTY_COMPONENTS ${dep_Eigen3}) + if(WITH_RSSDK2) get_filename_component(RSSDK2_ROOT "${RSSDK2_INCLUDE_DIRS}" PATH) install( diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index 12d69ed5ccf..fe0ad8fa3ea 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -4,7 +4,7 @@ set(SUBSYS_DEPS) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS eigen boost) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS eigen3 boost) PCL_ADD_DOC("${SUBSYS_NAME}") @@ -179,7 +179,7 @@ target_include_directories(${LIB_NAME} PUBLIC $ ) -target_link_libraries(${LIB_NAME} Boost::boost) +target_link_libraries(${LIB_NAME} Boost::boost Eigen3::Eigen) if(MSVC AND NOT (MSVC_VERSION LESS 1915)) # MSVC resolved a byte alignment issue in compiler version 15.9 diff --git a/cuda/features/CMakeLists.txt b/cuda/features/CMakeLists.txt index 0932378c62d..7d271029708 100644 --- a/cuda/features/CMakeLists.txt +++ b/cuda/features/CMakeLists.txt @@ -26,6 +26,7 @@ set(incs set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) +target_link_libraries(${LIB_NAME} pcl_common) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/cuda/io/CMakeLists.txt b/cuda/io/CMakeLists.txt index 8361560bbf3..fcf78689437 100644 --- a/cuda/io/CMakeLists.txt +++ b/cuda/io/CMakeLists.txt @@ -37,6 +37,7 @@ set(incs set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) +target_link_libraries(${LIB_NAME} pcl_common) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS}) diff --git a/cuda/segmentation/CMakeLists.txt b/cuda/segmentation/CMakeLists.txt index b96cf182e5c..38a17aa490f 100644 --- a/cuda/segmentation/CMakeLists.txt +++ b/cuda/segmentation/CMakeLists.txt @@ -27,6 +27,7 @@ set(srcs set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) +target_link_libraries(${LIB_NAME} pcl_common) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/doc/tutorials/content/building_pcl.rst b/doc/tutorials/content/building_pcl.rst index 187b4b0760c..d0b07ce1ffd 100644 --- a/doc/tutorials/content/building_pcl.rst +++ b/doc/tutorials/content/building_pcl.rst @@ -176,7 +176,6 @@ The available ROOTs you can set are as follow: * **CMINPACK_ROOT**: for cminpack with value `C:/Program Files/CMINPACK 1.1.13` for instance * **QHULL_ROOT**: for qhull with value `C:/Program Files/qhull 6.2.0.1373` for instance * **FLANN_ROOT**: for flann with value `C:/Program Files/flann 1.6.8` for instance -* **EIGEN_ROOT**: for eigen with value `C:/Program Files/Eigen 3.0.0` for instance To ensure that all the dependencies were correctly found, beside the message you get from CMake, you can check or edit each dependency specific @@ -253,9 +252,8 @@ then a sample value is given for reference. * Eigen -+------------------+---------------------------------+---------------------------+ -| cache variable | meaning | sample value | -+==================+=================================+===========================+ -| EIGEN_INCLUDE_DIR| path to eigen headers directory | /usr/local/include/eigen3 | -+------------------+---------------------------------+---------------------------+ - ++--------------------+---------------------------------+-------------------------------+ +| cache variable | meaning | sample value | ++====================+=================================+===============================+ +| Eigen3_DIR | path to eigen cmake directory | /usr/local/share/eigen3/cmake | ++--------------------+---------------------------------+-------------------------------+ diff --git a/gpu/containers/CMakeLists.txt b/gpu/containers/CMakeLists.txt index 74384d5b579..f25120bafc0 100644 --- a/gpu/containers/CMakeLists.txt +++ b/gpu/containers/CMakeLists.txt @@ -25,6 +25,7 @@ get_filename_component(UTILS_INC "${CMAKE_CURRENT_SOURCE_DIR}/../utils/include" set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" ${UTILS_INC}) PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) +target_link_libraries(${LIB_NAME} pcl_common) #Ensures that CUDA is added and the project can compile as it uses cuda calls. set_source_files_properties(src/device_memory.cpp PROPERTIES LANGUAGE CUDA) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index e5fc2095192..7fc86b26e64 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME io) set(SUBSYS_DESC "Point cloud IO library") set(SUBSYS_DEPS common octree) -set(SUBSYS_EXT_DEPS boost eigen) +set(SUBSYS_EXT_DEPS boost eigen3) set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) From b268d07d9fa8faa8e46a0994a47d330e0d953da5 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Thu, 13 Jul 2023 07:19:04 -0700 Subject: [PATCH 100/288] Part D of transition to support modernize-use-default-member-init (#5738) * Part D of trannsition to support modernize-use-default-member-init * Made changes from inspection --- features/include/pcl/features/narf.h | 4 +- features/src/narf.cpp | 5 +- io/include/pcl/compression/color_coding.h | 9 ++-- .../octree_pointcloud_compression.h | 38 +++++++------- io/include/pcl/compression/point_coding.h | 10 ++-- io/include/pcl/io/dinast_grabber.h | 26 +++++----- io/include/pcl/io/impl/synchronized_queue.hpp | 6 +-- io/include/pcl/io/lzf_image_io.h | 16 +++--- io/include/pcl/io/oni_grabber.h | 34 ++++++------- .../openni_shift_to_depth_conversion.h | 4 +- .../pcl/io/openni_camera/openni_device.h | 4 +- .../io/openni_camera/openni_device_kinect.h | 2 +- .../pcl/io/openni_camera/openni_device_oni.h | 6 +-- .../openni_shift_to_depth_conversion.h | 4 +- io/include/pcl/io/openni_grabber.h | 50 +++++++++---------- io/include/pcl/io/pcd_io.h | 4 +- io/include/pcl/io/ply/ply_parser.h | 8 ++- io/include/pcl/io/ply_io.h | 27 ++++------ .../pcl/io/point_cloud_image_extractors.h | 8 ++- io/src/dinast_grabber.cpp | 11 ---- io/src/lzf_image_io.cpp | 4 +- io/src/oni_grabber.cpp | 11 ---- io/src/openni_camera/openni_device_kinect.cpp | 1 - io/src/openni_camera/openni_device_oni.cpp | 3 -- io/src/openni_grabber.cpp | 18 +------ .../include/pcl/kdtree/impl/kdtree_flann.hpp | 5 +- 26 files changed, 123 insertions(+), 195 deletions(-) diff --git a/features/include/pcl/features/narf.h b/features/include/pcl/features/narf.h index 83015b970d0..9a18d222d10 100644 --- a/features/include/pcl/features/narf.h +++ b/features/include/pcl/features/narf.h @@ -279,8 +279,8 @@ namespace pcl Eigen::Affine3f transformation_; float* surface_patch_{nullptr}; int surface_patch_pixel_size_{0}; - float surface_patch_world_size_{}; - float surface_patch_rotation_{}; + float surface_patch_world_size_{0.0f}; + float surface_patch_rotation_{0.0f}; float* descriptor_{nullptr}; int descriptor_size_{0}; diff --git a/features/src/narf.cpp b/features/src/narf.cpp index 54ab40463d8..b391e3fcff5 100644 --- a/features/src/narf.cpp +++ b/features/src/narf.cpp @@ -67,10 +67,7 @@ Narf::~Narf() } ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// -Narf::Narf (const Narf& other) : - surface_patch_ (nullptr), - surface_patch_pixel_size_ (0), surface_patch_world_size_ (), - surface_patch_rotation_ (), descriptor_ (nullptr), descriptor_size_ (0) +Narf::Narf (const Narf& other) { deepCopy (other); } diff --git a/io/include/pcl/compression/color_coding.h b/io/include/pcl/compression/color_coding.h index 67cd089b58f..8b26fad35ec 100644 --- a/io/include/pcl/compression/color_coding.h +++ b/io/include/pcl/compression/color_coding.h @@ -64,10 +64,7 @@ class ColorCoding /** \brief Constructor. * * */ - ColorCoding () : - output_ (), colorBitReduction_ (0) - { - } + ColorCoding () = default; /** \brief Empty class constructor. */ virtual @@ -353,7 +350,7 @@ class ColorCoding protected: /** \brief Pointer to output point cloud dataset. */ - PointCloudPtr output_; + PointCloudPtr output_{nullptr}; /** \brief Vector for storing average color information */ std::vector pointAvgColorDataVector_; @@ -368,7 +365,7 @@ class ColorCoding std::vector::const_iterator pointDiffColorDataVector_Iterator_; /** \brief Amount of bits to be removed from color components before encoding */ - unsigned char colorBitReduction_; + unsigned char colorBitReduction_{0}; // frame header identifier static const int defaultColor_; diff --git a/io/include/pcl/compression/octree_pointcloud_compression.h b/io/include/pcl/compression/octree_pointcloud_compression.h index 40c85c9e577..d2eae276364 100644 --- a/io/include/pcl/compression/octree_pointcloud_compression.h +++ b/io/include/pcl/compression/octree_pointcloud_compression.h @@ -106,13 +106,11 @@ namespace pcl color_coder_ (), point_coder_ (), do_voxel_grid_enDecoding_ (doVoxelGridDownDownSampling_arg), i_frame_rate_ (iFrameRate_arg), - i_frame_counter_ (0), frame_ID_ (0), point_count_ (0), i_frame_ (true), - do_color_encoding_ (doColorEncoding_arg), cloud_with_color_ (false), data_with_color_ (false), - point_color_offset_ (0), b_show_statistics_ (showStatistics_arg), - compressed_point_data_len_ (), compressed_color_data_len_ (), selected_profile_(compressionProfile_arg), + + do_color_encoding_ (doColorEncoding_arg), b_show_statistics_ (showStatistics_arg), + selected_profile_(compressionProfile_arg), point_resolution_(pointResolution_arg), octree_resolution_(octreeResolution_arg), - color_bit_resolution_(colorBitResolution_arg), - object_count_(0) + color_bit_resolution_(colorBitResolution_arg) { initialization(); } @@ -266,22 +264,22 @@ namespace pcl /** \brief Static range coder instance */ StaticRangeCoder entropy_coder_; - bool do_voxel_grid_enDecoding_; - std::uint32_t i_frame_rate_; - std::uint32_t i_frame_counter_; - std::uint32_t frame_ID_; - std::uint64_t point_count_; - bool i_frame_; + bool do_voxel_grid_enDecoding_{false}; + std::uint32_t i_frame_rate_{0}; + std::uint32_t i_frame_counter_{0}; + std::uint32_t frame_ID_{0}; + std::uint64_t point_count_{0}; + bool i_frame_{true}; - bool do_color_encoding_; - bool cloud_with_color_; - bool data_with_color_; - unsigned char point_color_offset_; + bool do_color_encoding_{false}; + bool cloud_with_color_{false}; + bool data_with_color_{false}; + unsigned char point_color_offset_{0}; //bool activating statistics - bool b_show_statistics_; - std::uint64_t compressed_point_data_len_; - std::uint64_t compressed_color_data_len_; + bool b_show_statistics_{false}; + std::uint64_t compressed_point_data_len_{0}; + std::uint64_t compressed_color_data_len_{0}; // frame header identifier static const char* frame_header_identifier_; @@ -291,7 +289,7 @@ namespace pcl const double octree_resolution_; const unsigned char color_bit_resolution_; - std::size_t object_count_; + std::size_t object_count_{0}; }; diff --git a/io/include/pcl/compression/point_coding.h b/io/include/pcl/compression/point_coding.h index 168d2f31f70..b365c18900c 100644 --- a/io/include/pcl/compression/point_coding.h +++ b/io/include/pcl/compression/point_coding.h @@ -60,11 +60,7 @@ class PointCoding public: /** \brief Constructor. */ - PointCoding () : - output_ (), - pointCompressionResolution_ (0.001f) // 1mm - { - } + PointCoding () = default; /** \brief Empty class constructor. */ virtual @@ -181,7 +177,7 @@ class PointCoding protected: /** \brief Pointer to output point cloud dataset. */ - PointCloudPtr output_; + PointCloudPtr output_{nullptr}; /** \brief Vector for storing differential point information */ std::vector pointDiffDataVector_; @@ -190,7 +186,7 @@ class PointCoding std::vector::const_iterator pointDiffDataVectorIterator_; /** \brief Precision of point coding*/ - float pointCompressionResolution_; + float pointCompressionResolution_{0.001f}; }; } // namespace octree diff --git a/io/include/pcl/io/dinast_grabber.h b/io/include/pcl/io/dinast_grabber.h index 766f8ecc39f..2bec889910a 100644 --- a/io/include/pcl/io/dinast_grabber.h +++ b/io/include/pcl/io/dinast_grabber.h @@ -163,51 +163,51 @@ namespace pcl captureThreadFunction (); /** \brief Width of image */ - int image_width_; + int image_width_{320}; /** \brief Height of image */ - int image_height_; + int image_height_{240}; /** \brief Total size of image */ - int image_size_; + int image_size_{image_width_ * image_height_}; /** \brief Length of a sync packet */ - int sync_packet_size_; + int sync_packet_size_{512}; - double dist_max_2d_; + double dist_max_2d_{1. / (image_width_ / 2.)}; /** \brief diagonal Field of View*/ - double fov_; + double fov_{64. * M_PI / 180.}; /** \brief Size of pixel */ enum pixel_size { RAW8=1, RGB16=2, RGB24=3, RGB32=4 }; /** \brief The libusb context*/ - libusb_context *context_; + libusb_context *context_{nullptr}; /** \brief the actual device_handle for the camera */ - struct libusb_device_handle *device_handle_; + struct libusb_device_handle *device_handle_{nullptr}; /** \brief Temporary USB read buffer, since we read two RGB16 images at a time size is the double of two images * plus a sync packet. */ - unsigned char *raw_buffer_ ; + unsigned char *raw_buffer_{nullptr} ; /** \brief Global circular buffer */ boost::circular_buffer g_buffer_; /** \brief Bulk endpoint address value */ - unsigned char bulk_ep_; + unsigned char bulk_ep_{std::numeric_limits::max ()}; /** \brief Device command values */ enum { CMD_READ_START=0xC7, CMD_READ_STOP=0xC8, CMD_GET_VERSION=0xDC, CMD_SEND_DATA=0xDE }; - unsigned char *image_; + unsigned char *image_{nullptr}; /** \brief Since there is no header after the first image, we need to save the state */ - bool second_image_; + bool second_image_{false}; - bool running_; + bool running_{false}; std::thread capture_thread_; diff --git a/io/include/pcl/io/impl/synchronized_queue.hpp b/io/include/pcl/io/impl/synchronized_queue.hpp index fe9aaf8104c..1e6ca9cb74d 100644 --- a/io/include/pcl/io/impl/synchronized_queue.hpp +++ b/io/include/pcl/io/impl/synchronized_queue.hpp @@ -53,7 +53,7 @@ namespace pcl public: SynchronizedQueue () : - queue_(), request_to_end_(false), enqueue_data_(true) { } + queue_() { } void enqueue (const T& data) @@ -127,7 +127,7 @@ namespace pcl mutable std::mutex mutex_; // The mutex to synchronise on std::condition_variable cond_; // The condition to wait for - bool request_to_end_; - bool enqueue_data_; + bool request_to_end_{false}; + bool enqueue_data_{true}; }; } diff --git a/io/include/pcl/io/lzf_image_io.h b/io/include/pcl/io/lzf_image_io.h index 77bd0fafd4b..416cbb426fb 100644 --- a/io/include/pcl/io/lzf_image_io.h +++ b/io/include/pcl/io/lzf_image_io.h @@ -161,10 +161,10 @@ namespace pcl std::vector &output); /** \brief The image width, as read from the file. */ - std::uint32_t width_; + std::uint32_t width_{0}; /** \brief The image height, as read from the file. */ - std::uint32_t height_; + std::uint32_t height_{0}; /** \brief The image type string, as read from the file. */ std::string image_type_identifier_; @@ -189,9 +189,7 @@ namespace pcl using LZFImageReader::readParameters; /** Empty constructor */ - LZFDepth16ImageReader () - : z_multiplication_factor_ (0.001) // Set default multiplication factor - {} + LZFDepth16ImageReader () = default; /** Empty destructor */ ~LZFDepth16ImageReader () override = default; @@ -223,7 +221,7 @@ namespace pcl /** \brief Z-value depth multiplication factor * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001) */ - double z_multiplication_factor_; + double z_multiplication_factor_{0.001}; }; /** \brief PCL-LZF 24-bit RGB image format reader. @@ -480,9 +478,7 @@ namespace pcl { public: /** Empty constructor */ - LZFDepth16ImageWriter () - : z_multiplication_factor_ (0.001) // Set default multiplication factor - {} + LZFDepth16ImageWriter () = default; /** Empty destructor */ ~LZFDepth16ImageWriter () override = default; @@ -519,7 +515,7 @@ namespace pcl /** \brief Z-value depth multiplication factor * (i.e., if raw data is in [mm] and we want [m], we need to multiply with 0.001) */ - double z_multiplication_factor_; + double z_multiplication_factor_{0.001}; }; /** \brief PCL-LZF 24-bit RGB image format writer. diff --git a/io/include/pcl/io/oni_grabber.h b/io/include/pcl/io/oni_grabber.h index 2da7895caad..389db10a099 100644 --- a/io/include/pcl/io/oni_grabber.h +++ b/io/include/pcl/io/oni_grabber.h @@ -175,23 +175,23 @@ namespace pcl openni_wrapper::DeviceONI::Ptr device_; std::string rgb_frame_id_; std::string depth_frame_id_; - bool running_; - unsigned image_width_; - unsigned image_height_; - unsigned depth_width_; - unsigned depth_height_; - openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle; - openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle; - openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle; - boost::signals2::signal* image_signal_; - boost::signals2::signal* depth_image_signal_; - boost::signals2::signal* ir_image_signal_; - boost::signals2::signal* image_depth_image_signal_; - boost::signals2::signal* ir_depth_image_signal_; - boost::signals2::signal* point_cloud_signal_; - boost::signals2::signal* point_cloud_i_signal_; - boost::signals2::signal* point_cloud_rgb_signal_; - boost::signals2::signal* point_cloud_rgba_signal_; + bool running_{false}; + unsigned image_width_{0}; + unsigned image_height_{0}; + unsigned depth_width_{0}; + unsigned depth_height_{0}; + openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle{}; + openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle{}; + openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle{}; + boost::signals2::signal* image_signal_{}; + boost::signals2::signal* depth_image_signal_{}; + boost::signals2::signal* ir_image_signal_{}; + boost::signals2::signal* image_depth_image_signal_{}; + boost::signals2::signal* ir_depth_image_signal_{}; + boost::signals2::signal* point_cloud_signal_{}; + boost::signals2::signal* point_cloud_i_signal_{}; + boost::signals2::signal* point_cloud_rgb_signal_{}; + boost::signals2::signal* point_cloud_rgba_signal_{}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h b/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h index 4c110a8ffc0..c4f7efbe7d2 100644 --- a/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h +++ b/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h @@ -52,7 +52,7 @@ namespace openni_wrapper { public: /** \brief Constructor. */ - ShiftToDepthConverter () : init_(false) {} + ShiftToDepthConverter () = default; /** \brief This method generates a look-up table to convert openni shift values to depth */ @@ -109,7 +109,7 @@ namespace openni_wrapper protected: std::vector lookupTable_; - bool init_; + bool init_{false}; } ; } #endif diff --git a/io/include/pcl/io/openni_camera/openni_device.h b/io/include/pcl/io/openni_camera/openni_device.h index 4c80eef91e6..ddda24b0cdc 100644 --- a/io/include/pcl/io/openni_camera/openni_device.h +++ b/io/include/pcl/io/openni_camera/openni_device.h @@ -485,7 +485,7 @@ namespace openni_wrapper struct ShiftConversion { - ShiftConversion() : init_(false) {} + ShiftConversion() = default; XnUInt16 zero_plane_distance_; XnFloat zero_plane_pixel_size_; @@ -498,7 +498,7 @@ namespace openni_wrapper XnUInt32 shift_scale_; XnUInt32 min_depth_; XnUInt32 max_depth_; - bool init_; + bool init_{false}; } shift_conversion_parameters_; diff --git a/io/include/pcl/io/openni_camera/openni_device_kinect.h b/io/include/pcl/io/openni_camera/openni_device_kinect.h index 9d7f2d37202..36d476e213d 100644 --- a/io/include/pcl/io/openni_camera/openni_device_kinect.h +++ b/io/include/pcl/io/openni_camera/openni_device_kinect.h @@ -69,7 +69,7 @@ namespace openni_wrapper Image::Ptr getCurrentImage (pcl::shared_ptr image_meta_data) const noexcept override; void enumAvailableModes () noexcept; bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const noexcept override; - ImageBayerGRBG::DebayeringMethod debayering_method_; + ImageBayerGRBG::DebayeringMethod debayering_method_{ImageBayerGRBG::EdgeAwareWeighted}; } ; void diff --git a/io/include/pcl/io/openni_camera/openni_device_oni.h b/io/include/pcl/io/openni_camera/openni_device_oni.h index f4cc8ff9f1e..9f09c39d674 100644 --- a/io/include/pcl/io/openni_camera/openni_device_oni.h +++ b/io/include/pcl/io/openni_camera/openni_device_oni.h @@ -111,9 +111,9 @@ namespace openni_wrapper mutable std::mutex player_mutex_; std::condition_variable player_condition_; bool streaming_; - bool depth_stream_running_; - bool image_stream_running_; - bool ir_stream_running_; + bool depth_stream_running_{false}; + bool image_stream_running_{false}; + bool ir_stream_running_{false}; }; } //namespace openni_wrapper #endif //HAVE_OPENNI diff --git a/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h b/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h index af911a947e7..e69ff33bdc3 100644 --- a/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h +++ b/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h @@ -53,7 +53,7 @@ namespace openni_wrapper { public: /** \brief Constructor. */ - ShiftToDepthConverter () : init_(false) {} + ShiftToDepthConverter () = default; /** \brief Destructor. */ virtual ~ShiftToDepthConverter () = default; @@ -113,7 +113,7 @@ namespace openni_wrapper protected: std::vector lookupTable_; - bool init_; + bool init_{false}; } ; } diff --git a/io/include/pcl/io/openni_grabber.h b/io/include/pcl/io/openni_grabber.h index d97ca6623c5..abcb95ee7ee 100644 --- a/io/include/pcl/io/openni_grabber.h +++ b/io/include/pcl/io/openni_grabber.h @@ -422,25 +422,25 @@ namespace pcl std::string rgb_frame_id_; std::string depth_frame_id_; - unsigned image_width_; - unsigned image_height_; - unsigned depth_width_; - unsigned depth_height_; - - bool image_required_; - bool depth_required_; - bool ir_required_; - bool sync_required_; - - boost::signals2::signal* image_signal_; - boost::signals2::signal* depth_image_signal_; - boost::signals2::signal* ir_image_signal_; - boost::signals2::signal* image_depth_image_signal_; - boost::signals2::signal* ir_depth_image_signal_; - boost::signals2::signal* point_cloud_signal_; - boost::signals2::signal* point_cloud_i_signal_; - boost::signals2::signal* point_cloud_rgb_signal_; - boost::signals2::signal* point_cloud_rgba_signal_; + unsigned image_width_{0}; + unsigned image_height_{0}; + unsigned depth_width_{0}; + unsigned depth_height_{0}; + + bool image_required_{false}; + bool depth_required_{false}; + bool ir_required_{false}; + bool sync_required_{false}; + + boost::signals2::signal* image_signal_{}; + boost::signals2::signal* depth_image_signal_{}; + boost::signals2::signal* ir_image_signal_{}; + boost::signals2::signal* image_depth_image_signal_{}; + boost::signals2::signal* ir_depth_image_signal_{}; + boost::signals2::signal* point_cloud_signal_{}; + boost::signals2::signal* point_cloud_i_signal_{}; + boost::signals2::signal* point_cloud_rgb_signal_{}; + boost::signals2::signal* point_cloud_rgba_signal_{}; struct modeComp { @@ -460,13 +460,13 @@ namespace pcl } ; std::map config2xn_map_; - openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle; - openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle; - openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle; - bool running_; + openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle{}; + openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle{}; + openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle{}; + bool running_{false}; - mutable unsigned rgb_array_size_; - mutable unsigned depth_buffer_size_; + mutable unsigned rgb_array_size_{0}; + mutable unsigned depth_buffer_size_{0}; mutable boost::shared_array rgb_array_; mutable boost::shared_array depth_buffer_; mutable boost::shared_array ir_buffer_; diff --git a/io/include/pcl/io/pcd_io.h b/io/include/pcl/io/pcd_io.h index 0131b5bf9d4..bc95c57f38d 100644 --- a/io/include/pcl/io/pcd_io.h +++ b/io/include/pcl/io/pcd_io.h @@ -298,7 +298,7 @@ namespace pcl class PCL_EXPORTS PCDWriter : public FileWriter { public: - PCDWriter() : map_synchronization_(false) {} + PCDWriter() = default; ~PCDWriter() override = default; /** \brief Set whether mmap() synchornization via msync() is desired before munmap() calls. @@ -615,7 +615,7 @@ namespace pcl private: /** \brief Set to true if msync() should be called before munmap(). Prevents data loss on NFS systems. */ - bool map_synchronization_; + bool map_synchronization_{false}; }; namespace io diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h index a64eaf219de..2e0390072af 100644 --- a/io/include/pcl/io/ply/ply_parser.h +++ b/io/include/pcl/io/ply/ply_parser.h @@ -293,9 +293,7 @@ namespace pcl using flags_type = int; enum flags { }; - ply_parser () : - line_number_ (0), current_element_ () - {} + ply_parser () = default; bool parse (const std::string& filename); //inline bool parse (const std::string& filename); @@ -414,8 +412,8 @@ namespace pcl const typename list_property_element_callback_type::type& list_property_element_callback, const typename list_property_end_callback_type::type& list_property_end_callback); - std::size_t line_number_; - element* current_element_; + std::size_t line_number_{0}; + element* current_element_{nullptr}; }; } // namespace ply } // namespace io diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 6df337227a4..3c6fbc4271d 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -89,15 +89,6 @@ namespace pcl PLYReader () : origin_ (Eigen::Vector4f::Zero ()) , orientation_ (Eigen::Matrix3f::Zero ()) - , cloud_ () - , vertex_count_ (0) - , vertex_offset_before_ (0) - , range_grid_ (nullptr) - , rgb_offset_before_ (0) - , do_resize_ (false) - , polygons_ (nullptr) - , r_(0), g_(0), b_(0) - , a_(0), rgba_(0) {} PLYReader (const PLYReader &p) @@ -524,23 +515,23 @@ namespace pcl Eigen::Matrix3f orientation_; //vertex element artifacts - pcl::PCLPointCloud2 *cloud_; - std::size_t vertex_count_; - int vertex_offset_before_; + pcl::PCLPointCloud2 *cloud_{nullptr}; + std::size_t vertex_count_{0}; + int vertex_offset_before_{0}; //range element artifacts - std::vector > *range_grid_; - std::size_t rgb_offset_before_; - bool do_resize_; + std::vector > *range_grid_{nullptr}; + std::size_t rgb_offset_before_{0}; + bool do_resize_{false}; //face element artifact - std::vector *polygons_; + std::vector *polygons_{nullptr}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW private: // RGB values stored by vertexColorCallback() - std::int32_t r_, g_, b_; + std::int32_t r_{0}, g_{0}, b_{0}; // Color values stored by vertexAlphaCallback() - std::uint32_t a_, rgba_; + std::uint32_t a_{0}, rgba_{0}; }; /** \brief Point Cloud Data (PLY) file format writer. diff --git a/io/include/pcl/io/point_cloud_image_extractors.h b/io/include/pcl/io/point_cloud_image_extractors.h index 5c8993a0820..d7f47646df8 100644 --- a/io/include/pcl/io/point_cloud_image_extractors.h +++ b/io/include/pcl/io/point_cloud_image_extractors.h @@ -84,9 +84,7 @@ namespace pcl using ConstPtr = shared_ptr >; /** \brief Constructor. */ - PointCloudImageExtractor () - : paint_nans_with_black_ (false) - {} + PointCloudImageExtractor () = default; /** \brief Destructor. */ virtual ~PointCloudImageExtractor () = default; @@ -118,7 +116,7 @@ namespace pcl /// A flag that controls if image pixels corresponding to NaN (infinite) /// points should be painted black. - bool paint_nans_with_black_; + bool paint_nans_with_black_{false}; }; ////////////////////////////////////////////////////////////////////////////////////// @@ -303,7 +301,7 @@ namespace pcl private: - ColorMode color_mode_; + ColorMode color_mode_{COLORS_MONO}; }; ////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/dinast_grabber.cpp b/io/src/dinast_grabber.cpp index 8071257f3bf..1cd33ba2bea 100644 --- a/io/src/dinast_grabber.cpp +++ b/io/src/dinast_grabber.cpp @@ -42,18 +42,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// pcl::DinastGrabber::DinastGrabber (const int device_position) - : image_width_ (320) - , image_height_ (240) - , sync_packet_size_ (512) - , fov_ (64. * M_PI / 180.) - , context_ (nullptr) - , device_handle_ (nullptr) - , bulk_ep_ (std::numeric_limits::max ()) - , second_image_ (false) - , running_ (false) { - image_size_ = image_width_ * image_height_; - dist_max_2d_ = 1. / (image_width_ / 2.); onInit(device_position); point_cloud_signal_ = createSignal (); diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index b3b61c638a2..ab59a6eeb11 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -347,9 +347,7 @@ pcl::io::LZFBayer8ImageWriter::write (const char *data, ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// pcl::io::LZFImageReader::LZFImageReader () - : width_ () - , height_ () - , parameters_ () + : parameters_ () { } diff --git a/io/src/oni_grabber.cpp b/io/src/oni_grabber.cpp index 1d18540f847..3ba4c8b8560 100644 --- a/io/src/oni_grabber.cpp +++ b/io/src/oni_grabber.cpp @@ -71,17 +71,6 @@ namespace pcl ONIGrabber::ONIGrabber (const std::string& file_name, bool repeat, bool stream) : rgb_frame_id_ ("/openni_rgb_optical_frame") , depth_frame_id_ ("/openni_depth_optical_frame") - , running_ (false) - , image_width_ () - , image_height_ () - , depth_width_ () - , depth_height_ () - , depth_callback_handle () - , image_callback_handle () - , ir_callback_handle () - , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ () - , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ (), point_cloud_rgb_signal_ () - , point_cloud_rgba_signal_ () { openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance (); device_ = dynamic_pointer_cast< openni_wrapper::DeviceONI> (driver.createVirtualDevice (file_name, repeat, stream)); diff --git a/io/src/openni_camera/openni_device_kinect.cpp b/io/src/openni_camera/openni_device_kinect.cpp index 36e229d3d43..e8147d0d02f 100644 --- a/io/src/openni_camera/openni_device_kinect.cpp +++ b/io/src/openni_camera/openni_device_kinect.cpp @@ -61,7 +61,6 @@ openni_wrapper::DeviceKinect::isSynchronizationSupported () const noexcept ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// openni_wrapper::DeviceKinect::DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) : OpenNIDevice (context, device_node, image_node, depth_node, ir_node) -, debayering_method_ (ImageBayerGRBG::EdgeAwareWeighted) { // setup stream modes enumAvailableModes (); diff --git a/io/src/openni_camera/openni_device_oni.cpp b/io/src/openni_camera/openni_device_oni.cpp index 94e3bfdac59..2a42d31402a 100644 --- a/io/src/openni_camera/openni_device_oni.cpp +++ b/io/src/openni_camera/openni_device_oni.cpp @@ -54,9 +54,6 @@ openni_wrapper::DeviceONI::DeviceONI ( bool streaming) : OpenNIDevice (context) , streaming_ (streaming) - , depth_stream_running_ (false) - , image_stream_running_ (false) - , ir_stream_running_ (false) { XnStatus status; #if (XN_MINOR_VERSION >= 3) diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 81e9aecfe41..04d43c765d5 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -53,22 +53,8 @@ using namespace std::chrono_literals; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// pcl::OpenNIGrabber::OpenNIGrabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode) - : image_width_ () - , image_height_ () - , depth_width_ () - , depth_height_ () - , image_required_ (false) - , depth_required_ (false) - , ir_required_ (false) - , sync_required_ (false) - , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ () - , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ () - , point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ () - , depth_callback_handle (), image_callback_handle (), ir_callback_handle () - , running_ (false) - , rgb_array_size_ (0) - , depth_buffer_size_ (0) - , rgb_focal_length_x_ (std::numeric_limits::quiet_NaN ()) + : + rgb_focal_length_x_ (std::numeric_limits::quiet_NaN ()) , rgb_focal_length_y_ (std::numeric_limits::quiet_NaN ()) , rgb_principal_point_x_ (std::numeric_limits::quiet_NaN ()) , rgb_principal_point_y_ (std::numeric_limits::quiet_NaN ()) diff --git a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp index f92017189a6..7edaf7a80df 100644 --- a/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp +++ b/kdtree/include/pcl/kdtree/impl/kdtree_flann.hpp @@ -70,9 +70,8 @@ template pcl::KdTreeFLANN::KdTreeFLANN (const KdTreeFLANN &k) : pcl::KdTree (false) , flann_index_ () - , identity_mapping_ (false) - , dim_ (0), total_nr_points_ (0) - , param_k_ (::flann::SearchParams (-1 , epsilon_)) + , + param_k_ (::flann::SearchParams (-1 , epsilon_)) , param_radius_ (::flann::SearchParams (-1, epsilon_, false)) { *this = k; From 0bc2f2cc369f7d013ee5c29075188c4e26ea6f87 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 15 Jul 2023 15:49:25 +0200 Subject: [PATCH 101/288] MovingLeastSquares: reduce the number of instantiations to reduce compile time PCL_XYZ_POINT_TYPES currently contains 18 types, so previously, MLS was instantiated for 18*18=324 different type combinations. However, among those were instantiations which are likely used by nobody (like `pcl::MovingLeastSquares`). With these changes, MLS is only instantiated 6*6+(18-6)=48 times. The most common type combinations should be covered, but if someone uses an uncommon combinations, they have to add `#define PCL_NO_PRECOMPILE` before including `pcl/surface/mls.h` to avoid linker errors. --- surface/src/mls.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/surface/src/mls.cpp b/surface/src/mls.cpp index ba2fd655300..c948f4d19e1 100644 --- a/surface/src/mls.cpp +++ b/surface/src/mls.cpp @@ -80,6 +80,15 @@ pcl::MLSResult::calculatePrincipalCurvatures (const double u, const double v) co PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal)) ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal))) #else - PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, (PCL_XYZ_POINT_TYPES)(PCL_XYZ_POINT_TYPES)) + // PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, (PCL_XYZ_POINT_TYPES)(PCL_XYZ_POINT_TYPES)) + // All instantiations that are available with PCL_ONLY_CORE_POINT_TYPES, plus instantiations for all XYZ types where PointInT and PointOutT are the same + #define PCL_INSTANTIATE_MovingLeastSquaresSameInAndOut(T) template class PCL_EXPORTS pcl::MovingLeastSquares; + PCL_INSTANTIATE(MovingLeastSquaresSameInAndOut, PCL_XYZ_POINT_TYPES) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZ))((pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal))) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZI))((pcl::PointXYZ)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal))) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGB))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal)(pcl::PointNormal))) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGBA))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBNormal)(pcl::PointNormal))) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointXYZRGBNormal))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointNormal))) + PCL_INSTANTIATE_PRODUCT(MovingLeastSquares, ((pcl::PointNormal))((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::PointXYZRGBNormal))) #endif #endif // PCL_NO_PRECOMPILE From 6bb70d68cabd9f9177966b097891b62e4d6fbf9f Mon Sep 17 00:00:00 2001 From: Alessio Stella Date: Mon, 17 Jul 2023 10:42:07 +0200 Subject: [PATCH 102/288] Clarify expected speedup with NormalEstimationOMP (#5721) * Update normal_estimation.rst * Update normal_estimation.rst * Update normal_estimation.rst, comment on multithread openMP speed up comment on multithread openMP speed up --- doc/tutorials/content/normal_estimation.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/content/normal_estimation.rst b/doc/tutorials/content/normal_estimation.rst index c0885fa43d2..702176ff85a 100644 --- a/doc/tutorials/content/normal_estimation.rst +++ b/doc/tutorials/content/normal_estimation.rst @@ -250,8 +250,8 @@ normal estimation which uses multi-core/multi-threaded paradigms using OpenMP to speed the computation. The name of the class is **pcl::NormalEstimationOMP**, and its API is 100% compatible to the single-threaded **pcl::NormalEstimation**, which makes it suitable as a drop-in -replacement. On a system with 8 cores, you should get anything between 6-8 -times faster computation times. +replacement. On a system with n cores, you should get m times faster computation, with m<=n depending on several factors including CPU architecture, +point cloud characteristics, search parameters chosen, CPU global load. .. note:: From 27198225dce4840de87af5893832a5b0967fda4f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 17 Jul 2023 14:18:14 +0200 Subject: [PATCH 103/288] Remove unnecessary pseudo-instantiations of checkCoordinateSystem Reduces the compile time of PCL, see also https://github.com/PointCloudLibrary/pcl/pull/4788 --- common/include/pcl/common/eigen.h | 32 +------------------------------ 1 file changed, 1 insertion(+), 31 deletions(-) diff --git a/common/include/pcl/common/eigen.h b/common/include/pcl/common/eigen.h index 15b079a19fa..a1259e9d6a9 100644 --- a/common/include/pcl/common/eigen.h +++ b/common/include/pcl/common/eigen.h @@ -503,41 +503,11 @@ namespace pcl { Eigen::Matrix line_x; Eigen::Matrix line_y; - line_x << origin, x_direction; - line_y << origin, y_direction; - return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); - } - - inline bool - checkCoordinateSystem (const Eigen::Matrix &origin, - const Eigen::Matrix &x_direction, - const Eigen::Matrix &y_direction, - const double norm_limit = 1e-3, - const double dot_limit = 1e-3) - { - Eigen::Matrix line_x; - Eigen::Matrix line_y; - line_x.resize (6); - line_y.resize (6); - line_x << origin, x_direction; - line_y << origin, y_direction; - return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); - } - - inline bool - checkCoordinateSystem (const Eigen::Matrix &origin, - const Eigen::Matrix &x_direction, - const Eigen::Matrix &y_direction, - const float norm_limit = 1e-3, - const float dot_limit = 1e-3) - { - Eigen::Matrix line_x; - Eigen::Matrix line_y; line_x.resize (6); line_y.resize (6); line_x << origin, x_direction; line_y << origin, y_direction; - return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); + return (checkCoordinateSystem (line_x, line_y, norm_limit, dot_limit)); } /** \brief Compute the transformation between two coordinate systems From 04906b4f5e9361ce8cc5e40eae10ac064e32f4fa Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 19 Jul 2023 10:18:14 +0200 Subject: [PATCH 104/288] Fix reading of origin and orientation from PLY files `origin_` and `orientation_` are set inside the `parse` function (if the PLY file contains the information). Afterwards, the values have to be transferred to `origin` and `orientation` (the output parameters) --- io/include/pcl/io/ply_io.h | 4 ++-- io/src/ply_io.cpp | 10 ++++++---- test/io/test_ply_io.cpp | 16 ++++++++++++++-- 3 files changed, 22 insertions(+), 8 deletions(-) diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 3c6fbc4271d..07f07192abe 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -88,12 +88,12 @@ namespace pcl PLYReader () : origin_ (Eigen::Vector4f::Zero ()) - , orientation_ (Eigen::Matrix3f::Zero ()) + , orientation_ (Eigen::Matrix3f::Identity ()) {} PLYReader (const PLYReader &p) : origin_ (Eigen::Vector4f::Zero ()) - , orientation_ (Eigen::Matrix3f::Zero ()) + , orientation_ (Eigen::Matrix3f::Identity ()) , cloud_ () , vertex_count_ (0) , vertex_offset_before_ (0) diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 96f1a407517..b8c94329723 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -562,6 +562,8 @@ pcl::PLYReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c cloud_->width = cloud_->height = 0; origin = Eigen::Vector4f::Zero (); orientation = Eigen::Quaternionf::Identity (); + origin_ = Eigen::Vector4f::Zero (); + orientation_ = Eigen::Matrix3f::Identity (); if (!parse (file_name)) { PCL_ERROR ("[pcl::PLYReader::read] problem parsing header!\n"); @@ -653,8 +655,8 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, cloud_->data.swap (data); } - orientation_ = Eigen::Quaternionf (orientation); - origin_ = origin; + orientation = Eigen::Quaternionf (orientation_); + origin = origin_; for (auto &field : cloud_->fields) { @@ -752,8 +754,8 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, cloud_->data.swap (data); } - orientation_ = Eigen::Quaternionf (orientation); - origin_ = origin; + orientation = Eigen::Quaternionf (orientation_); + origin = origin_; for (auto &field : cloud_->fields) { diff --git a/test/io/test_ply_io.cpp b/test/io/test_ply_io.cpp index 7901a7e36e0..c6472e24580 100644 --- a/test/io/test_ply_io.cpp +++ b/test/io/test_ply_io.cpp @@ -80,10 +80,22 @@ TEST (PCL, PLYReaderWriter) // test for toPCLPointCloud2 () pcl::PLYWriter writer; - writer.write ("test_pcl_io.ply", cloud_blob, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), true, true); + const Eigen::Vector4f origin (0.0f, 0.5f, -1.0f, 0.0f); + const Eigen::Quaternionf orientation(std::sqrt(0.5f), std::sqrt(0.5f), 0.0f, 0.0f); + writer.write ("test_pcl_io.ply", cloud_blob, origin, orientation, true, true); pcl::PLYReader reader; - reader.read ("test_pcl_io.ply", cloud_blob2); + Eigen::Vector4f origin2; + Eigen::Quaternionf orientation2; + int ply_version; + reader.read ("test_pcl_io.ply", cloud_blob2, origin2, orientation2, ply_version); + EXPECT_NEAR (origin.x(), origin2.x(), 1e-5); + EXPECT_NEAR (origin.y(), origin2.y(), 1e-5); + EXPECT_NEAR (origin.z(), origin2.z(), 1e-5); + EXPECT_NEAR (orientation.x(), orientation2.x(), 1e-5); + EXPECT_NEAR (orientation.y(), orientation2.y(), 1e-5); + EXPECT_NEAR (orientation.z(), orientation2.z(), 1e-5); + EXPECT_NEAR (orientation.w(), orientation2.w(), 1e-5); //PLY DOES preserve organiziation EXPECT_EQ (cloud_blob.width * cloud_blob.height, cloud_blob2.width * cloud_blob2.height); EXPECT_EQ (cloud_blob.is_dense, cloud.is_dense); From e72ec76b6d1576a35ebc5692f0108b6a62c19ec2 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Fri, 21 Jul 2023 10:32:27 +0200 Subject: [PATCH 105/288] Correct doxygen in ply_io.h --- io/include/pcl/io/ply_io.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 07f07192abe..65a247a0b2a 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -129,8 +129,8 @@ namespace pcl * * > 0 on success * \param[in] file_name the name of the file to load * \param[out] cloud the resultant point cloud dataset (only the header will be filled) - * \param[in] origin the sensor data acquisition origin (translation) - * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] origin the sensor data acquisition origin (translation) + * \param[out] orientation the sensor data acquisition origin (rotation) * \param[out] ply_version the PLY version read from the file * \param[out] data_type the type of PLY data stored in the file * \param[out] data_idx the data index @@ -148,8 +148,8 @@ namespace pcl /** \brief Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2. * \param[in] file_name the name of the file containing the actual PointCloud data * \param[out] cloud the resultant PointCloud message read from disk - * \param[in] origin the sensor data acquisition origin (translation) - * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] origin the sensor data acquisition origin (translation) + * \param[out] orientation the sensor data acquisition origin (rotation) * \param[out] ply_version the PLY version read from the file * \param[in] offset the offset in the file where to expect the true header to begin. * One usage example for setting the offset parameter is for reading @@ -208,8 +208,8 @@ namespace pcl * * \param[in] file_name the name of the file containing the actual PointCloud data * \param[out] mesh the resultant PolygonMesh message read from disk - * \param[in] origin the sensor data acquisition origin (translation) - * \param[in] orientation the sensor data acquisition origin (rotation) + * \param[out] origin the sensor data acquisition origin (translation) + * \param[out] orientation the sensor data acquisition origin (rotation) * \param[out] ply_version the PLY version read from the file * \param[in] offset the offset in the file where to expect the true header to begin. * One usage example for setting the offset parameter is for reading @@ -747,9 +747,9 @@ namespace pcl /** \brief Load any PLY file into a PCLPointCloud2 type. * \param[in] file_name the name of the file to load - * \param[in] cloud the resultant templated point cloud - * \param[in] origin the sensor acquisition origin (only for > PLY_V7 - null if not present) - * \param[in] orientation the sensor acquisition orientation if available, + * \param[out] cloud the resultant templated point cloud + * \param[out] origin the sensor acquisition origin (only for > PLY_V7 - null if not present) + * \param[out] orientation the sensor acquisition orientation if available, * identity if not present * \ingroup io */ From dda590cfd18958aa07330c5bbcfb5bd37f24bb97 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 22 Jul 2023 15:34:56 +0200 Subject: [PATCH 106/288] =?UTF-8?q?Fix=20behaviour=20of=20BoxClipper3D=20T?= =?UTF-8?q?he=20constructor=20(as=20well=20as=20the=20setTransformation=20?= =?UTF-8?q?function)=20that=20takes=20a=20rotation,=20translation,=20and?= =?UTF-8?q?=20scaling=20as=20input,=20says=20in=20the=20documentation=20th?= =?UTF-8?q?at=20theses=20transformations=20are=20applied=20to=20the=20box.?= =?UTF-8?q?=20But=20actually=20they=20are=20applied=20to=20the=20points.?= =?UTF-8?q?=20This=20commit=20changes=20the=20behaviour=20of=20the=20code?= =?UTF-8?q?=20to=20match=20the=20documentation.=20I=20considered=20changin?= =?UTF-8?q?g=20the=20documentation=20to=20match=20the=20behaviour=20of=20t?= =?UTF-8?q?he=20code,=20but=20-=20in=20my=20opinion=20it=20is=20useful=20t?= =?UTF-8?q?o=20have=20a=20constructor/function=20to=20describe=20the=20box?= =?UTF-8?q?=20(rotation,=20box=20center,=20box=20dimensions)=20-=20the=20c?= =?UTF-8?q?urrent=20code=20(which=20applies=20first=20scaling,=20then=20ro?= =?UTF-8?q?tation,=20then=20translation=20to=20the=20points)=20is=20not=20?= =?UTF-8?q?very=20useful=20or=20intuitive.=20Imagine=20for=20example=20a?= =?UTF-8?q?=20box,=20one=20side=20twice=20as=20long=20as=20the=20others,?= =?UTF-8?q?=20and=20rotated=20by=2045=20degrees=20around=20some=20axis.=20?= =?UTF-8?q?Then=20it=20is=20impossible=20to=20find=20a=20scaling=20transfo?= =?UTF-8?q?rmation=20and=20rotation=20to=20transform=20all=20points=20insi?= =?UTF-8?q?de=20the=20box=20to=20the=20interval=20[-1;=20+1]=C2=B3,=20cons?= =?UTF-8?q?idering=20the=20scaling=20is=20applied=20first=20and=20in=20eac?= =?UTF-8?q?h=20axis=20separately.=20It=20would=20always=20result=20in=20a?= =?UTF-8?q?=20parallelepiped.=20-=20if=20one=20specifically=20wants=20to?= =?UTF-8?q?=20rotate/translate/whatever=20the=20points,=20it=20is=20easy?= =?UTF-8?q?=20to=20do=20so=20by=20using=20the=20constructor/function=20tha?= =?UTF-8?q?t=20takes=20an=20Affine3f=20and=20construct=20for=20example=20`?= =?UTF-8?q?Eigen::Affine3f=20transform=3DEigen::Translation3f(...)*Eigen::?= =?UTF-8?q?AngleAxisf(...,=20Eigen::Vector3f(...).normalized());`?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This also fixes incorrect references to a unit cube, which is a cube with edge length 1, or sometimes specifically a cube in the interval [0; 1]. However, BoxClipper3D uses a cube in the interval [-1; +1] (edge length 2). --- filters/include/pcl/filters/box_clipper3D.h | 9 +++++---- filters/include/pcl/filters/impl/box_clipper3D.hpp | 5 +---- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/filters/include/pcl/filters/box_clipper3D.h b/filters/include/pcl/filters/box_clipper3D.h index b2ebfa51f78..feade7de860 100644 --- a/filters/include/pcl/filters/box_clipper3D.h +++ b/filters/include/pcl/filters/box_clipper3D.h @@ -46,7 +46,8 @@ namespace pcl /** * \author Suat Gedikli * \brief Implementation of a box clipper in 3D. Actually it allows affine transformations, thus any parallelepiped in general pose. - * The affine transformation is used to transform the point before clipping it using the unit cube centered at origin and with an extend of -1 to +1 in each dimension + * The affine transformation is used to transform the point before clipping it using a cube centered at origin and with an extend of -1 to +1 in each dimension + * \sa CropBox * \ingroup filters */ template @@ -61,7 +62,7 @@ namespace pcl /** * \author Suat Gedikli * \brief Constructor taking an affine transformation matrix, which allows also shearing of the clipping area - * \param[in] transformation the 3x3 affine transformation matrix that is used to describe the unit cube + * \param[in] transformation the 3 dimensional affine transformation that is used to describe the cube ([-1; +1] in each dimension). The transformation is applied to the point(s)! */ BoxClipper3D (const Eigen::Affine3f& transformation); @@ -75,7 +76,7 @@ namespace pcl /** * \brief Set the affine transformation - * \param[in] transformation + * \param[in] transformation applied to the point(s) */ void setTransformation (const Eigen::Affine3f& transformation); @@ -115,7 +116,7 @@ namespace pcl void transformPoint (const PointT& pointIn, PointT& pointOut) const; private: /** - * \brief the affine transformation that is applied before clipping is done on the unit cube. + * \brief the affine transformation that is applied before clipping is done on the [-1; +1] cube. */ Eigen::Affine3f transformation_; diff --git a/filters/include/pcl/filters/impl/box_clipper3D.hpp b/filters/include/pcl/filters/impl/box_clipper3D.hpp index 9ef530eed72..923a3024a43 100644 --- a/filters/include/pcl/filters/impl/box_clipper3D.hpp +++ b/filters/include/pcl/filters/impl/box_clipper3D.hpp @@ -41,7 +41,6 @@ template pcl::BoxClipper3D::BoxClipper3D (const Eigen::Affine3f& transformation) : transformation_ (transformation) { - //inverse_transformation_ = transformation_.inverse (); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -61,15 +60,13 @@ template void pcl::BoxClipper3D::setTransformation (const Eigen::Affine3f& transformation) { transformation_ = transformation; - //inverse_transformation_ = transformation_.inverse (); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::BoxClipper3D::setTransformation (const Eigen::Vector3f& rodrigues, const Eigen::Vector3f& translation, const Eigen::Vector3f& box_size) { - transformation_ = Eigen::Translation3f (translation) * Eigen::AngleAxisf(rodrigues.norm (), rodrigues.normalized ()) * Eigen::Scaling (box_size); - //inverse_transformation_ = transformation_.inverse (); + transformation_ = (Eigen::Translation3f (translation) * Eigen::AngleAxisf(rodrigues.norm (), rodrigues.normalized ()) * Eigen::Scaling (0.5f * box_size)).inverse (); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// From 680c9a788c23e501699e78662a45bca6bb918e1a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 28 Jul 2023 11:02:59 +0200 Subject: [PATCH 107/288] Make Flann optional Fixes https://github.com/PointCloudLibrary/pcl/issues/5654 cmake prints a warning if Flann is not found PCL modules that can be built without Flann: common, octree, geometry, io, ml, stereo, tools --- CMakeLists.txt | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f1795cb72a9..b253942cf51 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -321,10 +321,14 @@ find_package(Threads REQUIRED) # Eigen3 (required) find_package(Eigen3 3.3 REQUIRED NO_MODULE) -# FLANN (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}") +# FLANN +find_package(FLANN 1.9.1) +if(NOT FLANN_FOUND) + message(WARNING "Flann was not found, so many PCL modules will not be built!") +else() + 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() endif() # libusb From be057496153b5038edec8b272d3fe41a6302c20d Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 30 Jul 2023 16:55:22 +0200 Subject: [PATCH 108/288] NormalEstimationOMP: use dynamic scheduling for faster computation So far, no scheduling was specified, which seems to result in a behaviour similar to static scheduling. However, this is suboptimal, as the workload is not balanced well between the threads, especially when using radius search. With dynamic scheduling (default chunk size of 256), the speedup (ratio of computation time of NormalEstimation and NormalEstimationOMP) is better. The speedup for organized datasets is slightly higher than for unorganized datasets, possibly because FLANN (used for unorganized datasets) already uses some parallelization, while OrganizedNeighbor does not. Laptop 1 (6 physical cores, 12 logical cores, number of threads set to 6): dataset | | | #/mm | speedup before | speedup after -----|-------------|----------|------|----------------|-------------- mug | organized | radius | 10 | 3.4857 | 5.2508 mug | organized | radius | 20 | 3.3441 | 5.1059 mug | organized | nearestk | 50 | 4.7033 | 5.0594 mug | organized | nearestk | 100 | 4.5808 | 4.9751 mug | unorganized | radius | 10 | 3.3374 | 4.8992 mug | unorganized | radius | 20 | 3.0206 | 4.7978 mug | unorganized | nearestk | 50 | 4.5841 | 4.9189 mug | unorganized | nearestk | 100 | 4.7062 | 4.8844 milk | organized | radius | 10 | 3.5140 | 5.1686 milk | organized | radius | 20 | 3.2605 | 5.1719 milk | organized | nearestk | 50 | 4.3245 | 4.9924 milk | organized | nearestk | 100 | 4.4170 | 4.9207 milk | unorganized | radius | 10 | 3.4451 | 4.8029 milk | unorganized | radius | 20 | 3.1887 | 4.8810 milk | unorganized | nearestk | 50 | 4.3789 | 4.6894 milk | unorganized | nearestk | 100 | 4.2717 | 4.7473 Laptop 2 (4 physical cores, 8 logical cores, number of threads set to 4): dataset | | | #/mm | speedup before | speedup after -----|-------------|----------|------|----------------|-------------- mug | organized | radius | 10 | 2.3783 | 3.9812 mug | organized | radius | 20 | 2.3080 | 3.9753 mug | organized | nearestk | 50 | 3.6190 | 3.9595 mug | organized | nearestk | 100 | 3.6100 | 3.9590 mug | unorganized | radius | 10 | 2.4181 | 3.7466 mug | unorganized | radius | 20 | 2.2157 | 3.8890 mug | unorganized | nearestk | 50 | 3.4894 | 3.6551 mug | unorganized | nearestk | 100 | 3.4293 | 3.7825 milk | organized | radius | 10 | 2.8174 | 3.8209 milk | organized | radius | 20 | 2.6911 | 3.9722 milk | organized | nearestk | 50 | 3.3346 | 3.9433 milk | organized | nearestk | 100 | 3.3275 | 3.9798 milk | unorganized | radius | 10 | 2.8815 | 3.5443 milk | unorganized | radius | 20 | 2.6467 | 3.7990 milk | unorganized | nearestk | 50 | 3.1602 | 3.6469 milk | unorganized | nearestk | 100 | 3.6460 | 3.7981 --- features/include/pcl/features/impl/normal_3d_omp.hpp | 6 ++++-- features/include/pcl/features/normal_3d_omp.h | 5 ++++- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/features/include/pcl/features/impl/normal_3d_omp.hpp b/features/include/pcl/features/impl/normal_3d_omp.hpp index a40b2bb2c2a..736b5c8d2fe 100644 --- a/features/include/pcl/features/impl/normal_3d_omp.hpp +++ b/features/include/pcl/features/impl/normal_3d_omp.hpp @@ -77,7 +77,8 @@ pcl::NormalEstimationOMP::computeFeature (PointCloudOut &ou default(none) \ shared(output) \ firstprivate(nn_indices, nn_dists) \ - num_threads(threads_) + num_threads(threads_) \ + schedule(dynamic, chunk_size_) // Iterating over the entire index vector for (std::ptrdiff_t idx = 0; idx < static_cast (indices_->size ()); ++idx) { @@ -106,7 +107,8 @@ pcl::NormalEstimationOMP::computeFeature (PointCloudOut &ou default(none) \ shared(output) \ firstprivate(nn_indices, nn_dists) \ - num_threads(threads_) + num_threads(threads_) \ + schedule(dynamic, chunk_size_) // Iterating over the entire index vector for (std::ptrdiff_t idx = 0; idx < static_cast (indices_->size ()); ++idx) { diff --git a/features/include/pcl/features/normal_3d_omp.h b/features/include/pcl/features/normal_3d_omp.h index a8ae45b0a37..ba10bb76d8d 100644 --- a/features/include/pcl/features/normal_3d_omp.h +++ b/features/include/pcl/features/normal_3d_omp.h @@ -72,8 +72,9 @@ namespace pcl public: /** \brief Initialize the scheduler and set the number of threads to use. * \param nr_threads the number of hardware threads to use (0 sets the value back to automatic) + * \param chunk_size PCL will use dynamic scheduling with this chunk size. Setting it too low will lead to more parallelization overhead. Setting it too high will lead to a worse balancing between the threads. */ - NormalEstimationOMP (unsigned int nr_threads = 0) + NormalEstimationOMP (unsigned int nr_threads = 0, int chunk_size = 256): chunk_size_(chunk_size) { feature_name_ = "NormalEstimationOMP"; @@ -90,6 +91,8 @@ namespace pcl /** \brief The number of threads the scheduler should use. */ unsigned int threads_; + /** \brief Chunk size for (dynamic) scheduling. */ + int chunk_size_; private: /** \brief Estimate normals for all points given in using the surface in * setSearchSurface () and the spatial locator in setSearchMethod () From 244da6ebdddaaf3675aa3943f2e73883125d201b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 1 Aug 2023 10:06:55 +0200 Subject: [PATCH 109/288] Add missing includes in cloud composer app --- .../include/pcl/apps/cloud_composer/signal_multiplexer.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h b/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h index 86c72299a5b..c8a5224f524 100644 --- a/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h +++ b/apps/cloud_composer/include/pcl/apps/cloud_composer/signal_multiplexer.h @@ -42,6 +42,8 @@ #pragma once +#include +#include #include namespace pcl From 3ed96c246e5c873713ec670b895469d09149a552 Mon Sep 17 00:00:00 2001 From: daizhirui Date: Wed, 9 Aug 2023 00:41:36 -0700 Subject: [PATCH 110/288] fix build with GNU13 and Eigen3.4 (#5783) * fix build with GNU13 and Eigen3.4 * fix clang-tidy test * set EIGEN3_FOUND from Eigen3_FOUND if it is not set --- CMakeLists.txt | 3 +++ PCLConfig.cmake.in | 3 +++ .../include/pcl/apps/point_cloud_editor/command.h | 2 ++ .../include/pcl/apps/point_cloud_editor/commandQueue.h | 1 + .../include/pcl/apps/point_cloud_editor/select1DTool.h | 2 ++ .../include/pcl/apps/point_cloud_editor/statistics.h | 1 + .../include/pcl/apps/point_cloud_editor/toolInterface.h | 2 ++ common/include/pcl/common/impl/gaussian.hpp | 1 + common/src/colors.cpp | 1 + common/src/gaussian.cpp | 1 + common/src/range_image_planar.cpp | 1 + geometry/include/pcl/geometry/mesh_base.h | 1 + gpu/features/src/features.cpp | 2 ++ kdtree/include/pcl/kdtree/kdtree.h | 1 + 14 files changed, 22 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 869b663cca3..92ffe0a4270 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -320,6 +320,9 @@ find_package(Threads REQUIRED) # Eigen3 (required) find_package(Eigen3 3.3 REQUIRED NO_MODULE) +if(NOT EIGEN3_FOUND AND Eigen3_FOUND) + set(EIGEN3_FOUND ${Eigen3_FOUND}) +endif() # FLANN find_package(FLANN 1.9.1) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 1a628a250c2..c66e5fcc7c0 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -117,6 +117,9 @@ macro(find_eigen3) set(Eigen3_DIR "${PCL_ROOT}/3rdParty/Eigen3/share/eigen3/cmake/") endif() find_package(Eigen3 3.3 REQUIRED NO_MODULE) + if(NOT EIGEN3_FOUND AND Eigen3_FOUND) + set(EIGEN3_FOUND ${Eigen3_FOUND}) + endif() endmacro() #remove this as soon as qhull is shipped with FindQhull.cmake diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/command.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/command.h index e7dbdedd3a0..ca4ef7fb128 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/command.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/command.h @@ -43,6 +43,8 @@ #include +#include + /// @brief The abstract parent class of all the command classes. Commands are /// non-copyable. class Command diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h index 93433339c06..f69d9fa05b4 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/commandQueue.h @@ -41,6 +41,7 @@ #pragma once +#include #include #include diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select1DTool.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select1DTool.h index fc21d80aac4..ee34d7d7502 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select1DTool.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select1DTool.h @@ -44,6 +44,8 @@ #include // for pcl::shared_ptr +#include + class Selection; class Select1DTool : public ToolInterface diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/statistics.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/statistics.h index 8618e4b965e..80d3fc4744d 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/statistics.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/statistics.h @@ -42,6 +42,7 @@ #include #include +#include #include class Statistics diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/toolInterface.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/toolInterface.h index c5cc67c89ea..38111acba28 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/toolInterface.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/toolInterface.h @@ -43,6 +43,8 @@ #include +#include + /// @brief the parent class of all the select and the transform tool classes class ToolInterface { diff --git a/common/include/pcl/common/impl/gaussian.hpp b/common/include/pcl/common/impl/gaussian.hpp index 3b9c20b22c9..f8ecab25c02 100644 --- a/common/include/pcl/common/impl/gaussian.hpp +++ b/common/include/pcl/common/impl/gaussian.hpp @@ -40,6 +40,7 @@ #pragma once #include +#include namespace pcl { diff --git a/common/src/colors.cpp b/common/src/colors.cpp index 4d53ab1304d..77970055fd2 100644 --- a/common/src/colors.cpp +++ b/common/src/colors.cpp @@ -38,6 +38,7 @@ #include #include +#include #include /// Glasbey lookup table diff --git a/common/src/gaussian.cpp b/common/src/gaussian.cpp index 69bbd125336..2b6a667164f 100644 --- a/common/src/gaussian.cpp +++ b/common/src/gaussian.cpp @@ -36,6 +36,7 @@ */ #include +#include void pcl::GaussianKernel::compute (float sigma, diff --git a/common/src/range_image_planar.cpp b/common/src/range_image_planar.cpp index 784c40ccb64..206288016ea 100644 --- a/common/src/range_image_planar.cpp +++ b/common/src/range_image_planar.cpp @@ -34,6 +34,7 @@ /** \author Bastian Steder */ +#include #include using std::cout; using std::cerr; diff --git a/geometry/include/pcl/geometry/mesh_base.h b/geometry/include/pcl/geometry/mesh_base.h index d9346bab944..f0437d2d5d3 100644 --- a/geometry/include/pcl/geometry/mesh_base.h +++ b/geometry/include/pcl/geometry/mesh_base.h @@ -48,6 +48,7 @@ #include #include +#include #include #include diff --git a/gpu/features/src/features.cpp b/gpu/features/src/features.cpp index cefd88b6916..a0172c3a2cb 100644 --- a/gpu/features/src/features.cpp +++ b/gpu/features/src/features.cpp @@ -41,6 +41,8 @@ #include #include +#include + using namespace pcl::device; ///////////////////////////////////////////////////////////////////////// diff --git a/kdtree/include/pcl/kdtree/kdtree.h b/kdtree/include/pcl/kdtree/kdtree.h index d8d4e4bdd26..fd5e357fb09 100644 --- a/kdtree/include/pcl/kdtree/kdtree.h +++ b/kdtree/include/pcl/kdtree/kdtree.h @@ -43,6 +43,7 @@ #include #include #include +#include namespace pcl { From b520a831182bc1d286bb2023093157f5796ad460 Mon Sep 17 00:00:00 2001 From: Tiago Gaspar Oliveira Date: Sun, 13 Aug 2023 09:36:48 +0100 Subject: [PATCH 111/288] Modify FlannSearch to return Indices of Point Cloud (issue #5774) (#5780) * Modify FlannSearch to return Indices of Point Cloud FlannSearch was returning, in the radiusSearch and NearestKSearch, the Indices of the Indices passed, which is inconsistent with the other search clases. * Correct FLannSearch bug Correct bug when k > input_ size * Change total_nr_points in flann_search to std::size_t * Add static_cast to k variable in flann_search.hpp --- search/include/pcl/search/flann_search.h | 2 ++ search/include/pcl/search/impl/flann_search.hpp | 15 ++++++++++++--- test/search/test_search.cpp | 6 ++++++ 3 files changed, 20 insertions(+), 3 deletions(-) diff --git a/search/include/pcl/search/flann_search.h b/search/include/pcl/search/flann_search.h index e3461988feb..f3de1362268 100644 --- a/search/include/pcl/search/flann_search.h +++ b/search/include/pcl/search/flann_search.h @@ -363,6 +363,8 @@ namespace pcl Indices index_mapping_; bool identity_mapping_; + std::size_t total_nr_points_; + }; } } diff --git a/search/include/pcl/search/impl/flann_search.hpp b/search/include/pcl/search/impl/flann_search.hpp index 1cd7e7f87b4..94270ba1bcf 100644 --- a/search/include/pcl/search/impl/flann_search.hpp +++ b/search/include/pcl/search/impl/flann_search.hpp @@ -118,6 +118,9 @@ pcl::search::FlannSearch::nearestKSearch (const PointT &p float* cdata = can_cast ? const_cast (reinterpret_cast (&point)): data; const flann::Matrix m (cdata ,1, point_representation_->getNumberOfDimensions ()); + if (static_cast(k) > total_nr_points_) + k = total_nr_points_; + flann::SearchParams p; p.eps = eps_; p.sorted = sorted_results_; @@ -180,6 +183,9 @@ pcl::search::FlannSearch::nearestKSearch ( float* cdata = can_cast ? const_cast (reinterpret_cast (&cloud[0])): data; const flann::Matrix m (cdata ,cloud.size (), dim_, can_cast ? sizeof (PointT) : dim_ * sizeof (float) ); + if (static_cast(k) > total_nr_points_) + k = total_nr_points_; + flann::SearchParams p; p.sorted = sorted_results_; p.eps = eps_; @@ -385,6 +391,7 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () // const cast is evil, but flann won't change the data input_flann_ = static_cast (new flann::Matrix (const_cast(reinterpret_cast(&(*input_) [0])), original_no_of_points, point_representation_->getNumberOfDimensions (),sizeof (PointT))); input_copied_for_flann_ = false; + total_nr_points_ = input_->points.size(); } else { @@ -400,11 +407,12 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () continue; } - index_mapping_.push_back (static_cast (i)); // If the returned index should be for the indices vector + index_mapping_.push_back (static_cast (i)); point_representation_->vectorize (point, cloud_ptr); cloud_ptr += dim_; } + total_nr_points_ = index_mapping_.size(); } } @@ -412,6 +420,7 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () { input_flann_ = static_cast (new flann::Matrix (new float[original_no_of_points*point_representation_->getNumberOfDimensions ()], original_no_of_points, point_representation_->getNumberOfDimensions ())); float* cloud_ptr = input_flann_->ptr(); + identity_mapping_ = false; for (std::size_t indices_index = 0; indices_index < original_no_of_points; ++indices_index) { index_t cloud_index = (*indices_)[indices_index]; @@ -419,15 +428,15 @@ pcl::search::FlannSearch::convertInputToFlannMatrix () // Check if the point is invalid if (!point_representation_->isValid (point)) { - identity_mapping_ = false; continue; } - index_mapping_.push_back (static_cast (indices_index)); // If the returned index should be for the indices vector + index_mapping_.push_back (static_cast (cloud_index)); point_representation_->vectorize (point, cloud_ptr); cloud_ptr += dim_; } + total_nr_points_ = index_mapping_.size(); } if (input_copied_for_flann_) input_flann_->rows = index_mapping_.size (); diff --git a/test/search/test_search.cpp b/test/search/test_search.cpp index 20bf9734d04..94b86d76922 100644 --- a/test/search/test_search.cpp +++ b/test/search/test_search.cpp @@ -41,6 +41,7 @@ #include #include +#include #include #include #include @@ -114,6 +115,9 @@ pcl::search::BruteForce brute_force; /** \brief instance of KDTree search method to be tested*/ pcl::search::KdTree KDTree; +/** \brief instance of FlannSearch search method to be tested*/ +pcl::search::FlannSearch FlannSearch; + /** \brief instance of Octree search method to be tested*/ pcl::search::Octree octree_search (0.1); @@ -657,10 +661,12 @@ main (int argc, char** argv) unorganized_search_methods.push_back (&brute_force); unorganized_search_methods.push_back (&KDTree); + unorganized_search_methods.push_back (&FlannSearch); unorganized_search_methods.push_back (&octree_search); organized_search_methods.push_back (&brute_force); organized_search_methods.push_back (&KDTree); + organized_search_methods.push_back (&FlannSearch); organized_search_methods.push_back (&octree_search); organized_search_methods.push_back (&organized); From 1f739500345c6fe8e6018e7da306013901d32867 Mon Sep 17 00:00:00 2001 From: daohu527 Date: Mon, 21 Aug 2023 19:17:10 +0800 Subject: [PATCH 112/288] fix: remove unnecessary indices erase in extract_clusters --- segmentation/include/pcl/segmentation/extract_clusters.h | 6 ++---- .../include/pcl/segmentation/impl/extract_clusters.hpp | 7 ++----- .../pcl/segmentation/impl/extract_labeled_clusters.hpp | 3 +-- 3 files changed, 5 insertions(+), 11 deletions(-) diff --git a/segmentation/include/pcl/segmentation/extract_clusters.h b/segmentation/include/pcl/segmentation/extract_clusters.h index d7234ade46f..b62b93cb8bf 100644 --- a/segmentation/include/pcl/segmentation/extract_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_clusters.h @@ -179,9 +179,8 @@ namespace pcl for (std::size_t j = 0; j < seed_queue.size (); ++j) r.indices[j] = seed_queue[j]; - // These two lines should not be needed: (can anyone confirm?) -FF + // After clustering, indices are out of order, so sort them std::sort (r.indices.begin (), r.indices.end ()); - r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); r.header = cloud.header; clusters.push_back (r); // We could avoid a copy by working directly in the vector @@ -299,9 +298,8 @@ namespace pcl for (std::size_t j = 0; j < seed_queue.size (); ++j) r.indices[j] = seed_queue[j]; - // These two lines should not be needed: (can anyone confirm?) -FF + // After clustering, indices are out of order, so sort them std::sort (r.indices.begin (), r.indices.end ()); - r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); r.header = cloud.header; clusters.push_back (r); diff --git a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp index 89ee6a01456..8c1fb79aa1e 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_clusters.hpp @@ -106,9 +106,8 @@ pcl::extractEuclideanClusters (const PointCloud &cloud, for (std::size_t j = 0; j < seed_queue.size (); ++j) r.indices[j] = seed_queue[j]; - // These two lines should not be needed: (can anyone confirm?) -FF + // After clustering, indices are out of order, so sort them std::sort (r.indices.begin (), r.indices.end ()); - r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); r.header = cloud.header; clusters.push_back (r); // We could avoid a copy by working directly in the vector @@ -203,10 +202,8 @@ pcl::extractEuclideanClusters (const PointCloud &cloud, // This is the only place where indices come into play r.indices[j] = seed_queue[j]; - // These two lines should not be needed: (can anyone confirm?) -FF - //r.indices.assign(seed_queue.begin(), seed_queue.end()); + // After clustering, indices are out of order, so sort them std::sort (r.indices.begin (), r.indices.end ()); - r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ()); r.header = cloud.header; clusters.push_back (r); // We could avoid a copy by working directly in the vector diff --git a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp index cbaa75aaf3d..17463b778e0 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp @@ -129,9 +129,8 @@ pcl::extractLabeledEuclideanClusters( r.indices.resize(seed_queue.size()); for (std::size_t j = 0; j < seed_queue.size(); ++j) r.indices[j] = seed_queue[j]; - + // After clustering, indices are out of order, so sort them std::sort(r.indices.begin(), r.indices.end()); - r.indices.erase(std::unique(r.indices.begin(), r.indices.end()), r.indices.end()); r.header = cloud.header; labeled_clusters[cloud[i].label].push_back( From cb33bf7b6f4605743586436ff33e664311e8ab1a Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Thu, 24 Aug 2023 09:20:25 +0200 Subject: [PATCH 113/288] Improve PPFRegistration (#5767) * Improve PPFRegistration - add function getBestPoseCandidates to have access to all pose candidates, not just the one with the most votes - use ceil instead of floor, otherwise the accumulator_array can be too small in some cases - do not only use the single highest peak from accumulator array, but use more peaks if they have similarly many votes as the maximum - while pose clustering, make sure that a pose is added to the closest cluster, not simply to the first cluster below the clustering threshold (if more than one clusters are possible) - use a better threshold-based filtering of candidate poses, instead of always using the 3 poses with the most votes - re-activate and improve test for PPFRegistration * Make clang-tidy happy * Make clang-format happy * Add more const * clang-format * Update ppf_registration.h --- .../registration/impl/ppf_registration.hpp | 165 +++++++++++------- .../pcl/registration/ppf_registration.h | 23 ++- test/registration/test_registration.cpp | 63 +++---- 3 files changed, 157 insertions(+), 94 deletions(-) diff --git a/registration/include/pcl/registration/impl/ppf_registration.hpp b/registration/include/pcl/registration/impl/ppf_registration.hpp index 18c5855605d..685c4b82767 100644 --- a/registration/include/pcl/registration/impl/ppf_registration.hpp +++ b/registration/include/pcl/registration/impl/ppf_registration.hpp @@ -78,12 +78,21 @@ pcl::PPFRegistration::computeTransformation( } const auto aux_size = static_cast( - std::floor(2 * M_PI / search_method_->getAngleDiscretizationStep())); + std::ceil(2 * M_PI / search_method_->getAngleDiscretizationStep())); + if (std::abs(std::round(2 * M_PI / search_method_->getAngleDiscretizationStep()) - + 2 * M_PI / search_method_->getAngleDiscretizationStep()) > 0.1) { + PCL_WARN("[pcl::PPFRegistration::computeTransformation] The chosen angle " + "discretization step (%g) does not result in a uniform discretization. " + "Consider using e.g. 2pi/%zu or 2pi/%zu\n", + search_method_->getAngleDiscretizationStep(), + aux_size - 1, + aux_size); + } const std::vector tmp_vec(aux_size, 0); std::vector> accumulator_array(input_->size(), tmp_vec); - PCL_DEBUG("Accumulator array size: %u x %u.\n", + PCL_DEBUG("[PPFRegistration] Accumulator array size: %u x %u.\n", accumulator_array.size(), accumulator_array.back().size()); @@ -137,9 +146,10 @@ pcl::PPFRegistration::computeTransformation( search_method_->nearestNeighborSearch(f1, f2, f3, f4, nearest_indices); // Compute alpha_s angle - Eigen::Vector3f scene_point = (*target_)[scene_point_index].getVector3fMap(); + const Eigen::Vector3f scene_point = + (*target_)[scene_point_index].getVector3fMap(); - Eigen::Vector3f scene_point_transformed = transform_sg * scene_point; + const Eigen::Vector3f scene_point_transformed = transform_sg * scene_point; float alpha_s = std::atan2(-scene_point_transformed(2), scene_point_transformed(1)); if (std::sin(alpha_s) * scene_point_transformed(2) < 0.0f) @@ -173,55 +183,60 @@ pcl::PPFRegistration::computeTransformation( } } - std::size_t max_votes_i = 0, max_votes_j = 0; + // the paper says: "For stability reasons, all peaks that received a certain amount + // of votes relative to the maximum peak are used." No specific value is mentioned, + // but 90% seems good unsigned int max_votes = 0; - - for (std::size_t i = 0; i < accumulator_array.size(); ++i) - for (std::size_t j = 0; j < accumulator_array.back().size(); ++j) { - if (accumulator_array[i][j] > max_votes) { + const std::size_t size_i = accumulator_array.size(), + size_j = accumulator_array.back().size(); + for (std::size_t i = 0; i < size_i; ++i) + for (std::size_t j = 0; j < size_j; ++j) { + if (accumulator_array[i][j] > max_votes) max_votes = accumulator_array[i][j]; - max_votes_i = i; - max_votes_j = j; + } + max_votes *= 0.9; + for (std::size_t i = 0; i < size_i; ++i) + for (std::size_t j = 0; j < size_j; ++j) { + if (accumulator_array[i][j] >= max_votes) { + const Eigen::Vector3f model_reference_point = (*input_)[i].getVector3fMap(), + model_reference_normal = + (*input_)[i].getNormalVector3fMap(); + const float rotation_angle_mg = + std::acos(model_reference_normal.dot(Eigen::Vector3f::UnitX())); + const bool parallel_to_x_mg = (model_reference_normal.y() == 0.0f && + model_reference_normal.z() == 0.0f); + const Eigen::Vector3f rotation_axis_mg = + (parallel_to_x_mg) + ? (Eigen::Vector3f::UnitY()) + : (model_reference_normal.cross(Eigen::Vector3f::UnitX()) + .normalized()); + const Eigen::AngleAxisf rotation_mg(rotation_angle_mg, rotation_axis_mg); + const Eigen::Affine3f transform_mg( + Eigen::Translation3f(rotation_mg * ((-1) * model_reference_point)) * + rotation_mg); + const Eigen::Affine3f max_transform = + transform_sg.inverse() * + Eigen::AngleAxisf((static_cast(j + 0.5) * + search_method_->getAngleDiscretizationStep() - + M_PI), + Eigen::Vector3f::UnitX()) * + transform_mg; + + voted_poses.push_back(PoseWithVotes(max_transform, accumulator_array[i][j])); } // Reset accumulator_array for the next set of iterations with a new scene // reference point accumulator_array[i][j] = 0; } - - Eigen::Vector3f model_reference_point = (*input_)[max_votes_i].getVector3fMap(), - model_reference_normal = - (*input_)[max_votes_i].getNormalVector3fMap(); - float rotation_angle_mg = - std::acos(model_reference_normal.dot(Eigen::Vector3f::UnitX())); - bool parallel_to_x_mg = - (model_reference_normal.y() == 0.0f && model_reference_normal.z() == 0.0f); - Eigen::Vector3f rotation_axis_mg = - (parallel_to_x_mg) - ? (Eigen::Vector3f::UnitY()) - : (model_reference_normal.cross(Eigen::Vector3f::UnitX()).normalized()); - Eigen::AngleAxisf rotation_mg(rotation_angle_mg, rotation_axis_mg); - Eigen::Affine3f transform_mg( - Eigen::Translation3f(rotation_mg * ((-1) * model_reference_point)) * - rotation_mg); - Eigen::Affine3f max_transform = - transform_sg.inverse() * - Eigen::AngleAxisf((static_cast(max_votes_j + 0.5) * - search_method_->getAngleDiscretizationStep() - - M_PI), - Eigen::Vector3f::UnitX()) * - transform_mg; - - voted_poses.push_back(PoseWithVotes(max_transform, max_votes)); } - PCL_DEBUG("Done with the Hough Transform ...\n"); + PCL_DEBUG("[PPFRegistration] Done with the Hough Transform ...\n"); // Cluster poses for filtering out outliers and obtaining more precise results - PoseWithVotesList results; - clusterPoses(voted_poses, results); + clusterPoses(voted_poses, best_pose_candidates); - pcl::transformPointCloud(*input_, output, results.front().pose); + pcl::transformPointCloud(*input_, output, best_pose_candidates.front().pose); - transformation_ = final_transformation_ = results.front().pose.matrix(); + transformation_ = final_transformation_ = best_pose_candidates.front().pose.matrix(); converged_ = true; } @@ -232,7 +247,8 @@ pcl::PPFRegistration::clusterPoses( typename pcl::PPFRegistration::PoseWithVotesList& poses, typename pcl::PPFRegistration::PoseWithVotesList& result) { - PCL_DEBUG("Clustering poses ...\n"); + PCL_DEBUG("[PPFRegistration] Clustering poses (initially got %zu poses)\n", + poses.size()); // Start off by sorting the poses by the number of votes sort(poses.begin(), poses.end(), poseWithVotesCompareFunction); @@ -240,17 +256,37 @@ pcl::PPFRegistration::clusterPoses( std::vector> cluster_votes; for (std::size_t poses_i = 0; poses_i < poses.size(); ++poses_i) { bool found_cluster = false; + float lowest_position_diff = std::numeric_limits::max(), + lowest_rotation_diff_angle = std::numeric_limits::max(); + std::size_t best_cluster = 0; for (std::size_t clusters_i = 0; clusters_i < clusters.size(); ++clusters_i) { + // if a pose can be added to more than one cluster (posesWithinErrorBounds returns + // true), then add it to the one where position and rotation difference are + // smallest + float position_diff, rotation_diff_angle; if (posesWithinErrorBounds(poses[poses_i].pose, - clusters[clusters_i].front().pose)) { - found_cluster = true; - clusters[clusters_i].push_back(poses[poses_i]); - cluster_votes[clusters_i].second += poses[poses_i].votes; - break; + clusters[clusters_i].front().pose, + position_diff, + rotation_diff_angle)) { + if (!found_cluster) { + found_cluster = true; + best_cluster = clusters_i; + lowest_position_diff = position_diff; + lowest_rotation_diff_angle = rotation_diff_angle; + } + else if (position_diff < lowest_position_diff && + rotation_diff_angle < lowest_rotation_diff_angle) { + best_cluster = clusters_i; + lowest_position_diff = position_diff; + lowest_rotation_diff_angle = rotation_diff_angle; + } } } - - if (!found_cluster) { + if (found_cluster) { + clusters[best_cluster].push_back(poses[poses_i]); + cluster_votes[best_cluster].second += poses[poses_i].votes; + } + else { // Create a new cluster with the current pose PoseWithVotesList new_cluster; new_cluster.push_back(poses[poses_i]); @@ -259,28 +295,30 @@ pcl::PPFRegistration::clusterPoses( clusters.size() - 1, poses[poses_i].votes)); } } + PCL_DEBUG("[PPFRegistration] %zu poses remaining after clustering. Now averaging " + "each cluster and removing clusters with too few votes.\n", + clusters.size()); // Sort clusters by total number of votes std::sort(cluster_votes.begin(), cluster_votes.end(), clusterVotesCompareFunction); // Compute pose average and put them in result vector - /// @todo some kind of threshold for determining whether a cluster has enough votes or - /// not... now just taking the first three clusters result.clear(); - std::size_t max_clusters = (clusters.size() < 3) ? clusters.size() : 3; - for (std::size_t cluster_i = 0; cluster_i < max_clusters; ++cluster_i) { + for (std::size_t cluster_i = 0; cluster_i < clusters.size(); ++cluster_i) { + // Remove all clusters that have less than 10% of the votes of the peak cluster. + // This way, if there is e.g. one cluster with far more votes than all other + // clusters, only that one is kept. + if (cluster_votes[cluster_i].second < 0.1 * cluster_votes[0].second) + continue; PCL_DEBUG("Winning cluster has #votes: %d and #poses voted: %d.\n", cluster_votes[cluster_i].second, clusters[cluster_votes[cluster_i].first].size()); Eigen::Vector3f translation_average(0.0, 0.0, 0.0); Eigen::Vector4f rotation_average(0.0, 0.0, 0.0, 0.0); - for (typename PoseWithVotesList::iterator v_it = - clusters[cluster_votes[cluster_i].first].begin(); - v_it != clusters[cluster_votes[cluster_i].first].end(); - ++v_it) { - translation_average += v_it->pose.translation(); + for (const auto& vote : clusters[cluster_votes[cluster_i].first]) { + translation_average += vote.pose.translation(); /// averaging rotations by just averaging the quaternions in 4D space - reference /// "On Averaging Rotations" by CLAUS GRAMKOW - rotation_average += Eigen::Quaternionf(v_it->pose.rotation()).coeffs(); + rotation_average += Eigen::Quaternionf(vote.pose.rotation()).coeffs(); } translation_average /= @@ -301,13 +339,16 @@ pcl::PPFRegistration::clusterPoses( template bool pcl::PPFRegistration::posesWithinErrorBounds( - Eigen::Affine3f& pose1, Eigen::Affine3f& pose2) + Eigen::Affine3f& pose1, + Eigen::Affine3f& pose2, + float& position_diff, + float& rotation_diff_angle) { - float position_diff = (pose1.translation() - pose2.translation()).norm(); + position_diff = (pose1.translation() - pose2.translation()).norm(); Eigen::AngleAxisf rotation_diff_mat( (pose1.rotation().inverse().lazyProduct(pose2.rotation()).eval())); - float rotation_diff_angle = std::abs(rotation_diff_mat.angle()); + rotation_diff_angle = std::abs(rotation_diff_mat.angle()); return (position_diff < clustering_position_diff_threshold_ && rotation_diff_angle < clustering_rotation_diff_threshold_); diff --git a/registration/include/pcl/registration/ppf_registration.h b/registration/include/pcl/registration/ppf_registration.h index 602cce85ead..81e783dd7f3 100644 --- a/registration/include/pcl/registration/ppf_registration.h +++ b/registration/include/pcl/registration/ppf_registration.h @@ -181,7 +181,7 @@ class PPFRegistration : public Registration { * - std::pair does not have a custom allocator */ struct PoseWithVotes { - PoseWithVotes(Eigen::Affine3f& a_pose, unsigned int& a_votes) + PoseWithVotes(const Eigen::Affine3f& a_pose, unsigned int& a_votes) : pose(a_pose), votes(a_votes) {} @@ -298,6 +298,18 @@ class PPFRegistration : public Registration { void setInputTarget(const PointCloudTargetConstPtr& cloud) override; + /** \brief Returns the most promising pose candidates, after clustering. The pose with + * the most votes is the result of the registration. It may make sense to check the + * next best pose candidates if the registration did not give the right result, or if + * there are more than one correct results. You need to call the align function before + * this one. + */ + inline PoseWithVotesList + getBestPoseCandidates() + { + return best_pose_candidates; + } + private: /** \brief Method that calculates the transformation between the input_ and target_ * point clouds, based on the PPF features */ @@ -321,6 +333,10 @@ class PPFRegistration : public Registration { * through the point cloud */ typename pcl::KdTreeFLANN::Ptr scene_search_tree_; + /** \brief List with the most promising pose candidates, after clustering. The pose + * with the most votes is returned as the registration result. */ + PoseWithVotesList best_pose_candidates; + /** \brief static method used for the std::sort function to order two PoseWithVotes * instances by their number of votes*/ static bool @@ -341,7 +357,10 @@ class PPFRegistration : public Registration { /** \brief Method that checks whether two poses are close together - based on the * clustering threshold parameters of the class */ bool - posesWithinErrorBounds(Eigen::Affine3f& pose1, Eigen::Affine3f& pose2); + posesWithinErrorBounds(Eigen::Affine3f& pose1, + Eigen::Affine3f& pose2, + float& position_diff, + float& rotation_diff_angle); }; } // namespace pcl diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index 6fa4ad6eb94..0d3b7dcdb6c 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -724,18 +724,21 @@ TEST (PCL, PyramidFeatureHistogram) EXPECT_NEAR (similarity_value3, 0.873699546, 1e-3); } -// Suat G: disabled, since the transformation does not look correct. -// ToDo: update transformation from the ground truth. -#if 0 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, PPFRegistration) { - // Transform the source cloud by a large amount - Eigen::Vector3f initial_offset (100, 0, 0); - float angle = M_PI/6; - Eigen::Quaternionf initial_rotation (std::cos (angle / 2), 0, 0, sin (angle / 2)); + Eigen::Matrix4f bun0_to_bun4_groundtruth; + bun0_to_bun4_groundtruth << + 0.825336f, 0.000000f, -0.564642f, 0.037267f, + 0.000000f, 1.000000f, 0.000000f, 0.000000f, + 0.564642f, 0.000000f, 0.825336f, 0.038325f, + 0.000000f, 0.000000f, 0.000000f, 1.000000f; + + // apply some additional, random transformation to show that the initial point cloud poses do not matter + const Eigen::Affine3f additional_transformation = Eigen::Translation3f(-0.515f, 0.260f, -0.845f) * + Eigen::AngleAxisf(-1.627f, Eigen::Vector3f(0.354f, 0.878f, -0.806f).normalized()); PointCloud cloud_source_transformed; - transformPointCloud (cloud_source, cloud_source_transformed, initial_offset, initial_rotation); + transformPointCloud (cloud_source, cloud_source_transformed, additional_transformation); // Create shared pointers @@ -747,7 +750,7 @@ TEST (PCL, PPFRegistration) NormalEstimation normal_estimation; search::KdTree::Ptr search_tree (new search::KdTree ()); normal_estimation.setSearchMethod (search_tree); - normal_estimation.setRadiusSearch (0.05); + normal_estimation.setKSearch(30); // nearest-k-search seems to work better than radius-search PointCloud::Ptr normals_target (new PointCloud ()), normals_source_transformed (new PointCloud ()); normal_estimation.setInputCloud (cloud_target_ptr); @@ -769,41 +772,41 @@ TEST (PCL, PPFRegistration) // Train the source cloud - create the hash map search structure - PPFHashMapSearch::Ptr hash_map_search (new PPFHashMapSearch (15.0 / 180 * M_PI, + PPFHashMapSearch::Ptr hash_map_search (new PPFHashMapSearch (2.0 * M_PI / 36, // divide into 36 steps 0.05)); hash_map_search->setInputFeatureCloud (features_source_transformed); // Finally, do the registration PPFRegistration ppf_registration; - ppf_registration.setSceneReferencePointSamplingRate (20); + ppf_registration.setSceneReferencePointSamplingRate (5); ppf_registration.setPositionClusteringThreshold (0.15); - ppf_registration.setRotationClusteringThreshold (45.0 / 180 * M_PI); + ppf_registration.setRotationClusteringThreshold (25.0 / 180 * M_PI); ppf_registration.setSearchMethod (hash_map_search); - ppf_registration.setInputCloud (cloud_source_transformed_with_normals); + ppf_registration.setInputSource (cloud_source_transformed_with_normals); ppf_registration.setInputTarget (cloud_target_with_normals); PointCloud cloud_output; ppf_registration.align (cloud_output); Eigen::Matrix4f transformation = ppf_registration.getFinalTransformation (); - EXPECT_NEAR (transformation(0, 0), -0.153768, 1e-4); - EXPECT_NEAR (transformation(0, 1), -0.628136, 1e-4); - EXPECT_NEAR (transformation(0, 2), 0.762759, 1e-4); - EXPECT_NEAR (transformation(0, 3), 15.472, 1e-4); - EXPECT_NEAR (transformation(1, 0), 0.967397, 1e-4); - EXPECT_NEAR (transformation(1, 1), -0.252918, 1e-4); - EXPECT_NEAR (transformation(1, 2), -0.0132578, 1e-4); - EXPECT_NEAR (transformation(1, 3), -96.6221, 1e-4); - EXPECT_NEAR (transformation(2, 0), 0.201243, 1e-4); - EXPECT_NEAR (transformation(2, 1), 0.735852, 1e-4); - EXPECT_NEAR (transformation(2, 2), 0.646547, 1e-4); - EXPECT_NEAR (transformation(2, 3), -20.134, 1e-4); - EXPECT_NEAR (transformation(3, 0), 0.000000, 1e-4); - EXPECT_NEAR (transformation(3, 1), 0.000000, 1e-4); - EXPECT_NEAR (transformation(3, 2), 0.000000, 1e-4); - EXPECT_NEAR (transformation(3, 3), 1.000000, 1e-4); + const Eigen::Matrix4f reference_transformation = bun0_to_bun4_groundtruth * additional_transformation.inverse().matrix(); + EXPECT_NEAR (transformation(0, 0), reference_transformation(0, 0), 0.1); + EXPECT_NEAR (transformation(0, 1), reference_transformation(0, 1), 0.1); + EXPECT_NEAR (transformation(0, 2), reference_transformation(0, 2), 0.1); + EXPECT_NEAR (transformation(0, 3), reference_transformation(0, 3), 0.1); + EXPECT_NEAR (transformation(1, 0), reference_transformation(1, 0), 0.1); + EXPECT_NEAR (transformation(1, 1), reference_transformation(1, 1), 0.1); + EXPECT_NEAR (transformation(1, 2), reference_transformation(1, 2), 0.1); + EXPECT_NEAR (transformation(1, 3), reference_transformation(1, 3), 0.1); + EXPECT_NEAR (transformation(2, 0), reference_transformation(2, 0), 0.1); + EXPECT_NEAR (transformation(2, 1), reference_transformation(2, 1), 0.1); + EXPECT_NEAR (transformation(2, 2), reference_transformation(2, 2), 0.1); + EXPECT_NEAR (transformation(2, 3), reference_transformation(2, 3), 0.1); + EXPECT_NEAR (transformation(3, 0), 0.0f, 1e-6); + EXPECT_NEAR (transformation(3, 1), 0.0f, 1e-6); + EXPECT_NEAR (transformation(3, 2), 0.0f, 1e-6); + EXPECT_NEAR (transformation(3, 3), 1.0f, 1e-6); } -#endif /* ---[ */ int From 3c77869e959ea0466867508b3218f630f08d5036 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 25 Aug 2023 14:02:03 +0200 Subject: [PATCH 114/288] Fix Eigen alignment problem when user project is compiled as C++17 or newer --- cmake/pcl_pclconfig.cmake | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/cmake/pcl_pclconfig.cmake b/cmake/pcl_pclconfig.cmake index 84a29ae0794..f0656e6ec3b 100644 --- a/cmake/pcl_pclconfig.cmake +++ b/cmake/pcl_pclconfig.cmake @@ -16,6 +16,13 @@ set(PCLCONFIG_SSE_DEFINITIONS "${SSE_DEFINITIONS}") set(PCLCONFIG_SSE_COMPILE_OPTIONS ${SSE_FLAGS}) set(PCLCONFIG_AVX_COMPILE_OPTIONS ${AVX_FLAGS}) +# Eigen has a custom mechanism to guarantee aligned memory (used for everything older than C++17, see Memory.h in the Eigen project) +# If PCL is compiled with C++14 and the user project is compiled with C++17, this will lead to problems (e.g. memory allocated with the custom mechanism but freed without it) +# Defining EIGEN_HAS_CXX17_OVERALIGN=0 forces Eigen in the user project to use Eigen's custom mechanism, even in C++17 and newer. +if(${CMAKE_CXX_STANDARD} LESS 17) + string(APPEND PCLCONFIG_SSE_DEFINITIONS " -DEIGEN_HAS_CXX17_OVERALIGN=0") +endif() + foreach(_ss ${PCL_SUBSYSTEMS_MODULES}) PCL_GET_SUBSYS_STATUS(_status ${_ss}) From 969d5d39b82e90cde2654dad414578175a631dd0 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Thu, 31 Aug 2023 05:21:26 -0700 Subject: [PATCH 115/288] Part E of transition to support modernize-use-default-member-init (#5782) * Part E of transition to support modernize-use-default-member-init * Added default constructor to IteratorState * Fixed formatting flagged by CI * Fixed further CI escapes in format, tidy * Fixed more clang-tidy, clang-format issues from CI * Fixed two more CI escapes * Addressed code review comments * Fixed yet more clang-format issues * Addressed further review comments --- features/include/pcl/features/brisk_2d.h | 32 +++++++-------- .../include/pcl/features/impl/brisk_2d.hpp | 15 ++----- .../pcl/geometry/organized_index_iterator.h | 6 +-- io/include/pcl/io/ply_io.h | 9 ----- keypoints/include/pcl/keypoints/agast_2d.h | 12 +++--- keypoints/include/pcl/keypoints/brisk_2d.h | 7 ++-- keypoints/include/pcl/keypoints/harris_3d.h | 9 ++--- keypoints/include/pcl/keypoints/harris_6d.h | 12 +++--- keypoints/include/pcl/keypoints/iss_3d.h | 27 +++++-------- keypoints/include/pcl/keypoints/keypoint.h | 12 +++--- .../include/pcl/keypoints/narf_keypoint.h | 40 ++++++++----------- .../include/pcl/keypoints/sift_keypoint.h | 12 +++--- .../keypoints/smoothed_surfaces_keypoint.h | 11 ++--- keypoints/include/pcl/keypoints/susan.h | 6 +-- .../include/pcl/keypoints/trajkovic_2d.h | 3 +- .../include/pcl/keypoints/trajkovic_3d.h | 3 +- keypoints/src/brisk_2d.cpp | 2 - keypoints/src/narf_keypoint.cpp | 3 +- ml/include/pcl/ml/densecrf.h | 2 +- .../pcl/ml/dt/decision_forest_trainer.h | 2 +- ml/include/pcl/ml/dt/decision_tree_trainer.h | 25 ++++++------ .../ml/impl/dt/decision_forest_trainer.hpp | 2 +- .../pcl/ml/impl/dt/decision_tree_trainer.hpp | 13 +----- ml/include/pcl/ml/point_xy_32f.h | 6 +-- ml/include/pcl/ml/point_xy_32i.h | 6 +-- ml/include/pcl/ml/svm.h | 4 +- ml/include/pcl/ml/svm_wrapper.h | 33 ++++++++------- ml/src/densecrf.cpp | 3 +- .../pcl/octree/impl/octree2buf_base.hpp | 9 +---- .../include/pcl/octree/impl/octree_base.hpp | 7 +--- .../pcl/octree/impl/octree_pointcloud.hpp | 6 --- octree/include/pcl/octree/octree2buf_base.h | 14 +++---- octree/include/pcl/octree/octree_base.h | 10 ++--- octree/include/pcl/octree/octree_iterator.h | 10 +++-- octree/include/pcl/octree/octree_key.h | 3 +- octree/include/pcl/octree/octree_pointcloud.h | 12 +++--- .../pcl/octree/octree_pointcloud_density.h | 4 +- .../include/pcl/outofcore/impl/lru_cache.hpp | 4 +- .../impl/outofcore_depth_first_iterator.hpp | 4 +- .../outofcore_depth_first_iterator.h | 2 +- .../pcl/outofcore/outofcore_node_data.h | 2 +- .../outofcore/visualization/outofcore_cloud.h | 10 ++--- outofcore/src/outofcore_node_data.cpp | 5 +-- .../src/visualization/outofcore_cloud.cpp | 3 +- 44 files changed, 170 insertions(+), 252 deletions(-) diff --git a/features/include/pcl/features/brisk_2d.h b/features/include/pcl/features/brisk_2d.h index 61433878c03..05950d6646c 100644 --- a/features/include/pcl/features/brisk_2d.h +++ b/features/include/pcl/features/brisk_2d.h @@ -161,13 +161,13 @@ namespace pcl const float max_x, const float max_y, const KeypointT& key_pt); /** \brief Specifies whether rotation invariance is enabled. */ - bool rotation_invariance_enabled_; + bool rotation_invariance_enabled_{true}; /** \brief Specifies whether scale invariance is enabled. */ - bool scale_invariance_enabled_; + bool scale_invariance_enabled_{true}; /** \brief Specifies the scale of the pattern. */ - const float pattern_scale_; + const float pattern_scale_{1.0f}; /** \brief the input cloud. */ PointCloudInTConstPtr input_cloud_; @@ -176,7 +176,7 @@ namespace pcl KeypointPointCloudTPtr keypoints_; // TODO: set - float scale_range_; + float scale_range_{0.0f}; // Some helper structures for the Brisk pattern representation struct BriskPatternPoint @@ -214,41 +214,41 @@ namespace pcl BriskPatternPoint* pattern_points_; /** Total number of collocation points. */ - unsigned int points_; + unsigned int points_{0u}; /** Discretization of the rotation look-up. */ - const unsigned int n_rot_; + const unsigned int n_rot_{1024}; /** Lists the scaling per scale index [scale]. */ - float* scale_list_; + float* scale_list_{nullptr}; /** Lists the total pattern size per scale index [scale]. */ - unsigned int* size_list_; + unsigned int* size_list_{nullptr}; /** Scales discretization. */ - const unsigned int scales_; + const unsigned int scales_{64}; /** Span of sizes 40->4 Octaves - else, this needs to be adjusted... */ - const float scalerange_; + const float scalerange_{30}; // general - const float basic_size_; + const float basic_size_{12.0}; // pairs /** Number of uchars the descriptor consists of. */ - int strings_; + int strings_{0}; /** Short pair maximum distance. */ - float d_max_; + float d_max_{0.0f}; /** Long pair maximum distance. */ - float d_min_; + float d_min_{0.0f}; /** d<_d_max. */ BriskShortPair* short_pairs_; /** d>_d_min. */ BriskLongPair* long_pairs_; /** Number of short pairs. */ - unsigned int no_short_pairs_; + unsigned int no_short_pairs_{0}; /** Number of long pairs. */ - unsigned int no_long_pairs_; + unsigned int no_long_pairs_{0}; /** \brief Intensity field accessor. */ IntensityT intensity_; diff --git a/features/include/pcl/features/impl/brisk_2d.hpp b/features/include/pcl/features/impl/brisk_2d.hpp index d067e0c5608..8d22f39bd87 100644 --- a/features/include/pcl/features/impl/brisk_2d.hpp +++ b/features/include/pcl/features/impl/brisk_2d.hpp @@ -47,17 +47,10 @@ namespace pcl template BRISK2DEstimation::BRISK2DEstimation () - : rotation_invariance_enabled_ (true) - , scale_invariance_enabled_ (true) - , pattern_scale_ (1.0f) - , input_cloud_ (), keypoints_ (), scale_range_ (), pattern_points_ (), points_ () - , n_rot_ (1024), scale_list_ (nullptr), size_list_ (nullptr) - , scales_ (64) - , scalerange_ (30) - , basic_size_ (12.0) - , strings_ (0), d_max_ (0.0f), d_min_ (0.0f), short_pairs_ (), long_pairs_ () - , no_short_pairs_ (0), no_long_pairs_ (0) - , intensity_ () + : + input_cloud_ (), keypoints_ (), pattern_points_ (), + short_pairs_ (), long_pairs_ () + , intensity_ () , name_ ("BRISK2Destimation") { // Since we do not assume pattern_scale_ should be changed by the user, we diff --git a/geometry/include/pcl/geometry/organized_index_iterator.h b/geometry/include/pcl/geometry/organized_index_iterator.h index e887e997b7f..967bff362dd 100644 --- a/geometry/include/pcl/geometry/organized_index_iterator.h +++ b/geometry/include/pcl/geometry/organized_index_iterator.h @@ -101,7 +101,7 @@ class OrganizedIndexIterator { unsigned width_; /** \brief the index of the current pixel/point*/ - unsigned index_; + unsigned index_{0}; }; //////////////////////////////////////////////////////////////////////////////// @@ -109,9 +109,7 @@ class OrganizedIndexIterator { //////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////// -inline OrganizedIndexIterator::OrganizedIndexIterator(unsigned width) -: width_(width), index_(0) -{} +inline OrganizedIndexIterator::OrganizedIndexIterator(unsigned width) : width_(width) {} //////////////////////////////////////////////////////////////////////////////// inline OrganizedIndexIterator::~OrganizedIndexIterator() = default; diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 65a247a0b2a..86e540771ae 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -94,15 +94,6 @@ namespace pcl PLYReader (const PLYReader &p) : origin_ (Eigen::Vector4f::Zero ()) , orientation_ (Eigen::Matrix3f::Identity ()) - , cloud_ () - , vertex_count_ (0) - , vertex_offset_before_ (0) - , range_grid_ (nullptr) - , rgb_offset_before_ (0) - , do_resize_ (false) - , polygons_ (nullptr) - , r_(0), g_(0), b_(0) - , a_(0), rgba_(0) { *this = p; } diff --git a/keypoints/include/pcl/keypoints/agast_2d.h b/keypoints/include/pcl/keypoints/agast_2d.h index e9e139fd048..5346e75c448 100644 --- a/keypoints/include/pcl/keypoints/agast_2d.h +++ b/keypoints/include/pcl/keypoints/agast_2d.h @@ -570,10 +570,8 @@ namespace pcl /** \brief Constructor */ AgastKeypoint2DBase () - : threshold_ (10) - , apply_non_max_suppression_ (true) - , bmax_ (255) - , nr_max_keypoints_ (std::numeric_limits::max ()) + : + nr_max_keypoints_ (std::numeric_limits::max ()) { k_ = 1; } @@ -673,13 +671,13 @@ namespace pcl IntensityT intensity_; /** \brief Threshold for corner detection. */ - double threshold_; + double threshold_{10}; /** \brief Determines whether non-max-suppression is activated. */ - bool apply_non_max_suppression_; + bool apply_non_max_suppression_{true}; /** \brief Max image value. */ - double bmax_; + double bmax_{255}; /** \brief The Agast detector to use. */ AgastDetectorPtr detector_; diff --git a/keypoints/include/pcl/keypoints/brisk_2d.h b/keypoints/include/pcl/keypoints/brisk_2d.h index e32fc258530..e530e6a5669 100644 --- a/keypoints/include/pcl/keypoints/brisk_2d.h +++ b/keypoints/include/pcl/keypoints/brisk_2d.h @@ -90,7 +90,6 @@ namespace pcl BriskKeypoint2D (int octaves = 4, int threshold = 60) : threshold_ (threshold) , octaves_ (octaves) - , remove_invalid_3D_keypoints_ (false) { k_ = 1; name_ = "BriskKeypoint2D"; @@ -232,7 +231,7 @@ namespace pcl /** \brief Specify whether the keypoints that do not have a valid 3D position are * kept (false) or removed (true). */ - bool remove_invalid_3D_keypoints_; + bool remove_invalid_3D_keypoints_{false}; }; //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -473,8 +472,8 @@ namespace pcl std::uint8_t safe_threshold_; // some constant parameters - float safety_factor_; - float basic_size_; + float safety_factor_{1.0}; + float basic_size_{12.0}; }; } // namespace brisk } // namespace keypoints diff --git a/keypoints/include/pcl/keypoints/harris_3d.h b/keypoints/include/pcl/keypoints/harris_3d.h index 88f8e637155..9ba689a0b57 100644 --- a/keypoints/include/pcl/keypoints/harris_3d.h +++ b/keypoints/include/pcl/keypoints/harris_3d.h @@ -84,10 +84,7 @@ namespace pcl */ HarrisKeypoint3D (ResponseMethod method = HARRIS, float radius = 0.01f, float threshold = 0.0f) : threshold_ (threshold) - , refine_ (true) - , nonmax_ (true) , method_ (method) - , threads_ (0) { name_ = "HarrisKeypoint3D"; search_radius_ = radius; @@ -171,11 +168,11 @@ namespace pcl void calculateNormalCovar (const pcl::Indices& neighbors, float* coefficients) const; private: float threshold_; - bool refine_; - bool nonmax_; + bool refine_{true}; + bool nonmax_{true}; ResponseMethod method_; PointCloudNConstPtr normals_; - unsigned int threads_; + unsigned int threads_{0}; }; } diff --git a/keypoints/include/pcl/keypoints/harris_6d.h b/keypoints/include/pcl/keypoints/harris_6d.h index e2ba39535f4..8b3b3ad880b 100644 --- a/keypoints/include/pcl/keypoints/harris_6d.h +++ b/keypoints/include/pcl/keypoints/harris_6d.h @@ -74,10 +74,8 @@ namespace pcl */ HarrisKeypoint6D (float radius = 0.01, float threshold = 0.0) : threshold_ (threshold) - , refine_ (true) - , nonmax_ (true) - , threads_ (0) - , normals_ (new pcl::PointCloud) + , + normals_ (new pcl::PointCloud) , intensity_gradients_ (new pcl::PointCloud) { name_ = "HarrisKeypoint6D"; @@ -129,9 +127,9 @@ namespace pcl void calculateCombinedCovar (const pcl::Indices& neighbors, float* coefficients) const; private: float threshold_; - bool refine_; - bool nonmax_; - unsigned int threads_; + bool refine_{true}; + bool nonmax_{true}; + unsigned int threads_{0}; typename pcl::PointCloud::Ptr normals_; pcl::PointCloud::Ptr intensity_gradients_; } ; diff --git a/keypoints/include/pcl/keypoints/iss_3d.h b/keypoints/include/pcl/keypoints/iss_3d.h index 24ebdbbddda..de5017f957c 100644 --- a/keypoints/include/pcl/keypoints/iss_3d.h +++ b/keypoints/include/pcl/keypoints/iss_3d.h @@ -111,17 +111,8 @@ namespace pcl */ ISSKeypoint3D (double salient_radius = 0.0001) : salient_radius_ (salient_radius) - , non_max_radius_ (0.0) - , normal_radius_ (0.0) - , border_radius_ (0.0) - , gamma_21_ (0.975) - , gamma_32_ (0.975) - , third_eigen_value_ (nullptr) - , edge_points_ (nullptr) - , min_neighbors_ (5) , normals_ (new pcl::PointCloud) , angle_threshold_ (static_cast (M_PI) / 2.0f) - , threads_ (0) { name_ = "ISSKeypoint3D"; search_radius_ = salient_radius_; @@ -236,28 +227,28 @@ namespace pcl double salient_radius_; /** \brief The non maxima suppression radius. */ - double non_max_radius_; + double non_max_radius_{0.0}; /** \brief The radius used to compute the normals of the input cloud. */ - double normal_radius_; + double normal_radius_{0.0}; /** \brief The radius used to compute the boundary points of the input cloud. */ - double border_radius_; + double border_radius_{0.0}; /** \brief The upper bound on the ratio between the second and the first eigenvalue returned by the EVD. */ - double gamma_21_; + double gamma_21_{0.975}; /** \brief The upper bound on the ratio between the third and the second eigenvalue returned by the EVD. */ - double gamma_32_; + double gamma_32_{0.975}; /** \brief Store the third eigen value associated to each point in the input cloud. */ - double *third_eigen_value_; + double *third_eigen_value_{nullptr}; /** \brief Store the information about the boundary points of the input cloud. */ - bool *edge_points_; + bool *edge_points_{nullptr}; /** \brief Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. */ - int min_neighbors_; + int min_neighbors_{5}; /** \brief The cloud of normals related to the input surface. */ PointCloudNConstPtr normals_; @@ -266,7 +257,7 @@ namespace pcl float angle_threshold_; /** \brief The number of threads that has to be used by the scheduler. */ - unsigned int threads_; + unsigned int threads_{0}; }; diff --git a/keypoints/include/pcl/keypoints/keypoint.h b/keypoints/include/pcl/keypoints/keypoint.h index 56f96c3065a..655006a0897 100644 --- a/keypoints/include/pcl/keypoints/keypoint.h +++ b/keypoints/include/pcl/keypoints/keypoint.h @@ -76,10 +76,8 @@ namespace pcl BaseClass (), search_method_surface_ (), surface_ (), - tree_ (), - search_parameter_ (0), - search_radius_ (0), - k_ (0) + tree_ () + {}; /** \brief Empty destructor */ @@ -181,13 +179,13 @@ namespace pcl KdTreePtr tree_; /** \brief The actual search parameter (casted from either \a search_radius_ or \a k_). */ - double search_parameter_; + double search_parameter_{0}; /** \brief The nearest neighbors search radius for each point. */ - double search_radius_; + double search_radius_{0}; /** \brief The number of K nearest neighbors to use for each point. */ - int k_; + int k_{0}; /** \brief Indices of the keypoints in the input cloud. */ pcl::PointIndicesPtr keypoints_indices_; diff --git a/keypoints/include/pcl/keypoints/narf_keypoint.h b/keypoints/include/pcl/keypoints/narf_keypoint.h index d9a4121afb2..c5034d16a98 100644 --- a/keypoints/include/pcl/keypoints/narf_keypoint.h +++ b/keypoints/include/pcl/keypoints/narf_keypoint.h @@ -72,46 +72,40 @@ class PCL_EXPORTS NarfKeypoint : public Keypoint //! Parameters used in this class struct Parameters { - Parameters() : support_size(-1.0f), max_no_of_interest_points(-1), min_distance_between_interest_points(0.25f), - optimal_distance_to_high_surface_change(0.25), min_interest_value(0.45f), - min_surface_change_score(0.2f), optimal_range_image_patch_size(10), - distance_for_additional_points(0.0f), add_points_on_straight_edges(false), - do_non_maximum_suppression(true), no_of_polynomial_approximations_per_point(false), - max_no_of_threads(1), use_recursive_scale_reduction(false), - calculate_sparse_interest_image(true) {} + Parameters() = default; - float support_size; //!< This defines the area 'covered' by an interest point (in meters) - int max_no_of_interest_points; //!< The maximum number of interest points that will be returned - float min_distance_between_interest_points; /**< Minimum distance between maximas + float support_size{-1.0f}; //!< This defines the area 'covered' by an interest point (in meters) + int max_no_of_interest_points{-1}; //!< The maximum number of interest points that will be returned + float min_distance_between_interest_points{0.25f}; /**< Minimum distance between maximas * (this is a factor for support_size, i.e. the distance is * min_distance_between_interest_points*support_size) */ - float optimal_distance_to_high_surface_change; /**< The distance we want keep between keypoints and areas + float optimal_distance_to_high_surface_change{0.25}; /**< The distance we want keep between keypoints and areas * of high surface change * (this is a factor for support_size, i.e., the distance is * optimal_distance_to_high_surface_change*support_size) */ - float min_interest_value; //!< The minimum value to consider a point as an interest point - float min_surface_change_score; //!< The minimum value of the surface change score to consider a point - int optimal_range_image_patch_size; /**< The size (in pixels) of the image patches from which the interest value + float min_interest_value{0.45f}; //!< The minimum value to consider a point as an interest point + float min_surface_change_score{0.2f}; //!< The minimum value of the surface change score to consider a point + int optimal_range_image_patch_size{10}; /**< The size (in pixels) of the image patches from which the interest value * should be computed. This influences, which range image is selected from * the scale space to compute the interest value of a pixel at a certain * distance. */ // TODO: - float distance_for_additional_points; /**< All points in this distance to a found maximum, that + float distance_for_additional_points{0.0f}; /**< All points in this distance to a found maximum, that * are above min_interest_value are also added as interest points * (this is a factor for support_size, i.e. the distance is * distance_for_additional_points*support_size) */ - bool add_points_on_straight_edges; /**< If this is set to true, there will also be interest points on + bool add_points_on_straight_edges{false}; /**< If this is set to true, there will also be interest points on * straight edges, e.g., just indicating an area of high surface change */ - bool do_non_maximum_suppression; /**< If this is set to false there will be much more points + bool do_non_maximum_suppression{true}; /**< If this is set to false there will be much more points * (can be used to spread points over the whole scene * (combined with a low min_interest_value)) */ - bool no_of_polynomial_approximations_per_point; /**< If this is >0, the exact position of the interest point is + bool no_of_polynomial_approximations_per_point{false}; /**< If this is >0, the exact position of the interest point is determined using bivariate polynomial approximations of the interest values of the area. */ - int max_no_of_threads; //!< The maximum number of threads this code is allowed to use with OPNEMP - bool use_recursive_scale_reduction; /**< Try to decrease runtime by extracting interest points at lower reolution + int max_no_of_threads{1}; //!< The maximum number of threads this code is allowed to use with OPNEMP + bool use_recursive_scale_reduction{false}; /**< Try to decrease runtime by extracting interest points at lower reolution * in areas that contain enough points, i.e., have lower range. */ - bool calculate_sparse_interest_image; /**< Use some heuristics to decide which areas of the interest image + bool calculate_sparse_interest_image{true}; /**< Use some heuristics to decide which areas of the interest image can be left out to improve the runtime. */ }; @@ -182,8 +176,8 @@ class PCL_EXPORTS NarfKeypoint : public Keypoint using BaseClass::name_; RangeImageBorderExtractor* range_image_border_extractor_; Parameters parameters_; - float* interest_image_; - ::pcl::PointCloud* interest_points_; + float* interest_image_{nullptr}; + ::pcl::PointCloud* interest_points_{nullptr}; std::vector is_interest_point_image_; std::vector range_image_scale_space_; std::vector border_extractor_scale_space_; diff --git a/keypoints/include/pcl/keypoints/sift_keypoint.h b/keypoints/include/pcl/keypoints/sift_keypoint.h index 688d87d4020..5077096343f 100644 --- a/keypoints/include/pcl/keypoints/sift_keypoint.h +++ b/keypoints/include/pcl/keypoints/sift_keypoint.h @@ -108,8 +108,8 @@ namespace pcl using Keypoint::initCompute; /** \brief Empty constructor. */ - SIFTKeypoint () : min_scale_ (0.0), nr_octaves_ (0), nr_scales_per_octave_ (0), - min_contrast_ (-std::numeric_limits::max ()), scale_idx_ (-1), + SIFTKeypoint () : + min_contrast_ (-std::numeric_limits::max ()), getFieldValue_ () { name_ = "SIFTKeypoint"; @@ -178,20 +178,20 @@ namespace pcl /** \brief The standard deviation of the smallest scale in the scale space.*/ - float min_scale_; + float min_scale_{0.0}; /** \brief The number of octaves (i.e. doublings of scale) over which to search for keypoints.*/ - int nr_octaves_; + int nr_octaves_{0}; /** \brief The number of scales to be computed for each octave.*/ - int nr_scales_per_octave_; + int nr_scales_per_octave_{0}; /** \brief The minimum contrast required for detection.*/ float min_contrast_; /** \brief Set to a value different than -1 if the output cloud has a "scale" field and we have to save * the keypoints scales. */ - int scale_idx_; + int scale_idx_{-1}; /** \brief The list of fields present in the output point cloud data. */ std::vector out_fields_; diff --git a/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h b/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h index bc021967d32..cc9759530a6 100644 --- a/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h +++ b/keypoints/include/pcl/keypoints/smoothed_surfaces_keypoint.h @@ -72,13 +72,10 @@ namespace pcl SmoothedSurfacesKeypoint () : Keypoint (), - neighborhood_constant_ (0.5f), clouds_ (), cloud_normals_ (), cloud_trees_ (), - normals_ (), - input_scale_ (0.0f), - input_index_ () + normals_ () { name_ = "SmoothedSurfacesKeypoint"; @@ -116,14 +113,14 @@ namespace pcl initCompute () override; private: - float neighborhood_constant_; + float neighborhood_constant_{0.5f}; std::vector clouds_; std::vector cloud_normals_; std::vector cloud_trees_; PointCloudNTConstPtr normals_; std::vector > scales_; - float input_scale_; - std::size_t input_index_; + float input_scale_{0.0f}; + std::size_t input_index_{0u}; static bool compareScalesFunction (const std::pair &a, diff --git a/keypoints/include/pcl/keypoints/susan.h b/keypoints/include/pcl/keypoints/susan.h index f11199b90aa..1b767bd2e03 100644 --- a/keypoints/include/pcl/keypoints/susan.h +++ b/keypoints/include/pcl/keypoints/susan.h @@ -93,8 +93,6 @@ namespace pcl , angular_threshold_ (angular_threshold) , intensity_threshold_ (intensity_threshold) , normals_ (new pcl::PointCloud) - , threads_ (0) - , label_idx_ (-1) { name_ = "SUSANKeypoint"; search_radius_ = radius; @@ -182,7 +180,7 @@ namespace pcl float intensity_threshold_; float tolerance_; PointCloudNConstPtr normals_; - unsigned int threads_; + unsigned int threads_{0}; bool geometric_validation_; bool nonmax_; /// intensity field accessor @@ -190,7 +188,7 @@ namespace pcl /** \brief Set to a value different than -1 if the output cloud has a "label" field and we have * to save the keypoints indices. */ - int label_idx_; + int label_idx_{-1}; /** \brief The list of fields present in the output point cloud data. */ std::vector out_fields_; pcl::common::IntensityFieldAccessor intensity_out_; diff --git a/keypoints/include/pcl/keypoints/trajkovic_2d.h b/keypoints/include/pcl/keypoints/trajkovic_2d.h index 7434f16a052..9baf1adb7b0 100644 --- a/keypoints/include/pcl/keypoints/trajkovic_2d.h +++ b/keypoints/include/pcl/keypoints/trajkovic_2d.h @@ -81,7 +81,6 @@ namespace pcl , window_size_ (window_size) , first_threshold_ (first_threshold) , second_threshold_ (second_threshold) - , threads_ (1) { name_ = "TrajkovicKeypoint2D"; } @@ -164,7 +163,7 @@ namespace pcl /// second threshold for corner evaluation float second_threshold_; /// number of threads to be used - unsigned int threads_; + unsigned int threads_{1}; /// point cloud response pcl::PointCloud::Ptr response_; }; diff --git a/keypoints/include/pcl/keypoints/trajkovic_3d.h b/keypoints/include/pcl/keypoints/trajkovic_3d.h index fe9f3b2d84f..1758c672387 100644 --- a/keypoints/include/pcl/keypoints/trajkovic_3d.h +++ b/keypoints/include/pcl/keypoints/trajkovic_3d.h @@ -85,7 +85,6 @@ namespace pcl , window_size_ (window_size) , first_threshold_ (first_threshold) , second_threshold_ (second_threshold) - , threads_ (1) { name_ = "TrajkovicKeypoint3D"; } @@ -204,7 +203,7 @@ namespace pcl /// second threshold for corner evaluation float second_threshold_; /// number of threads to be used - unsigned int threads_; + unsigned int threads_{1}; /// point cloud normals NormalsConstPtr normals_; /// point cloud response diff --git a/keypoints/src/brisk_2d.cpp b/keypoints/src/brisk_2d.cpp index c836dec780b..4b3d52c9031 100644 --- a/keypoints/src/brisk_2d.cpp +++ b/keypoints/src/brisk_2d.cpp @@ -54,8 +54,6 @@ const int pcl::keypoints::brisk::Layer::CommonParams::TWOTHIRDSAMPLE = 1; ///////////////////////////////////////////////////////////////////////////////////////// // construct telling the octaves number: pcl::keypoints::brisk::ScaleSpace::ScaleSpace (int octaves) - : safety_factor_ (1.0) - , basic_size_ (12.0) { if (octaves == 0) layers_ = 1; diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index 1c51db55c30..088bcbceca6 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -45,8 +45,7 @@ namespace pcl { ///////////////////////////////////////////////////////////////////////// -NarfKeypoint::NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor, float support_size) : - interest_image_ (nullptr), interest_points_ (nullptr) +NarfKeypoint::NarfKeypoint (RangeImageBorderExtractor* range_image_border_extractor, float support_size) { name_ = "NarfKeypoint"; clearData (); diff --git a/ml/include/pcl/ml/densecrf.h b/ml/include/pcl/ml/densecrf.h index 70d56650bbc..c93d01ac422 100644 --- a/ml/include/pcl/ml/densecrf.h +++ b/ml/include/pcl/ml/densecrf.h @@ -155,7 +155,7 @@ class PCL_EXPORTS DenseCrf { std::vector pairwise_potential_; /** Input types */ - bool xyz_, rgb_, normal_; + bool xyz_{false}, rgb_{false}, normal_{false}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/ml/include/pcl/ml/dt/decision_forest_trainer.h b/ml/include/pcl/ml/dt/decision_forest_trainer.h index b177198622e..135a90352df 100644 --- a/ml/include/pcl/ml/dt/decision_forest_trainer.h +++ b/ml/include/pcl/ml/dt/decision_forest_trainer.h @@ -211,7 +211,7 @@ class PCL_EXPORTS DecisionForestTrainer { private: /** The number of trees to train. */ - std::size_t num_of_trees_to_train_; + std::size_t num_of_trees_to_train_{1}; /** The trainer for the decision trees of the forest. */ pcl::DecisionTreeTrainer diff --git a/ml/include/pcl/ml/dt/decision_tree_trainer.h b/ml/include/pcl/ml/dt/decision_tree_trainer.h index 35650887cf3..312aa2200c5 100644 --- a/ml/include/pcl/ml/dt/decision_tree_trainer.h +++ b/ml/include/pcl/ml/dt/decision_tree_trainer.h @@ -229,28 +229,29 @@ class PCL_EXPORTS DecisionTreeTrainer { private: /** Maximum depth of the learned tree. */ - std::size_t max_tree_depth_; + std::size_t max_tree_depth_{15}; /** Number of features used to find optimal decision features. */ - std::size_t num_of_features_; + std::size_t num_of_features_{1000}; /** Number of thresholds. */ - std::size_t num_of_thresholds_; + std::size_t num_of_thresholds_{10}; /** FeatureHandler instance, responsible for creating and evaluating features. */ - pcl::FeatureHandler* feature_handler_; + pcl::FeatureHandler* feature_handler_{nullptr}; /** StatsEstimator instance, responsible for gathering stats about a node. */ - pcl::StatsEstimator* stats_estimator_; + pcl::StatsEstimator* stats_estimator_{ + nullptr}; /** The training data set. */ - DataSet data_set_; + DataSet data_set_{}; /** The label data. */ - std::vector label_data_; + std::vector label_data_{}; /** The example data. */ - std::vector examples_; + std::vector examples_{}; /** Minimum number of examples to split a node. */ - std::size_t min_examples_for_split_; + std::size_t min_examples_for_split_{0u}; /** Thresholds to be used instead of generating uniform distributed thresholds. */ - std::vector thresholds_; + std::vector thresholds_{}; /** The data provider which is called before training a specific tree, if pointer is * NULL, then data_set_ is used. */ typename pcl::DecisionTreeTrainerDataProvider::Ptr - decision_tree_trainer_data_provider_; + decision_tree_trainer_data_provider_{nullptr}; /** If true, random features are generated at each node, otherwise, at start of * training the tree */ - bool random_features_at_split_node_; + bool random_features_at_split_node_{false}; }; } // namespace pcl diff --git a/ml/include/pcl/ml/impl/dt/decision_forest_trainer.hpp b/ml/include/pcl/ml/impl/dt/decision_forest_trainer.hpp index a7657651bc8..11094206040 100644 --- a/ml/include/pcl/ml/impl/dt/decision_forest_trainer.hpp +++ b/ml/include/pcl/ml/impl/dt/decision_forest_trainer.hpp @@ -46,7 +46,7 @@ template DecisionForestTrainer:: DecisionForestTrainer() -: num_of_trees_to_train_(1), decision_tree_trainer_() +: decision_tree_trainer_() {} template DecisionTreeTrainer:: - DecisionTreeTrainer() -: max_tree_depth_(15) -, num_of_features_(1000) -, num_of_thresholds_(10) -, feature_handler_(nullptr) -, stats_estimator_(nullptr) -, data_set_() -, label_data_() -, examples_() -, decision_tree_trainer_data_provider_() -, random_features_at_split_node_(false) -{} + DecisionTreeTrainer() = default; template > prediction_; // It stores the resulting prediction. /** It scales the input dataset using the model information. */ @@ -395,10 +397,7 @@ class SVMClassify : public SVM { public: /** Constructor. */ - SVMClassify() : model_extern_copied_(false), predict_probability_(false) - { - class_name_ = "SvmClassify"; - } + SVMClassify() { class_name_ = "SvmClassify"; } /** Destructor. */ ~SVMClassify() diff --git a/ml/src/densecrf.cpp b/ml/src/densecrf.cpp index d1cf11a7242..e0dd25d7860 100644 --- a/ml/src/densecrf.cpp +++ b/ml/src/densecrf.cpp @@ -39,8 +39,7 @@ #include -pcl::DenseCrf::DenseCrf(int N, int m) -: N_(N), M_(m), xyz_(false), rgb_(false), normal_(false) +pcl::DenseCrf::DenseCrf(int N, int m) : N_(N), M_(m) { current_.resize(N_ * M_, 0.0f); next_.resize(N_ * M_, 0.0f); diff --git a/octree/include/pcl/octree/impl/octree2buf_base.hpp b/octree/include/pcl/octree/impl/octree2buf_base.hpp index 5736f06bd6e..b91b03baf01 100644 --- a/octree/include/pcl/octree/impl/octree2buf_base.hpp +++ b/octree/include/pcl/octree/impl/octree2buf_base.hpp @@ -44,14 +44,7 @@ namespace octree { ////////////////////////////////////////////////////////////////////////////////////////////// template Octree2BufBase::Octree2BufBase() -: leaf_count_(0) -, branch_count_(1) -, root_node_(new BranchNode()) -, depth_mask_(0) -, buffer_selector_(0) -, tree_dirty_flag_(false) -, octree_depth_(0) -, dynamic_depth_enabled_(false) +: root_node_(new BranchNode()) {} ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/octree/include/pcl/octree/impl/octree_base.hpp b/octree/include/pcl/octree/impl/octree_base.hpp index 3d25960f650..92b0489ef1e 100644 --- a/octree/include/pcl/octree/impl/octree_base.hpp +++ b/octree/include/pcl/octree/impl/octree_base.hpp @@ -46,12 +46,7 @@ namespace octree { ////////////////////////////////////////////////////////////////////////////////////////////// template OctreeBase::OctreeBase() -: leaf_count_(0) -, branch_count_(1) -, root_node_(new BranchNode()) -, depth_mask_(0) -, octree_depth_(0) -, dynamic_depth_enabled_(false) +: root_node_(new BranchNode()) {} ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/octree/include/pcl/octree/impl/octree_pointcloud.hpp b/octree/include/pcl/octree/impl/octree_pointcloud.hpp index 6ba8d3aa3fe..ae370081059 100644 --- a/octree/include/pcl/octree/impl/octree_pointcloud.hpp +++ b/octree/include/pcl/octree/impl/octree_pointcloud.hpp @@ -55,16 +55,10 @@ pcl::octree::OctreePointCloud : OctreeT() , input_(PointCloudConstPtr()) , indices_(IndicesConstPtr()) -, epsilon_(0) , resolution_(resolution) -, min_x_(0.0f) , max_x_(resolution) -, min_y_(0.0f) , max_y_(resolution) -, min_z_(0.0f) , max_z_(resolution) -, bounding_box_defined_(false) -, max_objs_per_leaf_(0) { if (resolution <= 0.0) { PCL_THROW_EXCEPTION(InitFailedException, diff --git a/octree/include/pcl/octree/octree2buf_base.h b/octree/include/pcl/octree/octree2buf_base.h index 1589b0303b6..54963e8f57c 100644 --- a/octree/include/pcl/octree/octree2buf_base.h +++ b/octree/include/pcl/octree/octree2buf_base.h @@ -972,33 +972,33 @@ class Octree2BufBase { ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Amount of leaf nodes **/ - std::size_t leaf_count_; + std::size_t leaf_count_{0}; /** \brief Amount of branch nodes **/ - std::size_t branch_count_; + std::size_t branch_count_{1}; /** \brief Pointer to root branch node of octree **/ BranchNode* root_node_; /** \brief Depth mask based on octree depth **/ - uindex_t depth_mask_; + uindex_t depth_mask_{0}; /** \brief key range */ OctreeKey max_key_; /** \brief Currently active octree buffer **/ - unsigned char buffer_selector_; + unsigned char buffer_selector_{0}; /** \brief flags indicating if unused branches and leafs might exist in previous * buffer **/ - bool tree_dirty_flag_; + bool tree_dirty_flag_{false}; /** \brief Octree depth */ - uindex_t octree_depth_; + uindex_t octree_depth_{0}; /** \brief Enable dynamic_depth * \note Note that this parameter is ignored in octree2buf! */ - bool dynamic_depth_enabled_; + bool dynamic_depth_enabled_{false}; }; } // namespace octree } // namespace pcl diff --git a/octree/include/pcl/octree/octree_base.h b/octree/include/pcl/octree/octree_base.h index 7ee6ddabcbf..d0157eef64c 100644 --- a/octree/include/pcl/octree/octree_base.h +++ b/octree/include/pcl/octree/octree_base.h @@ -75,22 +75,22 @@ class OctreeBase { /////////////////////////////////////////////////////////////////////// /** \brief Amount of leaf nodes **/ - std::size_t leaf_count_; + std::size_t leaf_count_{0}; /** \brief Amount of branch nodes **/ - std::size_t branch_count_; + std::size_t branch_count_{1}; /** \brief Pointer to root branch node of octree **/ BranchNode* root_node_; /** \brief Depth mask based on octree depth **/ - uindex_t depth_mask_; + uindex_t depth_mask_{0}; /** \brief Octree depth */ - uindex_t octree_depth_; + uindex_t octree_depth_{0}; /** \brief Enable dynamic_depth **/ - bool dynamic_depth_enabled_; + bool dynamic_depth_enabled_{false}; /** \brief key range */ OctreeKey max_key_; diff --git a/octree/include/pcl/octree/octree_iterator.h b/octree/include/pcl/octree/octree_iterator.h index 9fa4330be97..e555039c1cd 100644 --- a/octree/include/pcl/octree/octree_iterator.h +++ b/octree/include/pcl/octree/octree_iterator.h @@ -57,9 +57,13 @@ namespace octree { // Octree iterator state pushed on stack/list struct IteratorState { - OctreeNode* node_; - OctreeKey key_; - uindex_t depth_; + OctreeNode* node_{nullptr}; + OctreeKey key_{}; + uindex_t depth_{0}; + IteratorState() = default; + IteratorState(OctreeNode* node, const OctreeKey& key, uindex_t depth) + : node_(node), key_(key), depth_(depth) + {} }; /** \brief @b Abstract octree iterator class diff --git a/octree/include/pcl/octree/octree_key.h b/octree/include/pcl/octree/octree_key.h index 86ac2533e5a..bf54471009d 100644 --- a/octree/include/pcl/octree/octree_key.h +++ b/octree/include/pcl/octree/octree_key.h @@ -143,7 +143,7 @@ class OctreeKey { static_cast(sizeof(uindex_t) * 8); // Indices addressing a voxel at (X, Y, Z) - + // NOLINTBEGIN(modernize-use-default-member-init) union { struct { uindex_t x; @@ -152,6 +152,7 @@ class OctreeKey { }; uindex_t key_[3]; }; + // NOLINTEND(modernize-use-default-member-init) }; } // namespace octree } // namespace pcl diff --git a/octree/include/pcl/octree/octree_pointcloud.h b/octree/include/pcl/octree/octree_pointcloud.h index 76fa60c656c..a1959dd51b4 100644 --- a/octree/include/pcl/octree/octree_pointcloud.h +++ b/octree/include/pcl/octree/octree_pointcloud.h @@ -583,28 +583,28 @@ class OctreePointCloud : public OctreeT { IndicesConstPtr indices_; /** \brief Epsilon precision (error bound) for nearest neighbors searches. */ - double epsilon_; + double epsilon_{0}; /** \brief Octree resolution. */ double resolution_; // Octree bounding box coordinates - double min_x_; + double min_x_{0.0f}; double max_x_; - double min_y_; + double min_y_{0.0f}; double max_y_; - double min_z_; + double min_z_{0.0f}; double max_z_; /** \brief Flag indicating if octree has defined bounding box. */ - bool bounding_box_defined_; + bool bounding_box_defined_{false}; /** \brief Amount of DataT objects per leafNode before expanding branch * \note zero indicates a fixed/maximum depth octree structure * **/ - std::size_t max_objs_per_leaf_; + std::size_t max_objs_per_leaf_{0}; }; } // namespace octree diff --git a/octree/include/pcl/octree/octree_pointcloud_density.h b/octree/include/pcl/octree/octree_pointcloud_density.h index 1a25343862f..87890a90d0a 100644 --- a/octree/include/pcl/octree/octree_pointcloud_density.h +++ b/octree/include/pcl/octree/octree_pointcloud_density.h @@ -50,7 +50,7 @@ namespace octree { class OctreePointCloudDensityContainer : public OctreeContainerBase { public: /** \brief Class initialization. */ - OctreePointCloudDensityContainer() : point_counter_(0) {} + OctreePointCloudDensityContainer() = default; /** \brief Empty class deconstructor. */ ~OctreePointCloudDensityContainer() override = default; @@ -99,7 +99,7 @@ class OctreePointCloudDensityContainer : public OctreeContainerBase { } private: - uindex_t point_counter_; + uindex_t point_counter_{0}; }; /** \brief @b Octree pointcloud density class diff --git a/outofcore/include/pcl/outofcore/impl/lru_cache.hpp b/outofcore/include/pcl/outofcore/impl/lru_cache.hpp index c24b090b940..9bdef7920fd 100644 --- a/outofcore/include/pcl/outofcore/impl/lru_cache.hpp +++ b/outofcore/include/pcl/outofcore/impl/lru_cache.hpp @@ -38,7 +38,7 @@ class LRUCache using CacheIterator = typename Cache::iterator; LRUCache (std::size_t c) : - capacity_ (c), size_ (0) + capacity_ (c) { assert(capacity_ != 0); } @@ -169,7 +169,7 @@ class LRUCache std::size_t capacity_; // Current cache size in kilobytes - std::size_t size_; + std::size_t size_{0}; // LRU key index LRU[0] ... MRU[N] KeyIndex key_index_; diff --git a/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp b/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp index 82d88c1a0bd..a7d15386619 100644 --- a/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp +++ b/outofcore/include/pcl/outofcore/impl/outofcore_depth_first_iterator.hpp @@ -47,8 +47,8 @@ namespace pcl template OutofcoreDepthFirstIterator::OutofcoreDepthFirstIterator (OutofcoreOctreeBase& octree_arg) : OutofcoreIteratorBase (octree_arg) - , currentChildIdx_ (0) - , stack_ (0) + , + stack_ (0) { stack_.reserve (this->octree_.getTreeDepth ()); OutofcoreIteratorBase::reset (); diff --git a/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h b/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h index 5d5210cd3c5..fec59893f23 100644 --- a/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h +++ b/outofcore/include/pcl/outofcore/outofcore_depth_first_iterator.h @@ -80,7 +80,7 @@ namespace pcl skipChildVoxels (); protected: - unsigned char currentChildIdx_; + unsigned char currentChildIdx_{0}; std::vector > stack_; }; } diff --git a/outofcore/include/pcl/outofcore/outofcore_node_data.h b/outofcore/include/pcl/outofcore/outofcore_node_data.h index 2627436e7e4..09a85876e83 100644 --- a/outofcore/include/pcl/outofcore/outofcore_node_data.h +++ b/outofcore/include/pcl/outofcore/outofcore_node_data.h @@ -176,7 +176,7 @@ namespace pcl /** \brief Metadata (JSON) file pathname (oct_idx extension JSON file) */ boost::filesystem::path metadata_filename_; /** \brief Outofcore library version identifier */ - int outofcore_version_; + int outofcore_version_{0}; /** \brief Computes the midpoint; used when bounding box is changed */ inline void diff --git a/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h b/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h index fde2b1773fc..69d8edf606f 100644 --- a/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h +++ b/outofcore/include/pcl/outofcore/visualization/outofcore_cloud.h @@ -265,15 +265,15 @@ class OutofcoreCloud : public Object // ----------------------------------------------------------------------------- OctreeDiskPtr octree_; - std::uint64_t display_depth_; - std::uint64_t points_loaded_; - std::uint64_t data_loaded_; + std::uint64_t display_depth_{1}; + std::uint64_t points_loaded_{0}; + std::uint64_t data_loaded_{0}; Eigen::Vector3d bbox_min_, bbox_max_; - Camera *render_camera_; + Camera *render_camera_{nullptr}; - int lod_pixel_threshold_; + int lod_pixel_threshold_{10000}; vtkSmartPointer voxel_actor_; diff --git a/outofcore/src/outofcore_node_data.cpp b/outofcore/src/outofcore_node_data.cpp index 54b9c6949a3..cb2dcc770ff 100644 --- a/outofcore/src/outofcore_node_data.cpp +++ b/outofcore/src/outofcore_node_data.cpp @@ -53,10 +53,7 @@ namespace pcl namespace outofcore { - OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata () - : outofcore_version_ () - { - } + OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata () = default; //////////////////////////////////////////////////////////////////////////////// diff --git a/outofcore/src/visualization/outofcore_cloud.cpp b/outofcore/src/visualization/outofcore_cloud.cpp index 8665640b67e..8d3fcf018d2 100644 --- a/outofcore/src/visualization/outofcore_cloud.cpp +++ b/outofcore/src/visualization/outofcore_cloud.cpp @@ -1,4 +1,3 @@ -// PCL #include #include @@ -105,7 +104,7 @@ OutofcoreCloud::pcdReaderThread () // Operators // ----------------------------------------------------------------------------- OutofcoreCloud::OutofcoreCloud (std::string name, boost::filesystem::path& tree_root) : - Object (name), display_depth_ (1), points_loaded_ (0), data_loaded_(0), render_camera_(nullptr), lod_pixel_threshold_(10000) + Object (name) { // Create the pcd reader thread once for all outofcore nodes From aab340f39390eb4fb6adbdac987ef23fca535101 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sat, 2 Sep 2023 07:53:35 +0200 Subject: [PATCH 116/288] Improve optimizeModelCoefficients for cone, cylinder, sphere models (#5790) * Improve optimizeModelCoefficients for cone,cylinder,sphere models This has two effects: making the functions faster and reducing PCL's compile time. The function that is optimized is exactly the same as before. In my tests, optimizeModelCoefficients is now at least twice as fast, often even three times as fast as before. This is because the x, y, and z values are perfectly arranged for SSE and AVX instructions. The time needed to compile PCL is also reduced: instantiating Eigen::LevenbergMarquardt takes a rather long time, and previously this was done for each point type (sphere model) or even each point type-normal type combination (cone and cylinder model). Now, Eigen::LevenbergMarquardt is only instantiated once for all cone models, once for all cylinder models, and once for all sphere models. In my tests, this leads to a compile time reduction of roughly 1 minute (building the sample consensus library took 14m35s before and 13m31s now, one compile job, PCL_ONLY_CORE_POINT_TYPES=OFF). * Add more const --- .../sample_consensus/impl/sac_model_cone.hpp | 21 +++++--- .../impl/sac_model_cylinder.hpp | 21 +++++--- .../impl/sac_model_sphere.hpp | 21 +++++--- .../pcl/sample_consensus/sac_model_cone.h | 52 ++----------------- .../pcl/sample_consensus/sac_model_cylinder.h | 40 ++------------ .../pcl/sample_consensus/sac_model_sphere.h | 38 ++------------ sample_consensus/src/sac_model_cone.cpp | 50 ++++++++++++++++++ sample_consensus/src/sac_model_cylinder.cpp | 49 +++++++++++++++++ sample_consensus/src/sac_model_sphere.cpp | 40 ++++++++++++++ 9 files changed, 190 insertions(+), 142 deletions(-) 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 1003cd96861..2f7118e7058 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,6 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CONE_H_ -#include // for LevenbergMarquardt #include #include // for getAngle3D #include @@ -344,14 +343,20 @@ pcl::SampleConsensusModelCone::optimizeModelCoefficients ( return; } - OptimizationFunctor functor (this, inliers); - Eigen::NumericalDiff num_diff (functor); - Eigen::LevenbergMarquardt, float> lm (num_diff); - int info = lm.minimize (optimized_coefficients); + Eigen::ArrayXf pts_x(inliers.size()); + Eigen::ArrayXf pts_y(inliers.size()); + Eigen::ArrayXf pts_z(inliers.size()); + std::size_t pos = 0; + for(const auto& index : inliers) { + pts_x[pos] = (*input_)[index].x; + pts_y[pos] = (*input_)[index].y; + pts_z[pos] = (*input_)[index].z; + ++pos; + } + pcl::internal::optimizeModelCoefficientsCone(optimized_coefficients, pts_x, pts_y, pts_z); - // Compute the L2 norm of the residuals - PCL_DEBUG ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", - info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], + PCL_DEBUG ("[pcl::SampleConsensusModelCone::optimizeModelCoefficients] Initial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", + model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]); Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]); 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 284e95c447b..b4caa68609b 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,6 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_CYLINDER_H_ -#include // for LevenbergMarquardt #include #include // for getAngle3D #include @@ -299,14 +298,20 @@ pcl::SampleConsensusModelCylinder::optimizeModelCoefficients ( return; } - OptimizationFunctor functor (this, inliers); - Eigen::NumericalDiff num_diff (functor); - Eigen::LevenbergMarquardt, float> lm (num_diff); - int info = lm.minimize (optimized_coefficients); + Eigen::ArrayXf pts_x(inliers.size()); + Eigen::ArrayXf pts_y(inliers.size()); + Eigen::ArrayXf pts_z(inliers.size()); + std::size_t pos = 0; + for(const auto& index : inliers) { + pts_x[pos] = (*input_)[index].x; + pts_y[pos] = (*input_)[index].y; + pts_z[pos] = (*input_)[index].z; + ++pos; + } + pcl::internal::optimizeModelCoefficientsCylinder(optimized_coefficients, pts_x, pts_y, pts_z); - // Compute the L2 norm of the residuals - PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", - info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], + PCL_DEBUG ("[pcl::SampleConsensusModelCylinder::optimizeModelCoefficients] Initial solution: %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g\n", + model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], model_coefficients[4], model_coefficients[5], model_coefficients[6], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5], optimized_coefficients[6]); Eigen::Vector3f line_dir (optimized_coefficients[3], optimized_coefficients[4], optimized_coefficients[5]); 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 6834afb601e..2ff3e55210f 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,6 @@ #ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_SPHERE_H_ -#include // for LevenbergMarquardt #include ////////////////////////////////////////////////////////////////////////// @@ -354,14 +353,20 @@ pcl::SampleConsensusModelSphere::optimizeModelCoefficients ( return; } - OptimizationFunctor functor (this, inliers); - Eigen::NumericalDiff num_diff (functor); - Eigen::LevenbergMarquardt, float> lm (num_diff); - int info = lm.minimize (optimized_coefficients); + Eigen::ArrayXf pts_x(inliers.size()); + Eigen::ArrayXf pts_y(inliers.size()); + Eigen::ArrayXf pts_z(inliers.size()); + std::size_t pos = 0; + for(const auto& index : inliers) { + pts_x[pos] = (*input_)[index].x; + pts_y[pos] = (*input_)[index].y; + pts_z[pos] = (*input_)[index].z; + ++pos; + } + pcl::internal::optimizeModelCoefficientsSphere(optimized_coefficients, pts_x, pts_y, pts_z); - // Compute the L2 norm of the residuals - PCL_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g \nFinal solution: %g %g %g %g\n", - info, lm.fvec.norm (), model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]); + PCL_DEBUG ("[pcl::SampleConsensusModelSphere::optimizeModelCoefficients] Initial solution: %g %g %g %g \nFinal solution: %g %g %g %g\n", + model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], optimized_coefficients[0], optimized_coefficients[1], optimized_coefficients[2], optimized_coefficients[3]); } ////////////////////////////////////////////////////////////////////////// diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h index d96a0d764b8..6137c26126c 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h @@ -44,6 +44,10 @@ namespace pcl { + namespace internal { + int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + } // namespace internal + /** \brief @b SampleConsensusModelCone defines a model for 3D cone segmentation. * The model coefficients are defined as: *
      @@ -299,54 +303,6 @@ namespace pcl /** \brief The minimum and maximum allowed opening angles of valid cone model. */ double min_angle_; double max_angle_; - - /** \brief Functor for the optimization function */ - struct OptimizationFunctor : pcl::Functor - { - /** Functor constructor - * \param[in] indices the indices of data points to evaluate - * \param[in] estimator pointer to the estimator object - */ - OptimizationFunctor (const pcl::SampleConsensusModelCone *model, const Indices& indices) : - pcl::Functor (indices.size ()), model_ (model), indices_ (indices) {} - - /** Cost function to be minimized - * \param[in] x variables array - * \param[out] fvec resultant functions evaluations - * \return 0 - */ - int - operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const - { - Eigen::Vector4f apex (x[0], x[1], x[2], 0); - Eigen::Vector4f axis_dir (x[3], x[4], x[5], 0); - float opening_angle = x[6]; - - float apexdotdir = apex.dot (axis_dir); - float dirdotdir = 1.0f / axis_dir.dot (axis_dir); - - for (int i = 0; i < values (); ++i) - { - // dist = f - r - Eigen::Vector4f pt = (*model_->input_)[indices_[i]].getVector4fMap(); - pt[3] = 0; - - // Calculate the point's projection on the cone axis - float k = (pt.dot (axis_dir) - apexdotdir) * dirdotdir; - Eigen::Vector4f pt_proj = apex + k * axis_dir; - - // Calculate the actual radius of the cone at the level of the projected point - Eigen::Vector4f height = apex-pt_proj; - float actual_cone_radius = tanf (opening_angle) * height.norm (); - - fvec[i] = static_cast (pcl::sqrPointToLineDistance (pt, apex, axis_dir) - actual_cone_radius * actual_cone_radius); - } - return (0); - } - - const pcl::SampleConsensusModelCone *model_; - const Indices &indices_; - }; }; } diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h index 7a45f26ff66..95a6e80873b 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h @@ -46,6 +46,10 @@ namespace pcl { + namespace internal { + int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + } // namespace internal + /** \brief @b SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. * The model coefficients are defined as: * - \b point_on_axis.x : the X coordinate of a point located on the cylinder axis @@ -295,42 +299,6 @@ namespace pcl /** \brief The maximum allowed difference between the cylinder direction and the given axis. */ double eps_angle_; - - /** \brief Functor for the optimization function */ - struct OptimizationFunctor : pcl::Functor - { - /** Functor constructor - * \param[in] indices the indices of data points to evaluate - * \param[in] estimator pointer to the estimator object - */ - OptimizationFunctor (const pcl::SampleConsensusModelCylinder *model, const Indices& indices) : - pcl::Functor (indices.size ()), model_ (model), indices_ (indices) {} - - /** Cost function to be minimized - * \param[in] x variables array - * \param[out] fvec resultant functions evaluations - * \return 0 - */ - int - operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const - { - Eigen::Vector4f line_pt (x[0], x[1], x[2], 0); - Eigen::Vector4f line_dir (x[3], x[4], x[5], 0); - - for (int i = 0; i < values (); ++i) - { - // dist = f - r - Eigen::Vector4f pt = (*model_->input_)[indices_[i]].getVector4fMap(); - pt[3] = 0; - - fvec[i] = static_cast (pcl::sqrPointToLineDistance (pt, line_pt, line_dir) - x[6]*x[6]); - } - return (0); - } - - const pcl::SampleConsensusModelCylinder *model_; - const Indices &indices_; - }; }; } diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h index 44dca3591af..1e15149953c 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h @@ -52,6 +52,10 @@ namespace pcl { + namespace internal { + int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + } // namespace internal + /** \brief SampleConsensusModelSphere defines a model for 3D sphere segmentation. * The model coefficients are defined as: * - \b center.x : the X coordinate of the sphere's center @@ -263,40 +267,6 @@ namespace pcl #endif private: - struct OptimizationFunctor : pcl::Functor - { - /** Functor constructor - * \param[in] indices the indices of data points to evaluate - * \param[in] estimator pointer to the estimator object - */ - OptimizationFunctor (const pcl::SampleConsensusModelSphere *model, const Indices& indices) : - pcl::Functor (indices.size ()), model_ (model), indices_ (indices) {} - - /** Cost function to be minimized - * \param[in] x the variables array - * \param[out] fvec the resultant functions evaluations - * \return 0 - */ - int - operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const - { - Eigen::Vector4f cen_t; - cen_t[3] = 0; - for (int i = 0; i < values (); ++i) - { - // Compute the difference between the center of the sphere and the datapoint X_i - cen_t.head<3>() = (*model_->input_)[indices_[i]].getVector3fMap() - x.head<3>(); - - // g = sqrt ((x-a)^2 + (y-b)^2 + (z-c)^2) - R - fvec[i] = std::sqrt (cen_t.dot (cen_t)) - x[3]; - } - return (0); - } - - const pcl::SampleConsensusModelSphere *model_; - const Indices &indices_; - }; - #ifdef __AVX__ inline __m256 sqr_dist8 (const std::size_t i, const __m256 a_vec, const __m256 b_vec, const __m256 c_vec) const; #endif diff --git a/sample_consensus/src/sac_model_cone.cpp b/sample_consensus/src/sac_model_cone.cpp index a321c33bbc0..e2db0c33731 100644 --- a/sample_consensus/src/sac_model_cone.cpp +++ b/sample_consensus/src/sac_model_cone.cpp @@ -37,6 +37,56 @@ */ #include +#include // for LevenbergMarquardt + +int pcl::internal::optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z) +{ + if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCone] Sizes not equal!\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + if(coeff.size() != 7) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCone] Coefficients have wrong size\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + struct ConeOptimizationFunctor : pcl::Functor + { + ConeOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) : + pcl::Functor(x.size()), pts_x(x), pts_y(y), pts_z(z) + {} + + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + Eigen::Vector3f axis_dir(x[3], x[4], x[5]); + axis_dir.normalize(); + const Eigen::ArrayXf axis_dir_x = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.x()); + const Eigen::ArrayXf axis_dir_y = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.y()); + const Eigen::ArrayXf axis_dir_z = Eigen::ArrayXf::Constant(pts_x.size(), axis_dir.z()); + const Eigen::ArrayXf bx = Eigen::ArrayXf::Constant(pts_x.size(), x[0]) - pts_x; + const Eigen::ArrayXf by = Eigen::ArrayXf::Constant(pts_x.size(), x[1]) - pts_y; + const Eigen::ArrayXf bz = Eigen::ArrayXf::Constant(pts_x.size(), x[2]) - pts_z; + const Eigen::ArrayXf actual_cone_radius = std::tan(x[6]) * + (bx*axis_dir_x+by*axis_dir_y+bz*axis_dir_z); + // compute the squared distance of point b to the line (cross product), then subtract the actual cone radius (squared) + fvec = ((axis_dir_y * bz - axis_dir_z * by).square() + +(axis_dir_z * bx - axis_dir_x * bz).square() + +(axis_dir_x * by - axis_dir_y * bx).square()) + -actual_cone_radius.square(); + return (0); + } + + const Eigen::ArrayXf& pts_x, pts_y, pts_z; + }; + + ConeOptimizationFunctor functor (pts_x, pts_y, pts_z); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + const int info = lm.minimize (coeff); + PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsCone] LM solver finished with exit code %i, having a residual norm of %g.\n", + info, lm.fvec.norm ()); + return info; +} #ifndef PCL_NO_PRECOMPILE #include diff --git a/sample_consensus/src/sac_model_cylinder.cpp b/sample_consensus/src/sac_model_cylinder.cpp index 54929fab8cb..aae33d91c7e 100644 --- a/sample_consensus/src/sac_model_cylinder.cpp +++ b/sample_consensus/src/sac_model_cylinder.cpp @@ -37,6 +37,55 @@ */ #include +#include // for LevenbergMarquardt + +int pcl::internal::optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z) +{ + if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCylinder] Sizes not equal!\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + if(coeff.size() != 7) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsCylinder] Coefficients have wrong size\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + struct CylinderOptimizationFunctor : pcl::Functor + { + CylinderOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) : + pcl::Functor(x.size()), pts_x(x), pts_y(y), pts_z(z) + {} + + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + Eigen::Vector3f line_dir(x[3], x[4], x[5]); + line_dir.normalize(); + const Eigen::ArrayXf line_dir_x = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.x()); + const Eigen::ArrayXf line_dir_y = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.y()); + const Eigen::ArrayXf line_dir_z = Eigen::ArrayXf::Constant(pts_x.size(), line_dir.z()); + const Eigen::ArrayXf bx = Eigen::ArrayXf::Constant(pts_x.size(), x[0]) - pts_x; + const Eigen::ArrayXf by = Eigen::ArrayXf::Constant(pts_x.size(), x[1]) - pts_y; + const Eigen::ArrayXf bz = Eigen::ArrayXf::Constant(pts_x.size(), x[2]) - pts_z; + // compute the squared distance of point b to the line (cross product), then subtract the squared model radius + fvec = ((line_dir_y * bz - line_dir_z * by).square() + +(line_dir_z * bx - line_dir_x * bz).square() + +(line_dir_x * by - line_dir_y * bx).square()) + -Eigen::ArrayXf::Constant(pts_x.size(), x[6]*x[6]); + return (0); + } + + const Eigen::ArrayXf& pts_x, pts_y, pts_z; + }; + + CylinderOptimizationFunctor functor (pts_x, pts_y, pts_z); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + const int info = lm.minimize (coeff); + coeff[6] = std::abs(coeff[6]); + PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsCylinder] LM solver finished with exit code %i, having a residual norm of %g.\n", + info, lm.fvec.norm ()); + return info; +} #ifndef PCL_NO_PRECOMPILE #include diff --git a/sample_consensus/src/sac_model_sphere.cpp b/sample_consensus/src/sac_model_sphere.cpp index 03d84652715..27fbf325760 100644 --- a/sample_consensus/src/sac_model_sphere.cpp +++ b/sample_consensus/src/sac_model_sphere.cpp @@ -37,6 +37,46 @@ */ #include +#include // for LevenbergMarquardt + +int pcl::internal::optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z) +{ + if(pts_x.size() != pts_y.size() || pts_y.size() != pts_z.size()) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsSphere] Sizes not equal!\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + if(coeff.size() != 4) { + PCL_ERROR("[pcl::internal::optimizeModelCoefficientsSphere] Coefficients have wrong size\n"); + return Eigen::LevenbergMarquardtSpace::ImproperInputParameters; + } + struct SphereOptimizationFunctor : pcl::Functor + { + SphereOptimizationFunctor (const Eigen::ArrayXf& x, const Eigen::ArrayXf& y, const Eigen::ArrayXf& z) : + pcl::Functor(x.size()), pts_x(x), pts_y(y), pts_z(z) + {} + + int + operator() (const Eigen::VectorXf &x, Eigen::VectorXf &fvec) const + { + // Compute distance of all points to center, then subtract radius + fvec = ((Eigen::ArrayXf::Constant(pts_x.size(), x[0])-pts_x).square() + +(Eigen::ArrayXf::Constant(pts_x.size(), x[1])-pts_y).square() + +(Eigen::ArrayXf::Constant(pts_x.size(), x[2])-pts_z).square()).sqrt() + -Eigen::ArrayXf::Constant(pts_x.size(), x[3]); + return (0); + } + + const Eigen::ArrayXf& pts_x, pts_y, pts_z; + }; + + SphereOptimizationFunctor functor (pts_x, pts_y, pts_z); + Eigen::NumericalDiff num_diff (functor); + Eigen::LevenbergMarquardt, float> lm (num_diff); + const int info = lm.minimize (coeff); + PCL_DEBUG ("[pcl::internal::optimizeModelCoefficientsSphere] LM solver finished with exit code %i, having a residual norm of %g.\n", + info, lm.fvec.norm ()); + return info; +} #ifndef PCL_NO_PRECOMPILE #include From 1b5f84e96ae92af7cff3ff6e5cd21092facae067 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 2 Sep 2023 12:08:58 +0200 Subject: [PATCH 117/288] Deprecate CrfNormalSegmentation It is not implemented and does not do anything useful. Users should be warned so they do not attempt to use it. --- segmentation/CMakeLists.txt | 1 - .../segmentation/crf_normal_segmentation.h | 4 +- segmentation/src/crf_normal_segmentation.cpp | 46 ------------------- 3 files changed, 1 insertion(+), 50 deletions(-) delete mode 100644 segmentation/src/crf_normal_segmentation.cpp diff --git a/segmentation/CMakeLists.txt b/segmentation/CMakeLists.txt index 1a8420fe964..f6cdf291a5a 100644 --- a/segmentation/CMakeLists.txt +++ b/segmentation/CMakeLists.txt @@ -25,7 +25,6 @@ set(srcs src/organized_multi_plane_segmentation.cpp src/planar_polygon_fusion.cpp src/crf_segmentation.cpp - src/crf_normal_segmentation.cpp src/unary_classifier.cpp src/conditional_euclidean_clustering.cpp src/supervoxel_clustering.cpp diff --git a/segmentation/include/pcl/segmentation/crf_normal_segmentation.h b/segmentation/include/pcl/segmentation/crf_normal_segmentation.h index 6eb2663c1ba..14a5d97c51f 100644 --- a/segmentation/include/pcl/segmentation/crf_normal_segmentation.h +++ b/segmentation/include/pcl/segmentation/crf_normal_segmentation.h @@ -47,7 +47,7 @@ namespace pcl * \author Christian Potthast */ template - class PCL_EXPORTS CrfNormalSegmentation + class PCL_DEPRECATED(1, 17, "CrfNormalSegmentation is not implemented and does not do anything useful") CrfNormalSegmentation { public: /** \brief Constructor that sets default values for member variables. */ @@ -71,6 +71,4 @@ namespace pcl }; } -#ifdef PCL_NO_PRECOMPILE #include -#endif diff --git a/segmentation/src/crf_normal_segmentation.cpp b/segmentation/src/crf_normal_segmentation.cpp deleted file mode 100644 index 70a378fcb6a..00000000000 --- a/segmentation/src/crf_normal_segmentation.cpp +++ /dev/null @@ -1,46 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * - * 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. - * - * Author : Christian Potthast - * Email : potthast@usc.edu - * - */ - -#include -#include -#include -#include - -// Instantiations of specific point types -template class pcl::CrfNormalSegmentation; From 6ae8c8844e43470fb4eca05ef5aa136db9296df7 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 2 Sep 2023 15:23:06 +0200 Subject: [PATCH 118/288] Deprecate SampleConsensusModelStick Fixes https://github.com/PointCloudLibrary/pcl/issues/2452 --- .../include/pcl/sample_consensus/sac_model_stick.h | 5 +++++ sample_consensus/src/sac_model_stick.cpp | 1 + .../include/pcl/segmentation/impl/sac_segmentation.hpp | 3 +++ 3 files changed, 9 insertions(+) diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h b/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h index 14805c67e94..3d8babdff42 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_stick.h @@ -56,11 +56,16 @@ namespace pcl * - \b line_direction.z : the Z coordinate of a line's direction * - \b line_width : the width of the line * + * \warning This model is considered deprecated. The coefficients are used inconsistently in the methods, and the last coefficient (line width) is unused. We recommend to use the line or cylinder model instead. * \author Radu B. Rusu * \ingroup sample_consensus */ template +#ifdef SAC_MODEL_STICK_DONT_WARN_DEPRECATED class SampleConsensusModelStick : public SampleConsensusModel +#else + class PCL_DEPRECATED(1, 17, "Use line or cylinder model instead") SampleConsensusModelStick : public SampleConsensusModel +#endif { public: using SampleConsensusModel::model_name_; diff --git a/sample_consensus/src/sac_model_stick.cpp b/sample_consensus/src/sac_model_stick.cpp index 0b00fba0ddd..db48a7f0ea4 100644 --- a/sample_consensus/src/sac_model_stick.cpp +++ b/sample_consensus/src/sac_model_stick.cpp @@ -37,6 +37,7 @@ */ #include +#define SAC_MODEL_STICK_DONT_WARN_DEPRECATED #include #ifndef PCL_NO_PRECOMPILE diff --git a/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp index 11686ae1dce..e701b5ef752 100644 --- a/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/sac_segmentation.hpp @@ -68,7 +68,9 @@ #include #include #include +#define SAC_MODEL_STICK_DONT_WARN_DEPRECATED #include +#undef SAC_MODEL_STICK_DONT_WARN_DEPRECATED #include #include // for static_pointer_cast @@ -155,6 +157,7 @@ pcl::SACSegmentation::initSACModel (const int model_type) } case SACMODEL_STICK: { + PCL_WARN ("[pcl::%s::initSACModel] SACMODEL_STICK is deprecated: Use SACMODEL_LINE instead (It will be removed in PCL 1.17)\n", getClassName ().c_str ()); PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_STICK\n", getClassName ().c_str ()); model_.reset (new SampleConsensusModelStick (input_, *indices_)); double min_radius, max_radius; From c2d850f20fb7fc8bb94fb85d2eb5d4d038c30082 Mon Sep 17 00:00:00 2001 From: = <=> Date: Tue, 5 Sep 2023 08:15:43 +0200 Subject: [PATCH 119/288] Remove 18.04 as its EOL. Added 23.04 as newest. --- .ci/azure-pipelines/env.yml | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index 4fc44c80a7b..eed0902a185 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -41,12 +41,7 @@ jobs: vmImage: 'ubuntu-latest' strategy: matrix: - Ubuntu 18.04: - # Test the oldest supported version of Ubuntu - UBUNTU_VERSION: 18.04 - VTK_VERSION: 7 - ENSENSOSDK_VERSION: 2.3.1570 - TAG: 18.04 + # Test the oldest supported version of Ubuntu Ubuntu 20.04: UBUNTU_VERSION: 20.04 VTK_VERSION: 7 @@ -56,11 +51,11 @@ jobs: UBUNTU_VERSION: 22.04 VTK_VERSION: 9 TAG: 22.04 - Ubuntu 22.10: - UBUNTU_VERSION: 22.10 + Ubuntu 23.04: + UBUNTU_VERSION: 23.04 USE_LATEST_CMAKE: true VTK_VERSION: 9 - TAG: 22.10 + TAG: 23.04 steps: - script: | dockerBuildArgs="" ; \ From e681e83cb6301434d180b858130d0df91ea17fd6 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 13 Sep 2023 09:42:43 +0200 Subject: [PATCH 120/288] Allow compilation with Boost 1.83 --- PCLConfig.cmake.in | 2 +- cmake/pcl_find_boost.cmake | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index c66e5fcc7c0..aede14383b2 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -96,7 +96,7 @@ macro(find_boost) set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" - "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" + "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index 016aa2037a9..fb9ef5b71a1 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -14,7 +14,7 @@ else() endif() set(Boost_ADDITIONAL_VERSIONS - "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" + "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") From 9c2b0888a24993a282e9dc3e4884a869d4aacb4a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 14 Sep 2023 21:43:39 +0200 Subject: [PATCH 121/288] Add missing cassert include --- io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h | 1 + .../pcl/io/openni_camera/openni_shift_to_depth_conversion.h | 1 + 2 files changed, 2 insertions(+) diff --git a/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h b/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h index c4f7efbe7d2..2946e4561a2 100644 --- a/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h +++ b/io/include/pcl/io/openni2/openni_shift_to_depth_conversion.h @@ -41,6 +41,7 @@ #include #ifdef HAVE_OPENNI2 +#include // for assert #include #include diff --git a/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h b/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h index e69ff33bdc3..b5f6258630d 100644 --- a/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h +++ b/io/include/pcl/io/openni_camera/openni_shift_to_depth_conversion.h @@ -41,6 +41,7 @@ #include #ifdef HAVE_OPENNI +#include // for assert #include #include #include From 77c628fba276d6693962401e89d1d6810bc01e8c Mon Sep 17 00:00:00 2001 From: Rasmus Diederichsen Date: Thu, 21 Sep 2023 12:54:02 +0200 Subject: [PATCH 122/288] update doc for OrganizedNeighnor --- search/include/pcl/search/organized.h | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/search/include/pcl/search/organized.h b/search/include/pcl/search/organized.h index cbf15566976..6d5e6461d82 100644 --- a/search/include/pcl/search/organized.h +++ b/search/include/pcl/search/organized.h @@ -52,10 +52,14 @@ namespace pcl { namespace search { - /** \brief OrganizedNeighbor is a class for optimized nearest neighbor search in organized point clouds. - * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys - * \ingroup search - */ + /** \brief OrganizedNeighbor is a class for optimized nearest neighbor search in + * organized projectable point clouds, for instance from Time-Of-Flight cameras or + * stereo cameras. Note that rotating LIDARs may output organized clouds, but are + * not projectable via a pinhole camera model into two dimensions and thus will + * generally not work with this class. + * \author Radu B. Rusu, Julius Kammerl, Suat Gedikli, Koen Buys + * \ingroup search + */ template class OrganizedNeighbor : public pcl::search::Search { From b5ce8f5ff3f23dcade59c1b78351037cf4bb3f97 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 21 Sep 2023 13:23:55 +0200 Subject: [PATCH 123/288] Update pipeline to newer docker images. (#5807) * Update vmImage to 22.04. Update builds to use 20.04 as lowest supported ubuntu and 23.04 as highest. Updated Clang builds to use 22.04. * Disable GPU build on clang, due to nvcc defaults to gcc. * Remove comment * Update ci status on readme page. --- .ci/azure-pipelines/azure-pipelines.yaml | 30 ++++++++++++------------ README.md | 2 +- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 8f93718d5ce..bb3c54e6a70 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -20,12 +20,12 @@ resources: image: pointcloudlibrary/env:winx86 - container: winx64 image: pointcloudlibrary/env:winx64 - - container: env1804 - image: pointcloudlibrary/env:18.04 - container: env2004 image: pointcloudlibrary/env:20.04 - container: env2204 image: pointcloudlibrary/env:22.04 + - container: env2304 + image: pointcloudlibrary/env:23.04 stages: - stage: formatting @@ -40,20 +40,20 @@ stages: - job: ubuntu displayName: Ubuntu pool: - vmImage: 'Ubuntu 20.04' + vmImage: 'ubuntu-22.04' strategy: matrix: - 18.04 GCC: # oldest LTS - CONTAINER: env1804 + 20.04 GCC: # oldest LTS + CONTAINER: env2004 CC: gcc CXX: g++ BUILD_GPU: ON CMAKE_ARGS: '-DPCL_WARNINGS_ARE_ERRORS=ON' - 22.04 GCC: # latest Ubuntu - CONTAINER: env2204 + 23.04 GCC: # latest Ubuntu + CONTAINER: env2304 CC: gcc CXX: g++ - BUILD_GPU: OFF # There are currently incompatibilities between GCC 11.2 and CUDA 11.5 + BUILD_GPU: ON container: $[ variables['CONTAINER'] ] timeoutInMinutes: 0 variables: @@ -95,14 +95,14 @@ stages: dependsOn: osx condition: succeededOrFailed() pool: - vmImage: 'Ubuntu 20.04' + vmImage: 'ubuntu-22.04' strategy: matrix: - 20.04 Clang: - CONTAINER: env2004 + 22.04 Clang: + CONTAINER: env2204 CC: clang CXX: clang++ - BUILD_GPU: ON + BUILD_GPU: OFF # There are currently incompatibilities between GCC 11.2 and CUDA 11.5 (Ubuntu 22.04) CMAKE_ARGS: '' container: $[ variables['CONTAINER'] ] timeoutInMinutes: 0 @@ -118,11 +118,11 @@ stages: dependsOn: osx condition: succeededOrFailed() pool: - vmImage: 'Ubuntu 20.04' + vmImage: 'ubuntu-22.04' strategy: matrix: - 20.04 Clang: - CONTAINER: env2004 + 22.04 Clang: + CONTAINER: env2204 CC: clang CXX: clang++ INDEX_SIGNED: OFF diff --git a/README.md b/README.md index ad4443647f8..ca2b0d9b9fd 100644 --- a/README.md +++ b/README.md @@ -21,9 +21,9 @@ If you really need access to the old website, please use [the copy made by the i Continuous integration ---------------------- [ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master -[ci-ubuntu-18.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2018.04%20GCC&label=Ubuntu%2018.04%20GCC [ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2020.04%20Clang&label=Ubuntu%2020.04%20Clang [ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2022.04%20GCC +[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2023.04%20GCC [ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86 [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64 [ci-macos-11]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Big%20Sur%2011&label=macOS%20Big%20Sur%2011 From 8662c13fc749d9dae851b2ca0a1e32a3d973d53b Mon Sep 17 00:00:00 2001 From: gaishunhua <1228843531@qq.com> Date: Fri, 22 Sep 2023 16:07:16 +0800 Subject: [PATCH 124/288] Update sac_model_cylinder.hpp Refer to the relevant calculation codes in other functions. Multiplication here should be changed to division. like "projectPointToLine (const Eigen::Vector4f &pt, const Eigen::Vector4f &line_pt, const Eigen::Vector4f &line_dir, Eigen::Vector4f &pt_proj) const { float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); // Calculate the projection of the point on the line pt_proj = line_pt + k * line_dir; } " --- .../include/pcl/sample_consensus/impl/sac_model_cylinder.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 b4caa68609b..03e26680a39 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 @@ -452,7 +452,7 @@ pcl::SampleConsensusModelCylinder::projectPointToCylinder ( Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f); Eigen::Vector4f line_dir (model_coefficients[3], model_coefficients[4], model_coefficients[5], 0.0f); - float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) * line_dir.dot (line_dir); + float k = (pt.dot (line_dir) - line_pt.dot (line_dir)) / line_dir.dot (line_dir); pt_proj = line_pt + k * line_dir; Eigen::Vector4f dir = pt - pt_proj; From 8c0230c43cbbecfe4706cdd4c3656c2fcba55049 Mon Sep 17 00:00:00 2001 From: javierBarandiaran Date: Sat, 23 Sep 2023 20:05:31 +0200 Subject: [PATCH 125/288] Replace std::time with std::random_device as seed for random number generator --- sample_consensus/include/pcl/sample_consensus/sac_model.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model.h b/sample_consensus/include/pcl/sample_consensus/sac_model.h index a1f3a91980a..39f066a7254 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model.h @@ -47,6 +47,7 @@ #include // for mt19937 #include // for uniform_int #include // for variate_generator +#include #include #include @@ -92,7 +93,7 @@ namespace pcl { // Create a random number generator object if (random) - rng_alg_.seed (static_cast (std::time(nullptr))); + rng_alg_.seed (std::random_device()()); else rng_alg_.seed (12345u); @@ -114,7 +115,7 @@ namespace pcl , custom_model_constraints_ ([](auto){return true;}) { if (random) - rng_alg_.seed (static_cast (std::time (nullptr))); + rng_alg_.seed (std::random_device()()); else rng_alg_.seed (12345u); @@ -143,7 +144,7 @@ namespace pcl , custom_model_constraints_ ([](auto){return true;}) { if (random) - rng_alg_.seed (static_cast (std::time(nullptr))); + rng_alg_.seed (std::random_device()()); else rng_alg_.seed (12345u); From d8127858c5f6162468b513708a16f29f0d6f516a Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sat, 30 Sep 2023 20:52:59 +0200 Subject: [PATCH 126/288] Some improvements to gpu/segmentation (#5813) * Some improvements to gpu/segmentation - move implementation of economical_download to hpp file, fixes https://github.com/PointCloudLibrary/pcl/issues/5791 - add necessary template parameter in example - const reference in for loop to avoid copies * Example: remove nan values * Undo changes * Undo changes and add PCL_EXPORTS --- gpu/examples/segmentation/src/seg.cpp | 4 +++- .../pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp | 2 +- gpu/segmentation/src/extract_clusters.cpp | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gpu/examples/segmentation/src/seg.cpp b/gpu/examples/segmentation/src/seg.cpp index 348e27c12c1..923b2326057 100644 --- a/gpu/examples/segmentation/src/seg.cpp +++ b/gpu/examples/segmentation/src/seg.cpp @@ -26,6 +26,8 @@ main (int argc, char** argv) pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud); pcl::PCDWriter writer; reader.read (argv[1], *cloud_filtered); + pcl::Indices unused; + pcl::removeNaNFromPointCloud(*cloud_filtered, *cloud_filtered, unused); ///////////////////////////////////////////// /// CPU VERSION @@ -81,7 +83,7 @@ main (int argc, char** argv) octree_device->build(); std::vector cluster_indices_gpu; - pcl::gpu::EuclideanClusterExtraction gec; + pcl::gpu::EuclideanClusterExtraction gec; gec.setClusterTolerance (0.02); // 2cm gec.setMinClusterSize (100); gec.setMaxClusterSize (25000); 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 d5c0371aac9..2e2be0de375 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 @@ -152,7 +152,7 @@ pcl::gpu::extractEuclideanClusters( continue; // Process the results - for (auto idx : data) { + for (const auto& idx : data) { if (processed[idx]) continue; processed[idx] = true; diff --git a/gpu/segmentation/src/extract_clusters.cpp b/gpu/segmentation/src/extract_clusters.cpp index 0e5eac3dcd1..3910551c624 100644 --- a/gpu/segmentation/src/extract_clusters.cpp +++ b/gpu/segmentation/src/extract_clusters.cpp @@ -46,7 +46,7 @@ PCL_INSTANTIATE(EuclideanClusterExtraction, PCL_XYZ_POINT_TYPES); PCL_INSTANTIATE(extractLabeledEuclideanClusters, PCL_XYZL_POINT_TYPES); PCL_INSTANTIATE(EuclideanLabeledClusterExtraction, PCL_XYZL_POINT_TYPES); -void +void PCL_EXPORTS pcl::detail::economical_download(const pcl::gpu::NeighborIndices& source_indices, const pcl::Indices& buffer_indices, std::size_t buffer_size, From 180b6e0e4a56da16d51c368acee09b01dc028a1b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 23 Sep 2023 16:36:33 +0200 Subject: [PATCH 127/288] GICP: add Newton optimizer (as new default) It replaces the current BFGS optimizer, which is still available via `useBFGS`. The Newton optimizer uses the hessian matrix of the function, while BFGS only computes an approximation of the hessian. In direct comparison (same GICP cost function to minimize and same starting point/same initial transformation), the Newton optimizer (estimateRigidTransformationNewton) takes only about one third of the time needed by the BFGS optimizer (estimateRigidTransformationBFGS). Every time, the Newton optimizer finds a slightly better transformation (lower cost) than the BFGS optimizer. Note: GICP.align() as a whole becomes only a bit faster (not 3x faster) because it also spends time on nearest-neighbour search. Even in very difficult situations, e.g. when both point clouds are far away from the origin meaning even a small rotation change results in a large point-to-point distance change, the Newton optimizer still finds a good solution, while the BFGS optimizer often fails completely. --- registration/include/pcl/registration/gicp.h | 62 ++- .../include/pcl/registration/impl/gicp.hpp | 371 +++++++++++++++++- 2 files changed, 415 insertions(+), 18 deletions(-) diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 2eae855abbf..65041fbabd7 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -49,8 +49,9 @@ namespace pcl { * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf * The approach is based on using anisotropic cost functions to optimize the alignment * after closest point assignments have been made. - * The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and - * FLANN. + * The original code uses GSL and ANN while in ours we use FLANN and Newton's method + * for optimization (call `useBFGS` to switch to BFGS optimizer, however Newton + * is usually faster and more accurate). * \author Nizar Sallem * \ingroup registration */ @@ -111,6 +112,7 @@ class GeneralizedIterativeClosestPoint using Matrix3 = typename Eigen::Matrix; using Matrix4 = typename IterativeClosestPoint::Matrix4; + using Matrix6d = Eigen::Matrix; using AngleAxis = typename Eigen::AngleAxis; PCL_MAKE_ALIGNED_OPERATOR_NEW @@ -135,7 +137,7 @@ class GeneralizedIterativeClosestPoint const PointCloudTarget& cloud_tgt, const pcl::Indices& indices_tgt, Matrix4& transformation_matrix) { - estimateRigidTransformationBFGS( + estimateRigidTransformationNewton( cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); }; } @@ -214,6 +216,23 @@ class GeneralizedIterativeClosestPoint const pcl::Indices& indices_tgt, Matrix4& transformation_matrix); + /** \brief Estimate a rigid rotation transformation between a source and a target + * point cloud using an iterative non-linear Newton 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[in,out] transformation_matrix the resultant transformation matrix + */ + void + estimateRigidTransformationNewton(const PointCloudSource& cloud_src, + const pcl::Indices& indices_src, + const PointCloudTarget& cloud_tgt, + const pcl::Indices& indices_tgt, + Matrix4& transformation_matrix); + /** \brief \return Mahalanobis distance matrix for the given point index */ inline const Eigen::Matrix3d& mahalanobis(std::size_t index) const @@ -276,6 +295,21 @@ class GeneralizedIterativeClosestPoint return k_correspondences_; } + /** \brief Use BFGS optimizer instead of default Newton optimizer + */ + void + useBFGS() + { + rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src, + const pcl::Indices& indices_src, + const PointCloudTarget& cloud_tgt, + const pcl::Indices& indices_tgt, + Matrix4& transformation_matrix) { + estimateRigidTransformationBFGS( + cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix); + }; + } + /** \brief Set maximum number of iterations at the optimization step * \param[in] max maximum number of iterations for the optimizer */ @@ -447,6 +481,8 @@ class GeneralizedIterativeClosestPoint df(const Vector6d& x, Vector6d& df) override; void fdf(const Vector6d& x, double& f, Vector6d& df) override; + void + dfddf(const Vector6d& x, Vector6d& df, Matrix6d& ddf); BFGSSpace::Status checkGradient(const Vector6d& g) override; @@ -459,6 +495,26 @@ class GeneralizedIterativeClosestPoint const pcl::Indices& tgt_indices, Matrix4& transformation_matrix)> rigid_transformation_estimation_; + +private: + void + getRDerivatives(double phi, + double theta, + double psi, + Eigen::Matrix3d& dR_dPhi, + Eigen::Matrix3d& dR_dTheta, + Eigen::Matrix3d& dR_dPsi) const; + + void + getR2ndDerivatives(double phi, + double theta, + double psi, + Eigen::Matrix3d& ddR_dPhi_dPhi, + Eigen::Matrix3d& ddR_dPhi_dTheta, + Eigen::Matrix3d& ddR_dPhi_dPsi, + Eigen::Matrix3d& ddR_dTheta_dTheta, + Eigen::Matrix3d& ddR_dTheta_dPsi, + Eigen::Matrix3d& ddR_dPsi_dPsi) const; }; } // namespace pcl diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index b3ce37af2f3..3e1bcb62ed6 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -129,19 +129,17 @@ GeneralizedIterativeClosestPoint::computeCovar template void -GeneralizedIterativeClosestPoint::computeRDerivative( - const Vector6d& x, const Eigen::Matrix3d& dCost_dR_T, Vector6d& g) const +GeneralizedIterativeClosestPoint::getRDerivatives( + double phi, + double theta, + double psi, + Eigen::Matrix3d& dR_dPhi, + Eigen::Matrix3d& dR_dTheta, + Eigen::Matrix3d& dR_dPsi) const { - Eigen::Matrix3d dR_dPhi; - Eigen::Matrix3d dR_dTheta; - Eigen::Matrix3d dR_dPsi; - - double phi = x[3], theta = x[4], psi = x[5]; - - double cphi = std::cos(phi), sphi = sin(phi); - double ctheta = std::cos(theta), stheta = sin(theta); - double cpsi = std::cos(psi), spsi = sin(psi); - + const double cphi = std::cos(phi), sphi = std::sin(phi); + const double ctheta = std::cos(theta), stheta = std::sin(theta); + const double cpsi = std::cos(psi), spsi = std::sin(psi); dR_dPhi(0, 0) = 0.; dR_dPhi(1, 0) = 0.; dR_dPhi(2, 0) = 0.; @@ -177,10 +175,97 @@ GeneralizedIterativeClosestPoint::computeRDeri dR_dPsi(0, 2) = cpsi * sphi - cphi * spsi * stheta; dR_dPsi(1, 2) = sphi * spsi + cphi * cpsi * stheta; dR_dPsi(2, 2) = 0.; +} + +template +void +GeneralizedIterativeClosestPoint::computeRDerivative( + const Vector6d& x, const Eigen::Matrix3d& dCost_dR_T, Vector6d& g) const +{ + Eigen::Matrix3d dR_dPhi; + Eigen::Matrix3d dR_dTheta; + Eigen::Matrix3d dR_dPsi; + getRDerivatives(x[3], x[4], x[5], dR_dPhi, dR_dTheta, dR_dPsi); - g[3] = matricesInnerProd(dR_dPhi, dCost_dR_T); - g[4] = matricesInnerProd(dR_dTheta, dCost_dR_T); - g[5] = matricesInnerProd(dR_dPsi, dCost_dR_T); + g[3] = (dR_dPhi * dCost_dR_T).trace(); + g[4] = (dR_dTheta * dCost_dR_T).trace(); + g[5] = (dR_dPsi * dCost_dR_T).trace(); +} + +template +void +GeneralizedIterativeClosestPoint::getR2ndDerivatives( + double phi, + double theta, + double psi, + Eigen::Matrix3d& ddR_dPhi_dPhi, + Eigen::Matrix3d& ddR_dPhi_dTheta, + Eigen::Matrix3d& ddR_dPhi_dPsi, + Eigen::Matrix3d& ddR_dTheta_dTheta, + Eigen::Matrix3d& ddR_dTheta_dPsi, + Eigen::Matrix3d& ddR_dPsi_dPsi) const +{ + const double sphi = std::sin(phi), stheta = std::sin(theta), spsi = std::sin(psi); + const double cphi = std::cos(phi), ctheta = std::cos(theta), cpsi = std::cos(psi); + ddR_dPhi_dPhi(0, 0) = 0.0; + ddR_dPhi_dPhi(1, 0) = 0.0; + ddR_dPhi_dPhi(2, 0) = 0.0; + ddR_dPhi_dPhi(0, 1) = -cpsi * stheta * sphi + spsi * cphi; + ddR_dPhi_dPhi(1, 1) = -cpsi * cphi - spsi * stheta * sphi; + ddR_dPhi_dPhi(2, 1) = -ctheta * sphi; + ddR_dPhi_dPhi(0, 2) = -spsi * sphi - cpsi * stheta * cphi; + ddR_dPhi_dPhi(1, 2) = -spsi * stheta * cphi + cpsi * sphi; + ddR_dPhi_dPhi(2, 2) = -ctheta * cphi; + + ddR_dPhi_dTheta(0, 0) = 0.0; + ddR_dPhi_dTheta(1, 0) = 0.0; + ddR_dPhi_dTheta(2, 0) = 0.0; + ddR_dPhi_dTheta(0, 1) = cpsi * ctheta * cphi; + ddR_dPhi_dTheta(1, 1) = spsi * ctheta * cphi; + ddR_dPhi_dTheta(2, 1) = -stheta * cphi; + ddR_dPhi_dTheta(0, 2) = -cpsi * ctheta * sphi; + ddR_dPhi_dTheta(1, 2) = -spsi * ctheta * sphi; + ddR_dPhi_dTheta(2, 2) = stheta * sphi; + + ddR_dPhi_dPsi(0, 0) = 0.0; + ddR_dPhi_dPsi(1, 0) = 0.0; + ddR_dPhi_dPsi(2, 0) = 0.0; + ddR_dPhi_dPsi(0, 1) = -spsi * stheta * cphi + cpsi * sphi; + ddR_dPhi_dPsi(1, 1) = spsi * sphi + cpsi * stheta * cphi; + ddR_dPhi_dPsi(2, 1) = 0.0; + ddR_dPhi_dPsi(0, 2) = cpsi * cphi + spsi * stheta * sphi; + ddR_dPhi_dPsi(1, 2) = -cpsi * stheta * sphi + spsi * cphi; + ddR_dPhi_dPsi(2, 2) = 0.0; + + ddR_dTheta_dTheta(0, 0) = -cpsi * ctheta; + ddR_dTheta_dTheta(1, 0) = -spsi * ctheta; + ddR_dTheta_dTheta(2, 0) = stheta; + ddR_dTheta_dTheta(0, 1) = -cpsi * stheta * sphi; + ddR_dTheta_dTheta(1, 1) = -spsi * stheta * sphi; + ddR_dTheta_dTheta(2, 1) = -ctheta * sphi; + ddR_dTheta_dTheta(0, 2) = -cpsi * stheta * cphi; + ddR_dTheta_dTheta(1, 2) = -spsi * stheta * cphi; + ddR_dTheta_dTheta(2, 2) = -ctheta * cphi; + + ddR_dTheta_dPsi(0, 0) = spsi * stheta; + ddR_dTheta_dPsi(1, 0) = -cpsi * stheta; + ddR_dTheta_dPsi(2, 0) = 0.0; + ddR_dTheta_dPsi(0, 1) = -spsi * ctheta * sphi; + ddR_dTheta_dPsi(1, 1) = cpsi * ctheta * sphi; + ddR_dTheta_dPsi(2, 1) = 0.0; + ddR_dTheta_dPsi(0, 2) = -spsi * ctheta * cphi; + ddR_dTheta_dPsi(1, 2) = cpsi * ctheta * cphi; + ddR_dTheta_dPsi(2, 2) = 0.0; + + ddR_dPsi_dPsi(0, 0) = -cpsi * ctheta; + ddR_dPsi_dPsi(1, 0) = -spsi * ctheta; + ddR_dPsi_dPsi(2, 0) = 0.0; + ddR_dPsi_dPsi(0, 1) = -cpsi * stheta * sphi + spsi * cphi; + ddR_dPsi_dPsi(1, 1) = -cpsi * cphi - spsi * stheta * sphi; + ddR_dPsi_dPsi(2, 1) = 0.0; + ddR_dPsi_dPsi(0, 2) = -spsi * sphi - cpsi * stheta * cphi; + ddR_dPsi_dPsi(1, 2) = -spsi * stheta * cphi + cpsi * sphi; + ddR_dPsi_dPsi(2, 2) = 0.0; } template @@ -259,6 +344,116 @@ GeneralizedIterativeClosestPoint:: "solver didn't converge!"); } +template +void +GeneralizedIterativeClosestPoint:: + estimateRigidTransformationNewton(const PointCloudSource& cloud_src, + const pcl::Indices& indices_src, + const PointCloudTarget& cloud_tgt, + const pcl::Indices& indices_tgt, + Matrix4& transformation_matrix) +{ + // need at least min_number_correspondences_ samples + if (indices_src.size() < min_number_correspondences_) { + PCL_THROW_EXCEPTION(NotEnoughPointsException, + "[pcl::GeneralizedIterativeClosestPoint::" + "estimateRigidTransformationNewton] Need " + "at least " + << min_number_correspondences_ + << " points to estimate a transform! " + "Source and target have " + << indices_src.size() << " points!"); + return; + } + // Set the initial solution + Vector6d x = Vector6d::Zero(); + // translation part + x[0] = transformation_matrix(0, 3); + x[1] = transformation_matrix(1, 3); + x[2] = transformation_matrix(2, 3); + // rotation part (Z Y X euler angles convention) + // see: https://en.wikipedia.org/wiki/Rotation_matrix#General_rotations + x[3] = std::atan2(transformation_matrix(2, 1), transformation_matrix(2, 2)); + x[4] = std::asin( + std::min(1.0, std::max(-1.0, -transformation_matrix(2, 0)))); + x[5] = std::atan2(transformation_matrix(1, 0), transformation_matrix(0, 0)); + + // Set temporary pointers + tmp_src_ = &cloud_src; + tmp_tgt_ = &cloud_tgt; + tmp_idx_src_ = &indices_src; + tmp_idx_tgt_ = &indices_tgt; + + // Optimize using Newton + OptimizationFunctorWithIndices functor(this); + Eigen::Matrix hessian; + Eigen::Matrix gradient; + double current_x_value = functor(x); + functor.dfddf(x, gradient, hessian); + Eigen::Matrix delta; + int inner_iterations_ = 0; + do { + ++inner_iterations_; + // compute descent direction from hessian and gradient. Take special measures if + // hessian is not positive-definite (positive Eigenvalues) + Eigen::SelfAdjointEigenSolver> eigensolver(hessian); + Eigen::Matrix inverted_eigenvalues = + Eigen::Matrix::Zero(); + for (int i = 0; i < 6; ++i) { + const double ev = eigensolver.eigenvalues()[i]; + if (ev < 0) + inverted_eigenvalues(i, i) = 1.0 / eigensolver.eigenvalues()[5]; + else + inverted_eigenvalues(i, i) = 1.0 / ev; + } + delta = eigensolver.eigenvectors() * inverted_eigenvalues * + eigensolver.eigenvectors().transpose() * gradient; + + // simple line search to guarantee a decrease in the function value + double alpha = 1.0; + double candidate_x_value; + bool improvement_found = false; + for (int i = 0; i < 10; ++i, alpha /= 2) { + Vector6d candidate_x = x - alpha * delta; + candidate_x_value = functor(candidate_x); + if (candidate_x_value < current_x_value) { + PCL_DEBUG("[estimateRigidTransformationNewton] Using stepsize=%g, function " + "value previously: %g, now: %g, " + "improvement: %g\n", + alpha, + current_x_value, + candidate_x_value, + current_x_value - candidate_x_value); + x = candidate_x; + current_x_value = candidate_x_value; + improvement_found = true; + break; + } + } + if (!improvement_found) { + PCL_DEBUG("[estimateRigidTransformationNewton] finishing because no progress\n"); + break; + } + functor.dfddf(x, gradient, hessian); + if (gradient.head<3>().norm() < translation_gradient_tolerance_ && + gradient.tail<3>().norm() < rotation_gradient_tolerance_) { + PCL_DEBUG("[estimateRigidTransformationNewton] finishing because gradient below " + "threshold: translation: %g<%g, rotation: %g<%g\n", + gradient.head<3>().norm(), + translation_gradient_tolerance_, + gradient.tail<3>().norm(), + rotation_gradient_tolerance_); + break; + } + } while (inner_iterations_ < max_inner_iterations_); + PCL_DEBUG("[estimateRigidTransformationNewton] solver finished after %i iterations " + "(of max %i)\n", + inner_iterations_, + max_inner_iterations_); + transformation_matrix.setIdentity(); + applyState(transformation_matrix, x); +} + template inline double GeneralizedIterativeClosestPoint:: @@ -377,6 +572,152 @@ GeneralizedIterativeClosestPoint:: gicp_->computeRDerivative(x, dCost_dR_T, g); } +template +inline void +GeneralizedIterativeClosestPoint:: + OptimizationFunctorWithIndices::dfddf(const Vector6d& x, + Vector6d& gradient, + Matrix6d& hessian) +{ + Matrix4 transformation_matrix = gicp_->base_transformation_; + gicp_->applyState(transformation_matrix, x); + const Eigen::Matrix4f transformation_matrix_float = + transformation_matrix.template cast(); + const Eigen::Matrix4f base_transformation_float = + gicp_->base_transformation_.template cast(); + // Zero out gradient and hessian + gradient.setZero(); + hessian.setZero(); + // Helper matrices + Eigen::Matrix3d dR_dPhi; + Eigen::Matrix3d dR_dTheta; + Eigen::Matrix3d dR_dPsi; + gicp_->getRDerivatives(x[3], x[4], x[5], dR_dPhi, dR_dTheta, dR_dPsi); + Eigen::Matrix3d ddR_dPhi_dPhi; + Eigen::Matrix3d ddR_dPhi_dTheta; + Eigen::Matrix3d ddR_dPhi_dPsi; + Eigen::Matrix3d ddR_dTheta_dTheta; + Eigen::Matrix3d ddR_dTheta_dPsi; + Eigen::Matrix3d ddR_dPsi_dPsi; + gicp_->getR2ndDerivatives(x[3], + x[4], + x[5], + ddR_dPhi_dPhi, + ddR_dPhi_dTheta, + ddR_dPhi_dPsi, + ddR_dTheta_dTheta, + ddR_dTheta_dPsi, + ddR_dPsi_dPsi); + Eigen::Matrix3d dCost_dR_T = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T1 = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T2 = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T3 = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T1b = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T2b = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d dCost_dR_T3b = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d hessian_rot_phi = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d hessian_rot_theta = Eigen::Matrix3d::Zero(); + Eigen::Matrix3d hessian_rot_psi = Eigen::Matrix3d::Zero(); + Eigen::Matrix hessian_rot_tmp = Eigen::Matrix::Zero(); + + int m = static_cast(gicp_->tmp_idx_src_->size()); + for (int i = 0; i < m; ++i) { + // The last coordinate, p_src[3] is guaranteed to be set to 1.0 in registration.hpp + const auto& src_idx = (*gicp_->tmp_idx_src_)[i]; + Vector4fMapConst p_src = (*gicp_->tmp_src_)[src_idx].getVector4fMap(); + // The last coordinate, p_tgt[3] is guaranteed to be set to 1.0 in registration.hpp + Vector4fMapConst p_tgt = + (*gicp_->tmp_tgt_)[(*gicp_->tmp_idx_tgt_)[i]].getVector4fMap(); + Eigen::Vector4f p_trans_src(transformation_matrix_float * p_src); + // The last coordinate is still guaranteed to be set to 1.0 + // The d here is the negative of the d in the paper + const Eigen::Vector3d d(p_trans_src[0] - p_tgt[0], + p_trans_src[1] - p_tgt[1], + p_trans_src[2] - p_tgt[2]); + const Eigen::Matrix3d& M = gicp_->mahalanobis(src_idx); + const Eigen::Vector3d Md(M * d); // Md = M*d + gradient.head<3>() += Md; // translation gradient + hessian.block<3, 3>(0, 0) += M; // translation-translation hessian + p_trans_src = base_transformation_float * p_src; + const Eigen::Vector3d p_base_src(p_trans_src[0], p_trans_src[1], p_trans_src[2]); + dCost_dR_T.noalias() += p_base_src * Md.transpose(); + dCost_dR_T1b += p_base_src[0] * M; + dCost_dR_T2b += p_base_src[1] * M; + dCost_dR_T3b += p_base_src[2] * M; + hessian_rot_tmp.noalias() += + Eigen::Map>{M.data()} * + (Eigen::Matrix() << p_base_src[0] * p_base_src[0], + p_base_src[0] * p_base_src[1], + p_base_src[0] * p_base_src[2], + p_base_src[1] * p_base_src[1], + p_base_src[1] * p_base_src[2], + p_base_src[2] * p_base_src[2]) + .finished(); + } + gradient.head<3>() *= 2.0 / m; // translation gradient + dCost_dR_T *= 2.0 / m; + gicp_->computeRDerivative(x, dCost_dR_T, gradient); // rotation gradient + hessian.block<3, 3>(0, 0) *= 2.0 / m; // translation-translation hessian + // translation-rotation hessian + dCost_dR_T1.row(0) = dCost_dR_T1b.col(0); + dCost_dR_T1.row(1) = dCost_dR_T2b.col(0); + dCost_dR_T1.row(2) = dCost_dR_T3b.col(0); + dCost_dR_T2.row(0) = dCost_dR_T1b.col(1); + dCost_dR_T2.row(1) = dCost_dR_T2b.col(1); + dCost_dR_T2.row(2) = dCost_dR_T3b.col(1); + dCost_dR_T3.row(0) = dCost_dR_T1b.col(2); + dCost_dR_T3.row(1) = dCost_dR_T2b.col(2); + dCost_dR_T3.row(2) = dCost_dR_T3b.col(2); + dCost_dR_T1 *= 2.0 / m; + dCost_dR_T2 *= 2.0 / m; + dCost_dR_T3 *= 2.0 / m; + hessian(3, 0) = (dR_dPhi * dCost_dR_T1).trace(); + hessian(4, 0) = (dR_dTheta * dCost_dR_T1).trace(); + hessian(5, 0) = (dR_dPsi * dCost_dR_T1).trace(); + hessian(3, 1) = (dR_dPhi * dCost_dR_T2).trace(); + hessian(4, 1) = (dR_dTheta * dCost_dR_T2).trace(); + hessian(5, 1) = (dR_dPsi * dCost_dR_T2).trace(); + hessian(3, 2) = (dR_dPhi * dCost_dR_T3).trace(); + hessian(4, 2) = (dR_dTheta * dCost_dR_T3).trace(); + hessian(5, 2) = (dR_dPsi * dCost_dR_T3).trace(); + hessian.block<3, 3>(0, 3) = hessian.block<3, 3>(3, 0).transpose(); + // rotation-rotation hessian + int lookup[3][3] = {{0, 1, 2}, {1, 3, 4}, {2, 4, 5}}; + for (int l = 0; l < 3; ++l) { + for (int i = 0; i < 3; ++i) { + double phi_tmp = 0.0, theta_tmp = 0.0, psi_tmp = 0.0; + for (int j = 0; j < 3; ++j) { + for (int k = 0; k < 3; ++k) { + phi_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dPhi(j, k); + theta_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dTheta(j, k); + psi_tmp += hessian_rot_tmp(3 * j + i, lookup[l][k]) * dR_dPsi(j, k); + } + } + hessian_rot_phi(i, l) = phi_tmp; + hessian_rot_theta(i, l) = theta_tmp; + hessian_rot_psi(i, l) = psi_tmp; + } + } + hessian_rot_phi *= 2.0 / m; + hessian_rot_theta *= 2.0 / m; + hessian_rot_psi *= 2.0 / m; + hessian(3, 3) = (dR_dPhi.transpose() * hessian_rot_phi).trace() + + (ddR_dPhi_dPhi * dCost_dR_T).trace(); + hessian(3, 4) = (dR_dPhi.transpose() * hessian_rot_theta).trace() + + (ddR_dPhi_dTheta * dCost_dR_T).trace(); + hessian(3, 5) = (dR_dPhi.transpose() * hessian_rot_psi).trace() + + (ddR_dPhi_dPsi * dCost_dR_T).trace(); + hessian(4, 4) = (dR_dTheta.transpose() * hessian_rot_theta).trace() + + (ddR_dTheta_dTheta * dCost_dR_T).trace(); + hessian(4, 5) = (dR_dTheta.transpose() * hessian_rot_psi).trace() + + (ddR_dTheta_dPsi * dCost_dR_T).trace(); + hessian(5, 5) = (dR_dPsi.transpose() * hessian_rot_psi).trace() + + (ddR_dPsi_dPsi * dCost_dR_T).trace(); + hessian(4, 3) = hessian(3, 4); + hessian(5, 3) = hessian(3, 5); + hessian(5, 4) = hessian(4, 5); +} + template inline BFGSSpace::Status GeneralizedIterativeClosestPoint:: From 86e89c2f5e48f12ea085899a57d87cb9cbf1f86f Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Mon, 25 Sep 2023 11:20:32 +0200 Subject: [PATCH 128/288] Fix GICP6D test M_PI/0.1 would mean 10*M_PI or 5 times 360 degrees. GICP can't reliably find the correct solution for such large rotations (it might e.g. align the object upside down). When using 0.25*M_PI (45 degrees), the transformation is the correct one, and we can even tighten the error threshold to 1e-4 --- 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 0d3b7dcdb6c..8b90cab08b7 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -593,7 +593,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D) PointCloud::Ptr src_full (new PointCloud); copyPointCloud (cloud_with_color, *src_full); PointCloud::Ptr tgt_full (new PointCloud); - sampleRandomTransform (delta_transform, M_PI/0.1, .03); + sampleRandomTransform (delta_transform, 0.25*M_PI, .03); pcl::transformPointCloud (cloud_with_color, *tgt_full, delta_transform); PointCloud output; @@ -616,7 +616,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D) // Register reg.align (output); EXPECT_EQ (output.size (), src->size ()); - EXPECT_LT (reg.getFitnessScore (), 0.003); + EXPECT_LT (reg.getFitnessScore (), 1e-4); // Check again, for all possible caching schemes for (int iter = 0; iter < 4; iter++) @@ -637,7 +637,7 @@ TEST (PCL, GeneralizedIterativeClosestPoint6D) // Register reg.align (output); EXPECT_EQ (output.size (), src->size ()); - EXPECT_LT (reg.getFitnessScore (), 0.003); + EXPECT_LT (reg.getFitnessScore (), 1e-4); } } From 0e0a942cfa6ea6563c2c451fb6e842a0904f67cf Mon Sep 17 00:00:00 2001 From: zhulingfeng <664675691@qq.com> Date: Tue, 3 Oct 2023 16:22:44 +0800 Subject: [PATCH 129/288] [surface] Fix memory leak bug of poisson reconstruction Fix memory leak when call pcl::Poisson::performReconstruction by release dot table memory according to input flags in BSplineData::clearDotTables. --- .../include/pcl/surface/3rdparty/poisson4/bspline_data.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp b/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp index 1fcab8091f8..7fbbbf2132b 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp +++ b/surface/include/pcl/surface/3rdparty/poisson4/bspline_data.hpp @@ -291,7 +291,11 @@ namespace pcl { if (flags & VV_DOT_FLAG) { delete[] vvDotTable ; vvDotTable = NULL; + } + if (flags & DV_DOT_FLAG) { delete[] dvDotTable ; dvDotTable = NULL; + } + if (flags & DD_DOT_FLAG) { delete[] ddDotTable ; ddDotTable = NULL; } } From e2055de2979d42b8f16e64923c04c883f310950f Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 15:03:15 +0200 Subject: [PATCH 130/288] Update CI versions Update to MacOS 13, update README badges, update compiler versions for ubuntu-variety --- .ci/azure-pipelines/azure-pipelines.yaml | 6 +++--- .ci/azure-pipelines/ubuntu-variety.yaml | 6 +++--- README.md | 12 ++++++------ 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index bb3c54e6a70..c40dbae510d 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -76,9 +76,9 @@ stages: Big Sur 11: VMIMAGE: 'macOS-11' OSX_VERSION: '11' - Monterey 12: - VMIMAGE: 'macOS-12' - OSX_VERSION: '12' + Ventura 13: + VMIMAGE: 'macOS-13' + OSX_VERSION: '13' timeoutInMinutes: 0 variables: BUILD_DIR: '$(Agent.WorkFolder)/build' diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml index e085ba0346d..e836a655c7b 100644 --- a/.ci/azure-pipelines/ubuntu-variety.yaml +++ b/.ci/azure-pipelines/ubuntu-variety.yaml @@ -32,9 +32,9 @@ jobs: POSSIBLE_VTK_VERSION=("9") \ POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \ POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \ - POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \ - POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16") \ - POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16") \ + POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \ + POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \ + POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16" "clang++-17") \ CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \ dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \ echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs" diff --git a/README.md b/README.md index ca2b0d9b9fd..5301c088978 100644 --- a/README.md +++ b/README.md @@ -21,21 +21,21 @@ If you really need access to the old website, please use [the copy made by the i Continuous integration ---------------------- [ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master -[ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2020.04%20Clang&label=Ubuntu%2020.04%20Clang -[ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2022.04%20GCC -[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2022.04%20GCC&label=Ubuntu%2023.04%20GCC +[ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2020.04%20GCC&label=Ubuntu%2020.04%20GCC +[ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2022.04%20Clang&label=Ubuntu%2022.04%20Clang +[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2023.04%20GCC&label=Ubuntu%2023.04%20GCC [ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86 [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64 [ci-macos-11]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Big%20Sur%2011&label=macOS%20Big%20Sur%2011 -[ci-macos-12]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Monterey%2012&label=macOS%20Monterey%2012 +[ci-macos-13]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Ventura%2013&label=macOS%20Ventura%2013 [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-22.04]][ci-latest-build] | +Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
      [![Status][ci-ubuntu-22.04]][ci-latest-build]
      [![Status][ci-ubuntu-23.04]][ci-latest-build] | Windows | [![Status][ci-windows-x86]][ci-latest-build]
      [![Status][ci-windows-x64]][ci-latest-build] | -macOS | [![Status][ci-macos-11]][ci-latest-build]
      [![Status][ci-macos-12]][ci-latest-build] | +macOS | [![Status][ci-macos-11]][ci-latest-build]
      [![Status][ci-macos-13]][ci-latest-build] | Documentation | [![Status][ci-docs]][ci-latest-docs] | Community From c6e36040d15110a63922882c67031c8e8b515940 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 15:10:42 +0200 Subject: [PATCH 131/288] Fix problem when building against Eigen master See also https://gitlab.com/libeigen/eigen/-/commit/f2984cd0778dd0a1d7e74216d826eaff2bc6bfab --- PCLConfig.cmake.in | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index aede14383b2..1c8a1bd59c9 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -120,6 +120,10 @@ macro(find_eigen3) if(NOT EIGEN3_FOUND AND Eigen3_FOUND) set(EIGEN3_FOUND ${Eigen3_FOUND}) endif() + # In very new Eigen versions, EIGEN3_INCLUDE_DIR(S) is not defined any more, only the target: + if(TARGET Eigen3::Eigen) + set(EIGEN3_LIBRARIES Eigen3::Eigen) + endif() endmacro() #remove this as soon as qhull is shipped with FindQhull.cmake From 9a12d817b99a6f0aa02c8e89c1c6fdb89cbe74c3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 15:19:51 +0200 Subject: [PATCH 132/288] Improve documentations/tutorials --- doc/tutorials/content/gasd_estimation.rst | 4 ++-- features/include/pcl/features/pfhrgb.h | 3 +++ filters/include/pcl/filters/approximate_voxel_grid.h | 3 ++- recognition/include/pcl/recognition/implicit_shape_model.h | 2 +- registration/include/pcl/registration/gicp.h | 4 ++-- registration/include/pcl/registration/ndt.h | 1 + registration/include/pcl/registration/ndt_2d.h | 1 + registration/include/pcl/registration/ppf_registration.h | 1 + 8 files changed, 13 insertions(+), 6 deletions(-) diff --git a/doc/tutorials/content/gasd_estimation.rst b/doc/tutorials/content/gasd_estimation.rst index bc28188c385..f725e4ea69f 100644 --- a/doc/tutorials/content/gasd_estimation.rst +++ b/doc/tutorials/content/gasd_estimation.rst @@ -98,7 +98,7 @@ The following code snippet will estimate a GASD shape + color descriptor for an gasd.compute (descriptor); // Get the alignment transform - Eigen::Matrix4f trans = gasd.getTransform (trans); + Eigen::Matrix4f trans = gasd.getTransform (); // Unpack histogram bins for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i) @@ -131,7 +131,7 @@ The following code snippet will estimate a GASD shape only descriptor for an inp gasd.compute (descriptor); // Get the alignment transform - Eigen::Matrix4f trans = gasd.getTransform (trans); + Eigen::Matrix4f trans = gasd.getTransform (); // Unpack histogram bins for (std::size_t i = 0; i < std::size_t( descriptor[0].descriptorSize ()); ++i) diff --git a/features/include/pcl/features/pfhrgb.h b/features/include/pcl/features/pfhrgb.h index f42f26e11b4..de87ce6bd94 100644 --- a/features/include/pcl/features/pfhrgb.h +++ b/features/include/pcl/features/pfhrgb.h @@ -43,6 +43,9 @@ namespace pcl { + /** \brief Similar to the Point Feature Histogram descriptor, but also takes color into account. See also \ref PFHEstimation + * \ingroup features + */ template class PFHRGBEstimation : public FeatureFromNormals { diff --git a/filters/include/pcl/filters/approximate_voxel_grid.h b/filters/include/pcl/filters/approximate_voxel_grid.h index 4e1b6319513..95e16a1d868 100644 --- a/filters/include/pcl/filters/approximate_voxel_grid.h +++ b/filters/include/pcl/filters/approximate_voxel_grid.h @@ -90,7 +90,8 @@ namespace pcl }; /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. - * + * Thus, this is similar to the \ref VoxelGrid filter. + * This class works best if points that are stored in memory next to each other (in the input point cloud), are also somewhat close in 3D euclidean space (this is for example usually the case for organized point clouds). If the points have no storage order (e.g. in synthetic, randomly generated point clouds), this class will give very poor results, and \ref VoxelGrid should be used instead. * \author James Bowman, Radu B. Rusu * \ingroup filters */ diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index 652200dd596..c32f55150f4 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -227,7 +227,7 @@ namespace pcl { /** \brief This class implements Implicit Shape Model algorithm described in * "Hough Transforms and 3D SURF for robust three dimensional classication" - * by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool. + * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool. * It has two main member functions. One for training, using the data for which we know * which class it belongs to. And second for investigating a cloud for the presence * of the class of interest. diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 2eae855abbf..b0fad8046cb 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -381,8 +381,8 @@ class GeneralizedIterativeClosestPoint /** \brief compute points covariances matrices according to the K nearest * neighbors. K is set via setCorrespondenceRandomness() method. - * \param cloud pointer to point cloud - * \param tree KD tree performer for nearest neighbors search + * \param[in] cloud pointer to point cloud + * \param[in] tree KD tree performer for nearest neighbors search * \param[out] cloud_covariances covariances matrices for each point in the cloud */ template diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index fbe2b16f5b5..81788ed687d 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -60,6 +60,7 @@ namespace pcl { * Optimization Theory and Methods: Nonlinear Programming. 89-100 * \note Math refactored by Todor Stoyanov. * \author Brian Okorn (Space and Naval Warfare Systems Center Pacific) + * \ingroup registration */ template class NormalDistributionsTransform diff --git a/registration/include/pcl/registration/ndt_2d.h b/registration/include/pcl/registration/ndt_2d.h index 8b3a927a84b..e65af5ab192 100644 --- a/registration/include/pcl/registration/ndt_2d.h +++ b/registration/include/pcl/registration/ndt_2d.h @@ -54,6 +54,7 @@ namespace pcl { * 2743–2748, Las Vegas, USA, October 2003. * * \author James Crosby + * \ingroup registration */ template class NormalDistributionsTransform2D : public Registration { diff --git a/registration/include/pcl/registration/ppf_registration.h b/registration/include/pcl/registration/ppf_registration.h index 81e783dd7f3..0e4bacea2ec 100644 --- a/registration/include/pcl/registration/ppf_registration.h +++ b/registration/include/pcl/registration/ppf_registration.h @@ -169,6 +169,7 @@ class PCL_EXPORTS PPFHashMapSearch { * 13-18 June 2010, San Francisco, CA * * \note This class works in tandem with the PPFEstimation class + * \ingroup registration * * \author Alexandru-Eugen Ichim */ From 55b57aee328ac9b1e70d66ae6eb14bfb55cc2631 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 15:27:14 +0200 Subject: [PATCH 133/288] Replace io functions based on VTK with PCL-native functions This is a first step to make the io module not depend on VTK any more --- .../tools/standalone_texture_mapping.cpp | 3 ++- io/src/davidsdk_grabber.cpp | 12 ++++++------ tools/mesh_sampling.cpp | 3 ++- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index 657927043c1..d1570464c87 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -48,6 +48,7 @@ #include #include #include +#include using namespace pcl; @@ -405,7 +406,7 @@ main (int argc, char** argv) // read mesh from plyfile PCL_INFO ("\nLoading mesh from file %s...\n", argv[1]); pcl::PolygonMesh triangles; - pcl::io::loadPolygonFilePLY(argv[1], triangles); + pcl::io::loadPLYFile(argv[1], triangles); pcl::PointCloud::Ptr cloud (new pcl::PointCloud); pcl::fromPCLPointCloud2(triangles.cloud, *cloud); diff --git a/io/src/davidsdk_grabber.cpp b/io/src/davidsdk_grabber.cpp index d13fb4663d7..4c3da25fedd 100644 --- a/io/src/davidsdk_grabber.cpp +++ b/io/src/davidsdk_grabber.cpp @@ -281,12 +281,12 @@ pcl::DavidSDKGrabber::grabSingleCloud (pcl::PointCloud &cloud) pcl::PolygonMesh mesh; if (file_format_ == "obj") { - if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0) + if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0) return (false); } else if (file_format_ == "ply") { - if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0) + if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0) return (false); } else if (file_format_ == "stl") @@ -323,12 +323,12 @@ pcl::DavidSDKGrabber::grabSingleMesh (pcl::PolygonMesh &mesh) if (file_format_ == "obj") { - if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, mesh) == 0) + if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, mesh) == 0) return (false); } else if (file_format_ == "ply") { - if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, mesh) == 0) + if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, mesh) == 0) return (false); } else if (file_format_ == "stl") @@ -400,12 +400,12 @@ pcl::DavidSDKGrabber::processGrabbing () if (file_format_ == "obj") { - if (pcl::io::loadPolygonFileOBJ (local_path_ + "scan." + file_format_, *mesh) == 0) + if (pcl::io::loadOBJFile (local_path_ + "scan." + file_format_, *mesh) == 0) return; } else if (file_format_ == "ply") { - if (pcl::io::loadPolygonFilePLY (local_path_ + "scan." + file_format_, *mesh) == 0) + if (pcl::io::loadPLYFile (local_path_ + "scan." + file_format_, *mesh) == 0) return; } else if (file_format_ == "stl") diff --git a/tools/mesh_sampling.cpp b/tools/mesh_sampling.cpp index 79f916ce6fc..5472545cd31 100644 --- a/tools/mesh_sampling.cpp +++ b/tools/mesh_sampling.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include #include @@ -244,7 +245,7 @@ main (int argc, char **argv) if (ply_file_indices.size () == 1) { pcl::PolygonMesh mesh; - pcl::io::loadPolygonFilePLY (argv[ply_file_indices[0]], mesh); + pcl::io::loadPLYFile (argv[ply_file_indices[0]], mesh); pcl::io::mesh2vtk (mesh, polydata1); } else if (obj_file_indices.size () == 1) From 2c32f359fec181756d57e742bb8efe828ec76dbd Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 16:12:13 +0200 Subject: [PATCH 134/288] Fix maybe-uninitialized warnings by checking function results --- features/include/pcl/features/impl/gasd.hpp | 11 ++++++----- surface/include/pcl/surface/impl/grid_projection.hpp | 6 +++++- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/features/include/pcl/features/impl/gasd.hpp b/features/include/pcl/features/impl/gasd.hpp index 73074b63fbd..47522c57631 100644 --- a/features/include/pcl/features/impl/gasd.hpp +++ b/features/include/pcl/features/impl/gasd.hpp @@ -76,11 +76,12 @@ pcl::GASDEstimation::computeAlignmentTransform () Eigen::Vector4f centroid; Eigen::Matrix3f covariance_matrix; - // compute centroid of the object's partial view - pcl::compute3DCentroid (*surface_, *indices_, centroid); - - // compute covariance matrix from points and centroid of the object's partial view - pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix); + // compute centroid of the object's partial view, then compute covariance matrix from points and centroid of the object's partial view + if (pcl::compute3DCentroid (*surface_, *indices_, centroid) == 0 || + pcl::computeCovarianceMatrix (*surface_, *indices_, centroid, covariance_matrix) == 0) { + PCL_ERROR("[pcl::GASDEstimation::computeAlignmentTransform] Surface cloud or indices are empty!\n"); + return; + } Eigen::Matrix3f eigenvectors; Eigen::Vector3f eigenvalues; diff --git a/surface/include/pcl/surface/impl/grid_projection.hpp b/surface/include/pcl/surface/impl/grid_projection.hpp index 7264ff26af6..c5e232fa606 100644 --- a/surface/include/pcl/surface/impl/grid_projection.hpp +++ b/surface/include/pcl/surface/impl/grid_projection.hpp @@ -319,7 +319,11 @@ pcl::GridProjection::getProjectionWithPlaneFit (const Eigen::Vector4f & Eigen::Matrix3f covariance_matrix; Eigen::Vector4f xyz_centroid; - computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid); + if (computeMeanAndCovarianceMatrix (*data_, pt_union_indices, covariance_matrix, xyz_centroid) == 0) { + PCL_ERROR("[pcl::GridProjection::getProjectionWithPlaneFit] cloud or indices are empty!\n"); + projection = p; + return; + } // Get the plane normal EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value; From 5e640dd0c26b487171eb60143cfe98dc09e8c2c4 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 17:22:57 +0200 Subject: [PATCH 135/288] Improve logging --- io/include/pcl/io/ply/ply_parser.h | 12 ++++++------ io/src/ply_io.cpp | 3 ++- .../pcl/sample_consensus/impl/sac_model_cone.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_cylinder.hpp | 2 +- .../pcl/sample_consensus/impl/sac_model_line.hpp | 3 +++ .../impl/sac_model_normal_sphere.hpp | 6 +++--- .../include/pcl/sample_consensus/sac_model_sphere.h | 8 ++++++-- visualization/src/pcl_visualizer.cpp | 2 +- 8 files changed, 23 insertions(+), 15 deletions(-) diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h index 2e0390072af..3023d566607 100644 --- a/io/include/pcl/io/ply/ply_parser.h +++ b/io/include/pcl/io/ply/ply_parser.h @@ -563,7 +563,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format, if (!istream || !isspace (space)) { if (error_callback_) - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing scalar property (file format: ascii)"); return (false); } if (scalar_property_callback) @@ -575,7 +575,7 @@ inline bool pcl::io::ply::ply_parser::parse_scalar_property (format_type format, if (!istream) { if (error_callback_) - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing scalar property (file format: binary)"); return (false); } if (((format == binary_big_endian_format) && (host_byte_order == little_endian_byte_order)) || @@ -608,7 +608,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s { if (error_callback_) { - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing list (file format: ascii)"); } return (false); } @@ -639,7 +639,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s { if (error_callback_) { - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing list (file format: ascii)"); } return (false); } @@ -665,7 +665,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s { if (error_callback_) { - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing list (file format: binary)"); } return (false); } @@ -678,7 +678,7 @@ inline bool pcl::io::ply::ply_parser::parse_list_property (format_type format, s istream.read (reinterpret_cast (&value), sizeof (scalar_type)); if (!istream) { if (error_callback_) { - error_callback_ (line_number_, "parse error"); + error_callback_ (line_number_, "error while parsing list (file format: binary)"); } return (false); } diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index b8c94329723..aaedca8f39d 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -566,7 +566,7 @@ pcl::PLYReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c orientation_ = Eigen::Matrix3f::Identity (); if (!parse (file_name)) { - PCL_ERROR ("[pcl::PLYReader::read] problem parsing header!\n"); + PCL_ERROR ("[pcl::PLYReader::readHeader] problem parsing header!\n"); return (-1); } cloud_->row_step = cloud_->point_step * cloud_->width; @@ -676,6 +676,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, const int offset) { + PCL_DEBUG("[pcl::PLYReader::read] Reading PolygonMesh from file: %s.\n", file_name.c_str()); // kept only for backward compatibility int data_type; unsigned int data_idx; 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 2f7118e7058..e0be7718f0d 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 @@ -69,7 +69,7 @@ pcl::SampleConsensusModelCone::computeModelCoefficients ( if (!normals_) { - PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given!\n"); + PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n"); return (false); } 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 03e26680a39..6ae067ad3c4 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 @@ -84,7 +84,7 @@ pcl::SampleConsensusModelCylinder::computeModelCoefficients ( if (!normals_) { - PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given!\n"); + PCL_ERROR ("[pcl::SampleConsensusModelCylinder::computeModelCoefficients] No input dataset containing normals was given! Use setInputNormals\n"); return (false); } diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp index 0e718f10072..94de2e7af8d 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_line.hpp @@ -251,7 +251,10 @@ pcl::SampleConsensusModelLine::projectPoints ( { // Needs a valid model coefficients if (!isModelValid (model_coefficients)) + { + PCL_ERROR ("[pcl::SampleConsensusModelLine::projectPoints] Given model is invalid!\n"); return; + } // Obtain the line point and direction Eigen::Vector4f line_pt (model_coefficients[0], model_coefficients[1], model_coefficients[2], 0.0f); diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp index b83d0f70ec4..a29a7067baf 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_sphere.hpp @@ -51,7 +51,7 @@ pcl::SampleConsensusModelNormalSphere::selectWithinDistance ( { if (!normals_) { - PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given!\n"); + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::selectWithinDistance] No input dataset containing normals was given! Use setInputNormals\n"); inliers.clear (); return; } @@ -112,7 +112,7 @@ pcl::SampleConsensusModelNormalSphere::countWithinDistance ( { if (!normals_) { - PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n"); + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n"); return (0); } @@ -163,7 +163,7 @@ pcl::SampleConsensusModelNormalSphere::getDistancesToModel ( { if (!normals_) { - PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given!\n"); + PCL_ERROR ("[pcl::SampleConsensusModelNormalSphere::getDistancesToModel] No input dataset containing normals was given! Use setInputNormals\n"); return; } diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h index 1e15149953c..537fcb3d0dd 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h @@ -223,10 +223,14 @@ namespace pcl if (!SampleConsensusModel::isModelValid (model_coefficients)) return (false); - if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_) + if (radius_min_ != -std::numeric_limits::max() && model_coefficients[3] < radius_min_) { + PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is smaller than user specified minimum radius %g\n", model_coefficients[3], radius_min_); return (false); - if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_) + } + if (radius_max_ != std::numeric_limits::max() && model_coefficients[3] > radius_max_) { + PCL_DEBUG("[SampleConsensusModelSphere::isModelValid] Model radius %g is bigger than user specified maximum radius %g\n", model_coefficients[3], radius_max_); return (false); + } return (true); } diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index f2eb40e4ff7..06d8fbfbf11 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -1630,7 +1630,7 @@ pcl::visualization::PCLVisualizer::setPointCloudSelected (const bool selected, c if (am_it == cloud_actor_map_->end ()) { - pcl::console::print_error ("[setPointCloudRenderingProperties] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ()); + pcl::console::print_error ("[setPointCloudSelected] Could not find any PointCloud datasets with id <%s>!\n", id.c_str ()); return (false); } // Get the actor pointer From 7c81724196332559b9bf8fe6ba3b0ced53589ae5 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 12 Oct 2023 19:59:41 +0200 Subject: [PATCH 136/288] Reduce number of allocations, for example for kdtree searches KdTree calls vectorize for every point. Before this commit, vectorize unnecessarily allocated and freed memory for evey call. --- common/include/pcl/point_representation.h | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 3d918a86df1..17b2a0d422c 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -158,6 +158,24 @@ namespace pcl delete [] temp; } + void + vectorize (const PointT &p, float* out) const + { + copyToFloatArray (p, out); + if (!alpha_.empty ()) + for (int i = 0; i < nr_dimensions_; ++i) + out[i] *= alpha_[i]; + } + + void + vectorize (const PointT &p, std::vector &out) const + { + copyToFloatArray (p, out.data()); + if (!alpha_.empty ()) + for (int i = 0; i < nr_dimensions_; ++i) + out[i] *= alpha_[i]; + } + /** \brief Set the rescale values to use when vectorizing points * \param[in] rescale_array The array/vector of rescale values. Can be of any type that implements the [] operator. */ From 2e78e75426e113d5bbe75c059147c2d998c02067 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 14 Oct 2023 17:32:40 +0200 Subject: [PATCH 137/288] Add checks for valid radius and max_results in gpu/features Fixes https://github.com/PointCloudLibrary/pcl/issues/5844 --- gpu/features/src/features.cpp | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/gpu/features/src/features.cpp b/gpu/features/src/features.cpp index a0172c3a2cb..5f356ef94df 100644 --- a/gpu/features/src/features.cpp +++ b/gpu/features/src/features.cpp @@ -103,6 +103,10 @@ void pcl::gpu::NormalEstimation::getViewPoint (float &vpx, float &vpy, float &vp void pcl::gpu::NormalEstimation::compute(Normals& normals) { assert(!cloud_.empty()); + if (radius_ <= 0.0f || max_results_ <= 0) { + pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__); + return; + } PointCloud& surface = surface_.empty() ? cloud_ : surface_; @@ -145,6 +149,10 @@ void pcl::gpu::PFHEstimation::compute(const PointCloud& cloud, const Normals& no void pcl::gpu::PFHEstimation::compute(DeviceArray2D& features) { + if (radius_ <= 0.0f || max_results_ <= 0) { + pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__); + return; + } PointCloud& surface = surface_.empty() ? cloud_ : surface_; octree_.setCloud(surface); @@ -183,6 +191,10 @@ void pcl::gpu::PFHRGBEstimation::compute(const PointCloud& cloud, const Normals& void pcl::gpu::PFHRGBEstimation::compute(DeviceArray2D& features) { + if (radius_ <= 0.0f || max_results_ <= 0) { + pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__); + return; + } PointCloud& surface = surface_.empty() ? cloud_ : surface_; octree_.setCloud(surface); @@ -231,6 +243,10 @@ void pcl::gpu::FPFHEstimation::compute(const PointCloud& cloud, const Normals& n void pcl::gpu::FPFHEstimation::compute(DeviceArray2D& features) { + if (radius_ <= 0.0f || max_results_ <= 0) { + pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__); + return; + } bool hasInds = !indices_.empty() && indices_.size() != cloud_.size(); bool hasSurf = !surface_.empty(); @@ -314,6 +330,10 @@ void pcl::gpu::PPFRGBEstimation::compute(DeviceArray& features) void pcl::gpu::PPFRGBRegionEstimation::compute(DeviceArray& features) { + if (radius_ <= 0.0f || max_results_ <= 0) { + pcl::gpu::error("radius and/or max_results is invalid. Set them appropriately with setRadiusSearch", __FILE__, __LINE__); + return; + } static_assert(sizeof(PPFRGBRegionEstimation:: PointType) == sizeof(device:: PointType), "Point sizes do not match"); static_assert(sizeof(PPFRGBRegionEstimation::NormalType) == sizeof(device::NormalType), "Normal sizes do not match"); From dc7aec5d38dc6f2e27d7138c03714dfbcdf28ea6 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Mon, 16 Oct 2023 14:43:33 +0200 Subject: [PATCH 138/288] Let setInputCloud of search methods indicate success or failure (#5840) * Let setInputCloud of search methods indicate success or failure Instead of returning nothing, return true on success and false on failure. This is especially useful for organized neighbor to indicate whether the input cloud is suitable, but might also come in handy for other methods in the future. In filters, use the returned value to abort in case of failure. Fixes https://github.com/PointCloudLibrary/pcl/issues/5819 * fixup --- filters/include/pcl/filters/impl/local_maximum.hpp | 8 +++++++- .../include/pcl/filters/impl/radius_outlier_removal.hpp | 8 +++++++- .../pcl/filters/impl/statistical_outlier_removal.hpp | 8 +++++++- filters/include/pcl/filters/local_maximum.h | 6 ++++++ filters/include/pcl/filters/radius_outlier_removal.h | 6 ++++++ filters/include/pcl/filters/statistical_outlier_removal.h | 6 ++++++ search/include/pcl/search/flann_search.h | 2 +- search/include/pcl/search/impl/flann_search.hpp | 3 ++- search/include/pcl/search/impl/kdtree.hpp | 3 ++- search/include/pcl/search/impl/organized.hpp | 8 +++++--- search/include/pcl/search/impl/search.hpp | 3 ++- search/include/pcl/search/kdtree.h | 2 +- search/include/pcl/search/octree.h | 3 ++- search/include/pcl/search/organized.h | 6 +++--- search/include/pcl/search/search.h | 3 ++- 15 files changed, 59 insertions(+), 16 deletions(-) diff --git a/filters/include/pcl/filters/impl/local_maximum.hpp b/filters/include/pcl/filters/impl/local_maximum.hpp index 59c821bb362..e2ab6c0232b 100644 --- a/filters/include/pcl/filters/impl/local_maximum.hpp +++ b/filters/include/pcl/filters/impl/local_maximum.hpp @@ -97,7 +97,13 @@ pcl::LocalMaximum::applyFilterIndices (Indices &indices) else searcher_.reset (new pcl::search::KdTree (false)); } - searcher_->setInputCloud (cloud_projected); + if (!searcher_->setInputCloud (cloud_projected)) + { + PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } // The arrays to be used indices.resize (indices_->size ()); diff --git a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp index 47c7a8e44be..8e13ec06824 100644 --- a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp +++ b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp @@ -64,7 +64,13 @@ pcl::RadiusOutlierRemoval::applyFilterIndices (Indices &indices) else searcher_.reset (new pcl::search::KdTree (false)); } - searcher_->setInputCloud (input_); + if (!searcher_->setInputCloud (input_)) + { + PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } // The arrays to be used Indices nn_indices (indices_->size ()); diff --git a/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp b/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp index e6c3182292f..0e9359f0bad 100644 --- a/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp +++ b/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp @@ -56,7 +56,13 @@ pcl::StatisticalOutlierRemoval::applyFilterIndices (Indices &indices) else searcher_.reset (new pcl::search::KdTree (false)); } - searcher_->setInputCloud (input_); + if (!searcher_->setInputCloud (input_)) + { + PCL_ERROR ("[pcl::%s::applyFilter] Error when initializing search method!\n", getClassName ().c_str ()); + indices.clear (); + removed_indices_->clear (); + return; + } // The arrays to be used const int searcher_k = mean_k_ + 1; // Find one more, since results include the query point. diff --git a/filters/include/pcl/filters/local_maximum.h b/filters/include/pcl/filters/local_maximum.h index 90755be55e7..cd65455f58d 100644 --- a/filters/include/pcl/filters/local_maximum.h +++ b/filters/include/pcl/filters/local_maximum.h @@ -84,6 +84,12 @@ namespace pcl inline float getRadius () const { return (radius_); } + /** \brief Provide a pointer to the search object. + * Calling this is optional. If not called, the search method will be chosen automatically. + * \param[in] searcher a pointer to the spatial search object. + */ + inline void + setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; } protected: using PCLBase::input_; using PCLBase::indices_; diff --git a/filters/include/pcl/filters/radius_outlier_removal.h b/filters/include/pcl/filters/radius_outlier_removal.h index 677284df29a..23f1d48317d 100644 --- a/filters/include/pcl/filters/radius_outlier_removal.h +++ b/filters/include/pcl/filters/radius_outlier_removal.h @@ -136,6 +136,12 @@ namespace pcl return (min_pts_radius_); } + /** \brief Provide a pointer to the search object. + * Calling this is optional. If not called, the search method will be chosen automatically. + * \param[in] searcher a pointer to the spatial search object. + */ + inline void + setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; } protected: using PCLBase::input_; using PCLBase::indices_; diff --git a/filters/include/pcl/filters/statistical_outlier_removal.h b/filters/include/pcl/filters/statistical_outlier_removal.h index 3c55dc0a25f..4abfd12316e 100644 --- a/filters/include/pcl/filters/statistical_outlier_removal.h +++ b/filters/include/pcl/filters/statistical_outlier_removal.h @@ -140,6 +140,12 @@ namespace pcl return (std_mul_); } + /** \brief Provide a pointer to the search object. + * Calling this is optional. If not called, the search method will be chosen automatically. + * \param[in] searcher a pointer to the spatial search object. + */ + inline void + setSearchMethod (const SearcherPtr &searcher) { searcher_ = searcher; } protected: using PCLBase::input_; using PCLBase::indices_; diff --git a/search/include/pcl/search/flann_search.h b/search/include/pcl/search/flann_search.h index f3de1362268..8d994895c59 100644 --- a/search/include/pcl/search/flann_search.h +++ b/search/include/pcl/search/flann_search.h @@ -254,7 +254,7 @@ namespace pcl * \param[in] cloud the const boost shared pointer to a PointCloud message * \param[in] indices the point indices subset that is to be used from \a cloud */ - void + bool setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ()) override; using Search::nearestKSearch; diff --git a/search/include/pcl/search/impl/flann_search.hpp b/search/include/pcl/search/impl/flann_search.hpp index 94270ba1bcf..218fd690998 100644 --- a/search/include/pcl/search/impl/flann_search.hpp +++ b/search/include/pcl/search/impl/flann_search.hpp @@ -91,7 +91,7 @@ pcl::search::FlannSearch::~FlannSearch() } ////////////////////////////////////////////////////////////////////////////////////////////// -template void +template bool pcl::search::FlannSearch::setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices) { input_ = cloud; @@ -99,6 +99,7 @@ pcl::search::FlannSearch::setInputCloud (const PointCloud convertInputToFlannMatrix (); index_ = creator_->createIndex (input_flann_); index_->buildIndex (); + return true; } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/search/include/pcl/search/impl/kdtree.hpp b/search/include/pcl/search/impl/kdtree.hpp index b3eff66740f..281b1cda360 100644 --- a/search/include/pcl/search/impl/kdtree.hpp +++ b/search/include/pcl/search/impl/kdtree.hpp @@ -72,7 +72,7 @@ pcl::search::KdTree::setEpsilon (float eps) } /////////////////////////////////////////////////////////////////////////////////////////// -template void +template bool pcl::search::KdTree::setInputCloud ( const PointCloudConstPtr& cloud, const IndicesConstPtr& indices) @@ -80,6 +80,7 @@ pcl::search::KdTree::setInputCloud ( tree_->setInputCloud (cloud, indices); input_ = cloud; indices_ = indices; + return true; } /////////////////////////////////////////////////////////////////////////////////////////// diff --git a/search/include/pcl/search/impl/organized.hpp b/search/include/pcl/search/impl/organized.hpp index fc5ce6cfda7..12e6da32962 100644 --- a/search/include/pcl/search/impl/organized.hpp +++ b/search/include/pcl/search/impl/organized.hpp @@ -329,7 +329,7 @@ pcl::search::OrganizedNeighbor::computeCameraMatrix (Eigen::Matrix3f& ca } ////////////////////////////////////////////////////////////////////////////////////////////// -template void +template bool pcl::search::OrganizedNeighbor::estimateProjectionMatrix () { // internally we calculate with double but store the result into float matrices. @@ -337,7 +337,7 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () if (input_->height == 1 || input_->width == 1) { PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not organized!\n", this->getName ().c_str ()); - return; + return false; } const unsigned ySkip = (std::max) (input_->height >> pyramid_level_, static_cast(1)); @@ -363,7 +363,7 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () if (std::abs (residual_sqr) > eps_ * static_cast(indices.size ())) { PCL_ERROR ("[pcl::%s::estimateProjectionMatrix] Input dataset is not from a projective device!\nResidual (MSE) %g, using %d valid points\n", this->getName ().c_str (), residual_sqr / double (indices.size()), indices.size ()); - return; + return false; } // get left 3x3 sub matrix, which contains K * R, with K = camera matrix = [[fx s cx] [0 fy cy] [0 0 1]] @@ -383,8 +383,10 @@ pcl::search::OrganizedNeighbor::estimateProjectionMatrix () if (!projectPoint(test_point, q) || std::abs(q.x-test_index%input_->width)>1 || std::abs(q.y-test_index/input_->width)>1) { PCL_WARN ("[pcl::%s::estimateProjectionMatrix] Input dataset does not seem to be from a projective device! (point %zu (%g,%g,%g) projected to pixel coordinates (%g,%g), but actual pixel coordinates are (%zu,%zu))\n", this->getName ().c_str (), test_index, test_point.x, test_point.y, test_point.z, q.x, q.y, static_cast(test_index%input_->width), static_cast(test_index/input_->width)); + return false; } } + return true; } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/search/include/pcl/search/impl/search.hpp b/search/include/pcl/search/impl/search.hpp index aa8d229fd89..9f24d244acd 100644 --- a/search/include/pcl/search/impl/search.hpp +++ b/search/include/pcl/search/impl/search.hpp @@ -71,12 +71,13 @@ pcl::search::Search::getSortedResults () } /////////////////////////////////////////////////////////////////////////////////////////// -template void +template bool pcl::search::Search::setInputCloud ( const PointCloudConstPtr& cloud, const IndicesConstPtr &indices) { input_ = cloud; indices_ = indices; + return true; } diff --git a/search/include/pcl/search/kdtree.h b/search/include/pcl/search/kdtree.h index c0503a12588..59018eac220 100644 --- a/search/include/pcl/search/kdtree.h +++ b/search/include/pcl/search/kdtree.h @@ -128,7 +128,7 @@ namespace pcl * \param[in] cloud the const boost shared pointer to a PointCloud message * \param[in] indices the point indices subset that is to be used from \a cloud */ - void + bool setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ()) override; diff --git a/search/include/pcl/search/octree.h b/search/include/pcl/search/octree.h index 283a02600e1..827667cb723 100644 --- a/search/include/pcl/search/octree.h +++ b/search/include/pcl/search/octree.h @@ -114,7 +114,7 @@ namespace pcl * \param[in] cloud the const boost shared pointer to a PointCloud message * \param[in] indices the point indices subset that is to be used from \a cloud */ - inline void + inline bool setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr& indices) override { tree_->deleteTree (); @@ -122,6 +122,7 @@ namespace pcl tree_->addPointsFromInputCloud (); input_ = cloud; indices_ = indices; + return true; } /** \brief Search for the k-nearest neighbors for the given query point. diff --git a/search/include/pcl/search/organized.h b/search/include/pcl/search/organized.h index 6d5e6461d82..fe07756ef44 100644 --- a/search/include/pcl/search/organized.h +++ b/search/include/pcl/search/organized.h @@ -125,7 +125,7 @@ namespace pcl * \param[in] cloud the const boost shared pointer to a PointCloud message * \param[in] indices the const boost shared pointer to PointIndices */ - void + bool setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ()) override { input_ = cloud; @@ -143,7 +143,7 @@ namespace pcl else mask_.assign (input_->size (), 1); - estimateProjectionMatrix (); + return estimateProjectionMatrix () && isValid (); } /** \brief Search for all neighbors of query point that are within a given radius. @@ -164,7 +164,7 @@ namespace pcl unsigned int max_nn = 0) const override; /** \brief estimated the projection matrix from the input cloud. */ - void + bool estimateProjectionMatrix (); /** \brief Search for the k-nearest neighbors for a given query point. diff --git a/search/include/pcl/search/search.h b/search/include/pcl/search/search.h index 396e1829d10..0991c98a967 100644 --- a/search/include/pcl/search/search.h +++ b/search/include/pcl/search/search.h @@ -113,8 +113,9 @@ namespace pcl /** \brief Pass the input dataset that the search will be performed on. * \param[in] cloud a const pointer to the PointCloud data * \param[in] indices the point indices subset that is to be used from the cloud + * \return True if successful, false if an error occurred, for example because the point cloud is unsuited for the search method. */ - virtual void + virtual bool setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr &indices = IndicesConstPtr ()); From 1cb996a5a875b76b1ddafa3a5a771d3df39af4b1 Mon Sep 17 00:00:00 2001 From: gscholer <51702175+gscholer@users.noreply.github.com> Date: Wed, 18 Oct 2023 17:39:52 +0800 Subject: [PATCH 139/288] MSAC and RMSAC: fix check array distances empty (#5849) * fix check array distances empty * fix typo --------- Co-authored-by: gyl --- sample_consensus/include/pcl/sample_consensus/impl/msac.hpp | 6 +++++- .../include/pcl/sample_consensus/impl/rmsac.hpp | 5 ++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp index 028fd3f7e18..c1ce5deefb1 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/msac.hpp @@ -90,8 +90,12 @@ pcl::MEstimatorSampleConsensus::computeModel (int debug_verbosity_level) // Iterate through the 3d points and calculate the distances from them to the model sac_model_->getDistancesToModel (model_coefficients, distances); - if (distances.empty () && k > 1.0) + if (distances.empty ()) + { + // skip invalid model suppress infinite loops + ++ skipped_count; continue; + } for (const double &distance : distances) d_cur_penalty += (std::min) (distance, threshold_); diff --git a/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp b/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp index f3879929b36..5f5cab7151c 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/rmsac.hpp @@ -108,8 +108,11 @@ pcl::RandomizedMEstimatorSampleConsensus::computeModel (int debug_verbos // Iterate through the 3d points and calculate the distances from them to the model sac_model_->getDistancesToModel (model_coefficients, distances); - if (distances.empty () && k > 1.0) + if (distances.empty ()) + { + ++ skipped_count; continue; + } for (const double &distance : distances) d_cur_penalty += std::min (distance, threshold_); From 669652b7e2c39a6949d2fdf24e6bd931bf5195ec Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Sat, 21 Oct 2023 12:04:36 -0700 Subject: [PATCH 140/288] Part F of transition to support modernize-use-default-member-init (#5815) * Part F of transition to support modernize-use-default-member-init * Fixed clang-tidy complaint * Made changes per inspection * Fixed CI formatting complaints * Fixed yet more CI formatting complaints * Reverted 3rdparty files per review * Reverted formatting per review * Addressed review comments * Reran clang-tidy after rebase * Addressed further review comments * Addressed latest issues flagged in review * Fixed clang-format complaint * Fixed omitted review item --- .../recognition/cg/geometric_consistency.h | 30 +++++----- .../include/pcl/recognition/cg/hough_3d.h | 28 ++++----- .../pcl/recognition/color_gradient_modality.h | 14 ++--- .../include/pcl/recognition/distance_map.h | 34 +++++------ .../recognition/impl/implicit_shape_model.hpp | 35 +---------- .../impl/ransac_based/simple_octree.hpp | 6 +- .../pcl/recognition/implicit_shape_model.h | 53 +++++++++-------- recognition/include/pcl/recognition/linemod.h | 45 +++++++------- .../pcl/recognition/linemod/line_rgbd.h | 29 +++++----- .../pcl/recognition/ransac_based/hypothesis.h | 12 ++-- .../recognition/ransac_based/model_library.h | 2 +- .../recognition/ransac_based/obj_rec_ransac.h | 18 +++--- .../pcl/recognition/ransac_based/orr_octree.h | 26 ++++----- .../ransac_based/orr_octree_zprojection.h | 10 ++-- .../ransac_based/rigid_transform_space.h | 9 +-- .../recognition/ransac_based/simple_octree.h | 8 +-- .../recognition/ransac_based/trimmed_icp.h | 6 +- .../include/pcl/recognition/region_xy.h | 14 ++--- .../sparse_quantized_multi_mod_template.h | 26 ++++----- .../pcl/recognition/surface_normal_modality.h | 58 ++++++++----------- recognition/src/linemod.cpp | 7 +-- .../src/ransac_based/model_library.cpp | 3 +- .../src/ransac_based/obj_rec_ransac.cpp | 11 +--- recognition/src/ransac_based/orr_octree.cpp | 7 +-- .../registration/correspondence_estimation.h | 12 ++-- ...correspondence_estimation_backprojection.h | 4 +- ...orrespondence_estimation_normal_shooting.h | 4 +- ...pondence_estimation_organized_projection.h | 10 +--- .../registration/correspondence_rejection.h | 8 +-- ...correspondence_rejection_median_distance.h | 6 +- ...respondence_rejection_organized_boundary.h | 10 ++-- .../correspondence_rejection_poly.h | 17 ++---- ...orrespondence_rejection_sample_consensus.h | 17 ++---- .../correspondence_rejection_surface_normal.h | 4 +- .../correspondence_rejection_trimmed.h | 9 +-- .../correspondence_rejection_var_trimmed.h | 11 ++-- .../default_convergence_criteria.h | 33 ++++------- registration/include/pcl/registration/elch.h | 3 +- registration/include/pcl/registration/gicp.h | 21 +++---- .../include/pcl/registration/ia_fpcs.h | 32 +++++----- .../include/pcl/registration/ia_kfpcs.h | 8 +-- .../include/pcl/registration/ia_ransac.h | 13 ++--- registration/include/pcl/registration/icp.h | 19 ++---- .../include/pcl/registration/impl/ia_fpcs.hpp | 42 +++----------- .../pcl/registration/impl/ia_kfpcs.hpp | 6 +- .../include/pcl/registration/impl/ndt.hpp | 8 +-- .../include/pcl/registration/impl/ndt_2d.hpp | 6 +- .../impl/pyramid_feature_matching.hpp | 7 +-- .../impl/transformation_estimation_lm.hpp | 6 +- ...ion_estimation_point_to_plane_weighted.hpp | 4 +- registration/include/pcl/registration/lum.h | 6 +- registration/include/pcl/registration/ndt.h | 10 ++-- .../pcl/registration/ppf_registration.h | 12 ++-- .../registration/pyramid_feature_matching.h | 4 +- .../include/pcl/registration/registration.h | 36 ++++-------- .../sample_consensus_prerejective.h | 9 +-- .../transformation_estimation_lm.h | 8 +-- ...ation_estimation_point_to_plane_weighted.h | 12 ++-- ..._estimation_symmetric_point_to_plane_lls.h | 5 +- .../transformation_validation_euclidean.h | 3 +- search/include/pcl/search/flann_search.h | 14 ++--- .../include/pcl/search/impl/flann_search.hpp | 3 +- .../include/pcl/simulation/range_likelihood.h | 32 +++++----- simulation/src/range_likelihood.cpp | 15 ----- test/common/test_transforms.cpp | 8 +-- test/octree/test_octree_iterator.cpp | 3 +- test/outofcore/test_outofcore.cpp | 4 +- 67 files changed, 373 insertions(+), 622 deletions(-) diff --git a/recognition/include/pcl/recognition/cg/geometric_consistency.h b/recognition/include/pcl/recognition/cg/geometric_consistency.h index 41d3ef5f35f..d1936b1d971 100644 --- a/recognition/include/pcl/recognition/cg/geometric_consistency.h +++ b/recognition/include/pcl/recognition/cg/geometric_consistency.h @@ -3,7 +3,7 @@ * * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2012, Willow Garage, Inc. - * + * * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -44,7 +44,7 @@ namespace pcl { - + /** \brief Class implementing a 3D correspondence grouping enforcing geometric consistency among feature correspondences * * \author Federico Tombari, Tommaso Cavallari, Aitor Aldoma @@ -61,14 +61,10 @@ namespace pcl using SceneCloudConstPtr = typename pcl::CorrespondenceGrouping::SceneCloudConstPtr; /** \brief Constructor */ - GeometricConsistencyGrouping () - : gc_threshold_ (3) - , gc_size_ (1.0) - {} + GeometricConsistencyGrouping () = default; - /** \brief Sets the minimum cluster size - * \param[in] threshold the minimum cluster size + * \param[in] threshold the minimum cluster size */ inline void setGCThreshold (int threshold) @@ -77,7 +73,7 @@ namespace pcl } /** \brief Gets the minimum cluster size. - * + * * \return the minimum cluster size used by GC. */ inline int @@ -87,7 +83,7 @@ namespace pcl } /** \brief Sets the consensus set resolution. This should be in metric units. - * + * * \param[in] gc_size consensus set resolution. */ inline void @@ -97,7 +93,7 @@ namespace pcl } /** \brief Gets the consensus set resolution. - * + * * \return the consensus set resolution. */ inline double @@ -107,7 +103,7 @@ namespace pcl } /** \brief The main function, recognizes instances of the model into the scene set by the user. - * + * * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. * * \return true if the recognition had been successful or false if errors have occurred. @@ -116,7 +112,7 @@ namespace pcl recognize (std::vector > &transformations); /** \brief The main function, recognizes instances of the model into the scene set by the user. - * + * * \param[out] transformations a vector containing one transformation matrix for each instance of the model recognized into the scene. * \param[out] clustered_corrs a vector containing the correspondences for each instance of the model found within the input data (the same output of clusterCorrespondences). * @@ -131,19 +127,19 @@ namespace pcl using CorrespondenceGrouping::model_scene_corrs_; /** \brief Minimum cluster size. It shouldn't be less than 3, since at least 3 correspondences are needed to compute the 6DOF pose */ - int gc_threshold_; + int gc_threshold_{3}; /** \brief Resolution of the consensus set used to cluster correspondences together*/ - double gc_size_; + double gc_size_{1.0}; /** \brief Transformations found by clusterCorrespondences method. */ std::vector > found_transformations_; /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene. - * + * * \param[out] model_instances a vector containing the clustered correspondences for each model found on the scene. * \return true if the clustering had been successful or false if errors have occurred. - */ + */ void clusterCorrespondences (std::vector &model_instances) override; }; diff --git a/recognition/include/pcl/recognition/cg/hough_3d.h b/recognition/include/pcl/recognition/cg/hough_3d.h index cd18a78b267..2a736805e3c 100644 --- a/recognition/include/pcl/recognition/cg/hough_3d.h +++ b/recognition/include/pcl/recognition/cg/hough_3d.h @@ -118,10 +118,10 @@ namespace pcl Eigen::Vector3i bin_count_; /** \brief Used to access hough_space_ as if it was a matrix. */ - int partial_bin_products_[4]; + int partial_bin_products_[4]{}; /** \brief Total number of bins in the Hough Space. */ - int total_bins_count_; + int total_bins_count_{0}; /** \brief The Hough Space. */ std::vector hough_space_; @@ -166,14 +166,6 @@ namespace pcl Hough3DGrouping () : input_rf_ () , scene_rf_ () - , needs_training_ (true) - ,hough_threshold_ (-1) - , hough_bin_size_ (1.0) - , use_interpolation_ (true) - , use_distance_weight_ (false) - , local_rf_normals_search_radius_ (0.0f) - , local_rf_search_radius_ (0.0f) - , hough_space_initialized_ (false) {} /** \brief Provide a pointer to the input dataset. @@ -445,28 +437,28 @@ namespace pcl SceneRfCloudConstPtr scene_rf_; /** \brief If the training of the Hough space is needed; set on change of either the input cloud or the input_rf. */ - bool needs_training_; + bool needs_training_{true}; /** \brief The result of the training. The vector between each model point and the centroid of the model adjusted by its local reference frame.*/ std::vector > model_votes_; /** \brief The minimum number of votes in the Hough space needed to infer the presence of a model instance into the scene cloud. */ - double hough_threshold_; + double hough_threshold_{-1.0}; /** \brief The size of each bin of the hough space. */ - double hough_bin_size_; + double hough_bin_size_{1.0}; /** \brief Use the interpolation between neighboring Hough bins when casting votes. */ - bool use_interpolation_; + bool use_interpolation_{true}; /** \brief Use the weighted correspondence distance when casting votes. */ - bool use_distance_weight_; + bool use_distance_weight_{false}; /** \brief Normals search radius for the potential Rf calculation. */ - float local_rf_normals_search_radius_; + float local_rf_normals_search_radius_{0.0f}; /** \brief Search radius for the potential Rf calculation. */ - float local_rf_search_radius_; + float local_rf_search_radius_{0.0f}; /** \brief The Hough space. */ pcl::recognition::HoughSpace3D::Ptr hough_space_; @@ -477,7 +469,7 @@ namespace pcl /** \brief Whether the Hough space already contains the correct votes for the current input parameters and so the cluster and recognize calls don't need to recompute each value. * Reset on the change of any parameter except the hough_threshold. */ - bool hough_space_initialized_; + bool hough_space_initialized_{false}; /** \brief Cluster the input correspondences in order to distinguish between different instances of the model into the scene. * diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 7e5bae23a7d..89ca02cb49c 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -240,7 +240,7 @@ namespace pcl private: /** \brief Determines whether variable numbers of features are extracted or not. */ - bool variable_feature_nr_; + bool variable_feature_nr_{false}; /** \brief Stores a smoothed version of the input cloud. */ pcl::PointCloud::Ptr smoothed_input_; @@ -249,15 +249,15 @@ namespace pcl FeatureSelectionMethod feature_selection_method_; /** \brief The threshold applied on the gradient magnitudes (for quantization). */ - float gradient_magnitude_threshold_; + float gradient_magnitude_threshold_{10.0f}; /** \brief The threshold applied on the gradient magnitudes for feature extraction. */ - float gradient_magnitude_threshold_feature_extraction_; + float gradient_magnitude_threshold_feature_extraction_{55.0f}; /** \brief The point cloud which holds the max-RGB gradients. */ pcl::PointCloud color_gradients_; /** \brief The spreading size. */ - std::size_t spreading_size_; + std::size_t spreading_size_{8}; /** \brief The map which holds the quantized max-RGB gradients. */ pcl::QuantizedMap quantized_color_gradients_; @@ -274,12 +274,8 @@ namespace pcl template pcl::ColorGradientModality:: ColorGradientModality () - : variable_feature_nr_ (false) - , smoothed_input_ (new pcl::PointCloud ()) + : smoothed_input_ (new pcl::PointCloud ()) , feature_selection_method_ (DISTANCE_MAGNITUDE_SCORE) - , gradient_magnitude_threshold_ (10.0f) - , gradient_magnitude_threshold_feature_extraction_ (55.0f) - , spreading_size_ (8) { } diff --git a/recognition/include/pcl/recognition/distance_map.h b/recognition/include/pcl/recognition/distance_map.h index d641265125d..1eb6fc29d61 100644 --- a/recognition/include/pcl/recognition/distance_map.h +++ b/recognition/include/pcl/recognition/distance_map.h @@ -4,7 +4,7 @@ * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2011, Willow Garage, Inc. * - * All rights reserved. + * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -40,35 +40,35 @@ namespace pcl { - /** \brief Represents a distance map obtained from a distance transformation. + /** \brief Represents a distance map obtained from a distance transformation. * \author Stefan Holzer */ class DistanceMap { public: /** \brief Constructor. */ - DistanceMap () : data_ (0), width_ (0), height_ (0) {} + DistanceMap () : data_ (0) {} /** \brief Destructor. */ virtual ~DistanceMap () = default; /** \brief Returns the width of the map. */ - inline std::size_t + inline std::size_t getWidth () const { - return (width_); + return (width_); } /** \brief Returns the height of the map. */ - inline std::size_t + inline std::size_t getHeight () const - { - return (height_); + { + return (height_); } - + /** \brief Returns a pointer to the beginning of map. */ - inline float * - getData () - { + inline float * + getData () + { return (data_.data()); } @@ -76,7 +76,7 @@ namespace pcl * \param[in] width the new width of the map. * \param[in] height the new height of the map. */ - void + void resize (const std::size_t width, const std::size_t height) { data_.resize (width*height); @@ -88,7 +88,7 @@ namespace pcl * \param[in] col_index the column index of the element to access. * \param[in] row_index the row index of the element to access. */ - inline float & + inline float & operator() (const std::size_t col_index, const std::size_t row_index) { return (data_[row_index*width_ + col_index]); @@ -98,7 +98,7 @@ namespace pcl * \param[in] col_index the column index of the element to access. * \param[in] row_index the row index of the element to access. */ - inline const float & + inline const float & operator() (const std::size_t col_index, const std::size_t row_index) const { return (data_[row_index*width_ + col_index]); @@ -108,9 +108,9 @@ namespace pcl /** \brief The storage for the distance map data. */ std::vector data_; /** \brief The width of the map. */ - std::size_t width_; + std::size_t width_{0}; /** \brief The height of the map. */ - std::size_t height_; + std::size_t height_{0}; }; } diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index 94afed0d52b..3830bdbe9b1 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -49,15 +49,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::features::ISMVoteList::ISMVoteList () : - votes_ (new pcl::PointCloud ()), - tree_is_valid_ (false), - votes_origins_ (new pcl::PointCloud ()), - votes_class_ (0), - k_ind_ (0), - k_sqr_dist_ (0) -{ -} +pcl::features::ISMVoteList::ISMVoteList() = default; ////////////////////////////////////////////////////////////////////////////////////////////// template @@ -297,18 +289,7 @@ pcl::features::ISMVoteList::getNumberOfVotes () } ////////////////////////////////////////////////////////////////////////////////////////////// -pcl::features::ISMModel::ISMModel () : - statistical_weights_ (0), - learned_weights_ (0), - classes_ (0), - sigmas_ (0), - clusters_ (0), - number_of_classes_ (0), - number_of_visual_words_ (0), - number_of_clusters_ (0), - descriptors_dimension_ (0) -{ -} +pcl::features::ISMModel::ISMModel () = default; ////////////////////////////////////////////////////////////////////////////////////////////// pcl::features::ISMModel::ISMModel (ISMModel const & copy) @@ -546,17 +527,7 @@ pcl::features::ISMModel::operator = (const pcl::features::ISMModel& other) ////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::ism::ImplicitShapeModelEstimation::ImplicitShapeModelEstimation () : - training_clouds_ (0), - training_classes_ (0), - training_normals_ (0), - training_sigmas_ (0), - sampling_size_ (0.1f), - feature_estimator_ (), - number_of_clusters_ (184), - n_vot_ON_ (true) -{ -} +pcl::ism::ImplicitShapeModelEstimation::ImplicitShapeModelEstimation () = default; ////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/recognition/include/pcl/recognition/impl/ransac_based/simple_octree.hpp b/recognition/include/pcl/recognition/impl/ransac_based/simple_octree.hpp index bd2e6436010..9e7f2103e0f 100644 --- a/recognition/include/pcl/recognition/impl/ransac_based/simple_octree.hpp +++ b/recognition/include/pcl/recognition/impl/ransac_based/simple_octree.hpp @@ -180,11 +180,7 @@ SimpleOctree::Node::makeNeighbors (Node* node template inline -SimpleOctree::SimpleOctree () -: tree_levels_ (0), - root_ (nullptr) -{ -} +SimpleOctree::SimpleOctree () = default; template inline diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index c32f55150f4..0347eff922a 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -128,25 +128,25 @@ namespace pcl protected: /** \brief Stores all votes. */ - pcl::PointCloud::Ptr votes_; + pcl::PointCloud::Ptr votes_{new pcl::PointCloud}; /** \brief Signalizes if the tree is valid. */ - bool tree_is_valid_; + bool tree_is_valid_{false}; /** \brief Stores the origins of the votes. */ - typename pcl::PointCloud::Ptr votes_origins_; + typename pcl::PointCloud::Ptr votes_origins_{new pcl::PointCloud}; /** \brief Stores classes for which every single vote was cast. */ - std::vector votes_class_; + std::vector votes_class_{}; /** \brief Stores the search tree. */ - pcl::KdTreeFLANN::Ptr tree_; + pcl::KdTreeFLANN::Ptr tree_{nullptr}; /** \brief Stores neighbours indices. */ - pcl::Indices k_ind_; + pcl::Indices k_ind_{}; /** \brief Stores square distances to the corresponding neighbours. */ - std::vector k_sqr_dist_; + std::vector k_sqr_dist_{}; }; /** \brief The assignment of this structure is to store the statistical/learned weights and other information @@ -187,16 +187,16 @@ namespace pcl ISMModel & operator = (const ISMModel& other); /** \brief Stores statistical weights. */ - std::vector > statistical_weights_; + std::vector > statistical_weights_{}; /** \brief Stores learned weights. */ - std::vector learned_weights_; + std::vector learned_weights_{}; /** \brief Stores the class label for every direction. */ - std::vector classes_; + std::vector classes_{}; /** \brief Stores the sigma value for each class. This values were used to compute the learned weights. */ - std::vector sigmas_; + std::vector sigmas_{}; /** \brief Stores the directions to objects center for each visual word. */ Eigen::MatrixXf directions_to_center_; @@ -205,19 +205,19 @@ namespace pcl Eigen::MatrixXf clusters_centers_; /** \brief This is an array of clusters. Each cluster stores the indices of the visual words that it contains. */ - std::vector > clusters_; + std::vector > clusters_{}; /** \brief Stores the number of classes. */ - unsigned int number_of_classes_; + unsigned int number_of_classes_{0}; /** \brief Stores the number of visual words. */ - unsigned int number_of_visual_words_; + unsigned int number_of_visual_words_{0}; /** \brief Stores the number of clusters. */ - unsigned int number_of_clusters_; + unsigned int number_of_clusters_{0}; /** \brief Stores descriptors dimension. */ - unsigned int descriptors_dimension_; + unsigned int descriptors_dimension_{0}; PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -316,15 +316,14 @@ namespace pcl { /** \brief Empty constructor with member variables initialization. */ VisualWordStat () : - class_ (-1), - learned_weight_ (0.0f), + dir_to_center_ (0.0f, 0.0f, 0.0f) {}; /** \brief Which class this vote belongs. */ - int class_; + int class_{-1}; /** \brief Weight of the vote. */ - float learned_weight_; + float learned_weight_{0.0f}; /** \brief Expected direction to center. */ pcl::PointXYZ dir_to_center_; @@ -583,30 +582,30 @@ namespace pcl protected: /** \brief Stores the clouds used for training. */ - std::vector::Ptr> training_clouds_; + std::vector::Ptr> training_clouds_{}; /** \brief Stores the class number for each cloud from training_clouds_. */ - std::vector training_classes_; + std::vector training_classes_{}; /** \brief Stores the normals for each training cloud. */ - std::vector::Ptr> training_normals_; + std::vector::Ptr> training_normals_{}; /** \brief This array stores the sigma values for each training class. If this array has a size equals 0, then * sigma values will be calculated automatically. */ - std::vector training_sigmas_; + std::vector training_sigmas_{}; /** \brief This value is used for the simplification. It sets the size of grid bin. */ - float sampling_size_; + float sampling_size_{0.1f}; /** \brief Stores the feature estimator. */ typename Feature::Ptr feature_estimator_; /** \brief Number of clusters, is used for clustering descriptors during the training. */ - unsigned int number_of_clusters_; + unsigned int number_of_clusters_{184}; /** \brief If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. */ - bool n_vot_ON_; + bool n_vot_ON_{true}; /** \brief This const value is used for indicating that for k-means clustering centers must * be generated as described in diff --git a/recognition/include/pcl/recognition/linemod.h b/recognition/include/pcl/recognition/linemod.h index fb771d75bb4..aac1e517b3f 100644 --- a/recognition/include/pcl/recognition/linemod.h +++ b/recognition/include/pcl/recognition/linemod.h @@ -55,10 +55,7 @@ namespace pcl { public: /** \brief Constructor. */ - EnergyMaps () : width_ (0), height_ (0), nr_bins_ (0) - { - } - + EnergyMaps () = default; /** \brief Destructor. */ virtual ~EnergyMaps () = default; @@ -182,11 +179,11 @@ namespace pcl private: /** \brief The width of the energy maps. */ - std::size_t width_; + std::size_t width_{0}; /** \brief The height of the energy maps. */ - std::size_t height_; + std::size_t height_{0}; /** \brief The number of quantization bins (== the number of internally stored energy maps). */ - std::size_t nr_bins_; + std::size_t nr_bins_{0}; /** \brief Storage for the energy maps. */ std::vector maps_; }; @@ -198,9 +195,7 @@ namespace pcl { public: /** \brief Constructor. */ - LinearizedMaps () : width_ (0), height_ (0), mem_width_ (0), mem_height_ (0), step_size_ (0) - { - } + LinearizedMaps () = default; /** \brief Destructor. */ virtual ~LinearizedMaps () = default; @@ -290,15 +285,15 @@ namespace pcl private: /** \brief the original width of the data represented by the map. */ - std::size_t width_; + std::size_t width_{0}; /** \brief the original height of the data represented by the map. */ - std::size_t height_; + std::size_t height_{0}; /** \brief the actual width of the linearized map. */ - std::size_t mem_width_; + std::size_t mem_width_{0}; /** \brief the actual height of the linearized map. */ - std::size_t mem_height_; + std::size_t mem_height_{0}; /** \brief the step-size used for sampling the original data. */ - std::size_t step_size_; + std::size_t step_size_{0}; /** \brief a vector containing all the linearized maps. */ std::vector maps_; }; @@ -309,18 +304,18 @@ namespace pcl struct PCL_EXPORTS LINEMODDetection { /** \brief Constructor. */ - LINEMODDetection () : x (0), y (0), template_id (0), score (0.0f), scale (1.0f) {} + LINEMODDetection () = default; /** \brief x-position of the detection. */ - int x; + int x{0}; /** \brief y-position of the detection. */ - int y; + int y{0}; /** \brief ID of the detected template. */ - int template_id; + int template_id{0}; /** \brief score of the detection. */ - float score; + float score{0.0f}; /** \brief scale at which the template was detected. */ - float scale; + float scale{1.0f}; }; /** @@ -461,13 +456,13 @@ namespace pcl private: /** template response threshold */ - float template_threshold_; + float template_threshold_{0.75f}; /** states whether non-max-suppression on detections is enabled or not */ - bool use_non_max_suppression_; + bool use_non_max_suppression_{false}; /** states whether to return an averaged detection */ - bool average_detections_; + bool average_detections_{false}; /** template storage */ - std::vector templates_; + std::vector templates_{}; }; } diff --git a/recognition/include/pcl/recognition/linemod/line_rgbd.h b/recognition/include/pcl/recognition/linemod/line_rgbd.h index 08f7292f3e9..d9f9cd5dec8 100644 --- a/recognition/include/pcl/recognition/linemod/line_rgbd.h +++ b/recognition/include/pcl/recognition/linemod/line_rgbd.h @@ -48,21 +48,21 @@ namespace pcl struct BoundingBoxXYZ { /** \brief Constructor. */ - BoundingBoxXYZ () : x (0.0f), y (0.0f), z (0.0f), width (0.0f), height (0.0f), depth (0.0f) {} + BoundingBoxXYZ () = default; /** \brief X-coordinate of the upper left front point */ - float x; + float x{0.0f}; /** \brief Y-coordinate of the upper left front point */ - float y; + float y{0.0f}; /** \brief Z-coordinate of the upper left front point */ - float z; + float z{0.0f}; /** \brief Width of the bounding box */ - float width; + float width{0.0f}; /** \brief Height of the bounding box */ - float height; + float height{0.0f}; /** \brief Depth of the bounding box */ - float depth; + float depth{0.0f}; }; /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data. @@ -77,16 +77,16 @@ namespace pcl struct Detection { /** \brief Constructor. */ - Detection () : template_id (0), object_id (0), detection_id (0), response (0.0f) {} + Detection () = default; /** \brief The ID of the template. */ - std::size_t template_id; + std::size_t template_id{0}; /** \brief The ID of the object corresponding to the template. */ - std::size_t object_id; + std::size_t object_id{0}; /** \brief The ID of this detection. This is only valid for the last call of the method detect (...). */ - std::size_t detection_id; + std::size_t detection_id{0}; /** \brief The response of this detection. Responses are between 0 and 1, where 1 is best. */ - float response; + float response{0.0f}; /** \brief The 3D bounding box of the detection. */ BoundingBoxXYZ bounding_box; /** \brief The 2D template region of the detection. */ @@ -95,8 +95,7 @@ namespace pcl /** \brief Constructor */ LineRGBD () - : intersection_volume_threshold_ (1.0f) - , color_gradient_mod_ () + : color_gradient_mod_ () , surface_normal_mod_ () , cloud_xyz_ () , cloud_rgb_ () @@ -281,7 +280,7 @@ namespace pcl readLTMHeader (int fd, pcl::io::TARHeader &header); /** \brief Intersection volume threshold. */ - float intersection_volume_threshold_; + float intersection_volume_threshold_{1.0f}; /** \brief LINEMOD instance. */ public: pcl::LINEMOD linemod_; diff --git a/recognition/include/pcl/recognition/ransac_based/hypothesis.h b/recognition/include/pcl/recognition/ransac_based/hypothesis.h index dafdef9e6d2..a8a2a681415 100644 --- a/recognition/include/pcl/recognition/ransac_based/hypothesis.h +++ b/recognition/include/pcl/recognition/ransac_based/hypothesis.h @@ -74,17 +74,15 @@ namespace pcl } public: - float rigid_transform_[12]; - const ModelLibrary::Model* obj_model_; + float rigid_transform_[12]{}; + const ModelLibrary::Model* obj_model_{nullptr}; }; class Hypothesis: public HypothesisBase { public: Hypothesis (const ModelLibrary::Model* obj_model = nullptr) - : HypothesisBase (obj_model), - match_confidence_ (-1.0f), - linear_id_ (-1) + : HypothesisBase (obj_model) { } @@ -149,9 +147,9 @@ namespace pcl } public: - float match_confidence_; + float match_confidence_{-1.0f}; std::set explained_pixels_; - int linear_id_; + int linear_id_{-1}; }; } // namespace recognition } // namespace pcl diff --git a/recognition/include/pcl/recognition/ransac_based/model_library.h b/recognition/include/pcl/recognition/ransac_based/model_library.h index 71b083fffba..a1c8ac673e5 100644 --- a/recognition/include/pcl/recognition/ransac_based/model_library.h +++ b/recognition/include/pcl/recognition/ransac_based/model_library.h @@ -258,7 +258,7 @@ namespace pcl float pair_width_; float voxel_size_; float max_coplanarity_angle_; - bool ignore_coplanar_opps_; + bool ignore_coplanar_opps_{true}; std::map models_; HashTable hash_table_; diff --git a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h index c2aa6173262..c4d3723e0bf 100644 --- a/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h +++ b/recognition/include/pcl/recognition/ransac_based/obj_rec_ransac.h @@ -454,15 +454,15 @@ namespace pcl float position_discretization_; float rotation_discretization_; float abs_zdist_thresh_; - float relative_obj_size_; - float visibility_; - float relative_num_of_illegal_pts_; - float intersection_fraction_; + float relative_obj_size_{0.05f}; + float visibility_{0.2f}; + float relative_num_of_illegal_pts_{0.02f}; + float intersection_fraction_{0.03f}; float max_coplanarity_angle_; - float scene_bounds_enlargement_factor_; - bool ignore_coplanar_opps_; - float frac_of_points_for_icp_refinement_; - bool do_icp_hypotheses_refinement_; + float scene_bounds_enlargement_factor_{0.25f}; + bool ignore_coplanar_opps_{true}; + float frac_of_points_for_icp_refinement_{0.3f}; + bool do_icp_hypotheses_refinement_{true}; ModelLibrary model_library_; ORROctree scene_octree_; @@ -473,7 +473,7 @@ namespace pcl std::list sampled_oriented_point_pairs_; std::vector accepted_hypotheses_; - Recognition_Mode rec_mode_; + Recognition_Mode rec_mode_{ObjRecRANSAC::FULL_RECOGNITION}; }; } // namespace recognition } // namespace pcl diff --git a/recognition/include/pcl/recognition/ransac_based/orr_octree.h b/recognition/include/pcl/recognition/ransac_based/orr_octree.h index 8c8fd7e354a..870624a228f 100644 --- a/recognition/include/pcl/recognition/ransac_based/orr_octree.h +++ b/recognition/include/pcl/recognition/ransac_based/orr_octree.h @@ -83,7 +83,7 @@ namespace pcl id_y_ (id_y), id_z_ (id_z), lin_id_ (lin_id), - num_points_ (0), + user_data_ (user_data) { n_[0] = n_[1] = n_[2] = p_[0] = p_[1] = p_[2] = 0.0f; @@ -156,17 +156,13 @@ namespace pcl getNeighbors () const { return (neighbors_);} protected: - float n_[3], p_[3]; - int id_x_, id_y_, id_z_, lin_id_, num_points_; + float n_[3]{}, p_[3]{}; + int id_x_{0}, id_y_{0}, id_z_{0}, lin_id_{0}, num_points_{0}; std::set neighbors_; - void *user_data_; + void *user_data_{nullptr}; }; - Node () - : data_ (nullptr), - parent_ (nullptr), - children_(nullptr) - {} + Node () = default; virtual~ Node () { @@ -264,9 +260,9 @@ namespace pcl } protected: - Node::Data *data_; - float center_[3], bounds_[6], radius_; - Node *parent_, *children_; + Node::Data *data_{nullptr}; + float center_[3]{}, bounds_[6]{}, radius_{0.0f}; + Node *parent_{nullptr}, *children_{nullptr}; }; ORROctree (); @@ -472,9 +468,9 @@ namespace pcl } protected: - float voxel_size_, bounds_[6]; - int tree_levels_; - Node* root_; + float voxel_size_{-1.0}, bounds_[6]; + int tree_levels_{-1}; + Node* root_{nullptr}; std::vector full_leaves_; }; } // namespace recognition diff --git a/recognition/include/pcl/recognition/ransac_based/orr_octree_zprojection.h b/recognition/include/pcl/recognition/ransac_based/orr_octree_zprojection.h index d485fc65cea..e05addd73fe 100644 --- a/recognition/include/pcl/recognition/ransac_based/orr_octree_zprojection.h +++ b/recognition/include/pcl/recognition/ransac_based/orr_octree_zprojection.h @@ -113,10 +113,8 @@ namespace pcl }; public: - ORROctreeZProjection () - : pixels_(nullptr), - sets_(nullptr) - {} + ORROctreeZProjection () = default; + virtual ~ORROctreeZProjection (){ this->clear();} void @@ -200,8 +198,8 @@ namespace pcl protected: float pixel_size_, inv_pixel_size_, bounds_[4], extent_x_, extent_y_; int num_pixels_x_, num_pixels_y_, num_pixels_; - Pixel ***pixels_; - Set ***sets_; + Pixel ***pixels_{nullptr}; + Set ***sets_{nullptr}; std::list full_sets_; std::list full_pixels_; }; diff --git a/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h b/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h index 3e92dd984f8..a47a30748a5 100644 --- a/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h +++ b/recognition/include/pcl/recognition/ransac_based/rigid_transform_space.h @@ -62,7 +62,6 @@ namespace pcl { public: Entry () - : num_transforms_ (0) { aux::set3 (axis_angle_, 0.0f); aux::set3 (translation_, 0.0f); @@ -134,7 +133,7 @@ namespace pcl protected: float axis_angle_[3], translation_[3]; - int num_transforms_; + int num_transforms_{0}; };// class Entry public: @@ -293,9 +292,7 @@ namespace pcl class RotationSpaceCreator { public: - RotationSpaceCreator() - : counter_ (0) - {} + RotationSpaceCreator() = default; virtual ~RotationSpaceCreator() = default; @@ -331,7 +328,7 @@ namespace pcl protected: float discretization_; - int counter_; + int counter_{0}; std::list rotation_spaces_; }; diff --git a/recognition/include/pcl/recognition/ransac_based/simple_octree.h b/recognition/include/pcl/recognition/ransac_based/simple_octree.h index 5084c7dbc51..fde0ff0e76e 100644 --- a/recognition/include/pcl/recognition/ransac_based/simple_octree.h +++ b/recognition/include/pcl/recognition/ransac_based/simple_octree.h @@ -198,11 +198,11 @@ namespace pcl insertNeighbors (Node* node); protected: - Scalar voxel_size_, bounds_[6]; - int tree_levels_; - Node* root_; + Scalar voxel_size_{0.0f}, bounds_[6]{}; + int tree_levels_{0}; + Node* root_{nullptr}; std::vector full_leaves_; - NodeDataCreator* node_data_creator_; + NodeDataCreator* node_data_creator_{nullptr}; }; } // namespace recognition } // namespace pcl diff --git a/recognition/include/pcl/recognition/ransac_based/trimmed_icp.h b/recognition/include/pcl/recognition/ransac_based/trimmed_icp.h index a26bca5b5db..ee731eba107 100644 --- a/recognition/include/pcl/recognition/ransac_based/trimmed_icp.h +++ b/recognition/include/pcl/recognition/ransac_based/trimmed_icp.h @@ -68,9 +68,7 @@ namespace pcl using Matrix4 = typename Eigen::Matrix; public: - TrimmedICP () - : new_to_old_energy_ratio_ (0.99f) - {} + TrimmedICP () = default; ~TrimmedICP () override = default; @@ -177,7 +175,7 @@ namespace pcl protected: PointCloudConstPtr target_points_; pcl::KdTreeFLANN kdtree_; - float new_to_old_energy_ratio_; + float new_to_old_energy_ratio_{0.99f}; }; } // namespace recognition } // namespace pcl diff --git a/recognition/include/pcl/recognition/region_xy.h b/recognition/include/pcl/recognition/region_xy.h index 78d413cdeb0..38260f1dd5c 100644 --- a/recognition/include/pcl/recognition/region_xy.h +++ b/recognition/include/pcl/recognition/region_xy.h @@ -4,7 +4,7 @@ * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2011, Willow Garage, Inc. * - * All rights reserved. + * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -81,16 +81,16 @@ namespace pcl struct PCL_EXPORTS RegionXY { /** \brief Constructor. */ - RegionXY () : x (0), y (0), width (0), height (0) {} + RegionXY () = default; /** \brief x-position of the region. */ - int x; + int x{0}; /** \brief y-position of the region. */ - int y; + int y{0}; /** \brief width of the region. */ - int width; + int width{0}; /** \brief height of the region. */ - int height; + int height{0}; /** \brief Serializes the object to the specified stream. * \param[out] stream the stream the object will be serialized to. */ @@ -105,7 +105,7 @@ namespace pcl /** \brief Deserializes the object from the specified stream. * \param[in] stream the stream the object will be deserialized from. */ - void + void deserialize (::std::istream & stream) { read (stream, x); diff --git a/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h b/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h index a626933ce63..70364c3a521 100644 --- a/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h +++ b/recognition/include/pcl/recognition/sparse_quantized_multi_mod_template.h @@ -4,7 +4,7 @@ * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2010-2011, Willow Garage, Inc. * - * All rights reserved. + * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -44,24 +44,24 @@ namespace pcl { - /** \brief Feature that defines a position and quantized value in a specific modality. + /** \brief Feature that defines a position and quantized value in a specific modality. * \author Stefan Holzer */ struct QuantizedMultiModFeature { /** \brief Constructor. */ - QuantizedMultiModFeature () : x (0), y (0), modality_index (0), quantized_value (0) {} + QuantizedMultiModFeature () = default; /** \brief x-position. */ - int x; + int x{0}; /** \brief y-position. */ - int y; + int y{0}; /** \brief the index of the corresponding modality. */ - std::size_t modality_index; + std::size_t modality_index{0u}; /** \brief the quantized value attached to the feature. */ - unsigned char quantized_value; + unsigned char quantized_value{0u}; - /** \brief Compares whether two features are the same. + /** \brief Compares whether two features are the same. * \param[in] base the feature to compare to. */ bool @@ -81,7 +81,7 @@ namespace pcl /** \brief Serializes the object to the specified stream. * \param[out] stream the stream the object will be serialized to. */ - void + void serialize (std::ostream & stream) const { write (stream, x); @@ -92,7 +92,7 @@ namespace pcl /** \brief Deserializes the object from the specified stream. * \param[in] stream the stream the object will be deserialized from. */ - void + void deserialize (std::istream & stream) { read (stream, x); @@ -103,7 +103,7 @@ namespace pcl }; /** \brief A multi-modality template constructed from a set of quantized multi-modality features. - * \author Stefan Holzer + * \author Stefan Holzer */ struct SparseQuantizedMultiModTemplate { @@ -118,7 +118,7 @@ namespace pcl /** \brief Serializes the object to the specified stream. * \param[out] stream the stream the object will be serialized to. */ - void + void serialize (std::ostream & stream) const { const int num_of_features = static_cast (features.size ()); @@ -133,7 +133,7 @@ namespace pcl /** \brief Deserializes the object from the specified stream. * \param[in] stream the stream the object will be deserialized from. */ - void + void deserialize (std::istream & stream) { features.clear (); diff --git a/recognition/include/pcl/recognition/surface_normal_modality.h b/recognition/include/pcl/recognition/surface_normal_modality.h index 3e0c7866b77..538e88c598d 100644 --- a/recognition/include/pcl/recognition/surface_normal_modality.h +++ b/recognition/include/pcl/recognition/surface_normal_modality.h @@ -63,7 +63,7 @@ namespace pcl { public: /** \brief Constructor. */ - inline LINEMOD_OrientationMap () : width_ (0), height_ (0) {} + inline LINEMOD_OrientationMap () = default; /** \brief Destructor. */ inline ~LINEMOD_OrientationMap () = default; @@ -118,9 +118,9 @@ namespace pcl private: /** \brief The width of the map. */ - std::size_t width_; + std::size_t width_{0}; /** \brief The height of the map. */ - std::size_t height_; + std::size_t height_{0}; /** \brief Storage for the data of the map. */ std::vector map_; @@ -132,35 +132,31 @@ namespace pcl struct QuantizedNormalLookUpTable { /** \brief The range of the LUT in x-direction. */ - int range_x; + int range_x{-1}; /** \brief The range of the LUT in y-direction. */ - int range_y; + int range_y{-1}; /** \brief The range of the LUT in z-direction. */ - int range_z; + int range_z{-1}; /** \brief The offset in x-direction. */ - int offset_x; + int offset_x{-1}; /** \brief The offset in y-direction. */ - int offset_y; + int offset_y{-1}; /** \brief The offset in z-direction. */ - int offset_z; + int offset_z{-1}; /** \brief The size of the LUT in x-direction. */ - int size_x; + int size_x{-1}; /** \brief The size of the LUT in y-direction. */ - int size_y; + int size_y{-1}; /** \brief The size of the LUT in z-direction. */ - int size_z; + int size_z{-1}; /** \brief The LUT data. */ - unsigned char * lut; + unsigned char * lut{nullptr}; /** \brief Constructor. */ - QuantizedNormalLookUpTable () : - range_x (-1), range_y (-1), range_z (-1), - offset_x (-1), offset_y (-1), offset_z (-1), - size_x (-1), size_y (-1), size_z (-1), lut (nullptr) - {} + QuantizedNormalLookUpTable () = default; /** \brief Destructor. */ ~QuantizedNormalLookUpTable () @@ -306,20 +302,20 @@ namespace pcl struct Candidate { /** \brief Constructor. */ - Candidate () : distance (0.0f), bin_index (0), x (0), y (0) {} + Candidate () = default; /** \brief Normal. */ Normal normal; /** \brief Distance to the next different quantized value. */ - float distance; + float distance{0.0f}; /** \brief Quantized value. */ - unsigned char bin_index; + unsigned char bin_index{0}; /** \brief x-position of the feature. */ - std::size_t x; + std::size_t x{0}; /** \brief y-position of the feature. */ - std::size_t y; + std::size_t y{0}; /** \brief Compares two candidates based on their distance to the next different quantized value. * \param[in] rhs the candidate to compare with. @@ -463,18 +459,18 @@ namespace pcl private: /** \brief Determines whether variable numbers of features are extracted or not. */ - bool variable_feature_nr_; + bool variable_feature_nr_{false}; /** \brief The feature distance threshold. */ - float feature_distance_threshold_; + float feature_distance_threshold_{2.0f}; /** \brief Minimum distance of a feature to a border. */ - float min_distance_to_border_; + float min_distance_to_border_{2.0f}; /** \brief Look-up-table for quantizing surface normals. */ QuantizedNormalLookUpTable normal_lookup_; /** \brief The spreading size. */ - std::size_t spreading_size_; + std::size_t spreading_size_{8}; /** \brief Point cloud holding the computed surface normals. */ pcl::PointCloud surface_normals_; @@ -495,13 +491,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////// template pcl::SurfaceNormalModality:: -SurfaceNormalModality () - : variable_feature_nr_ (false) - , feature_distance_threshold_ (2.0f) - , min_distance_to_border_ (2.0f) - , spreading_size_ (8) -{ -} +SurfaceNormalModality () = default; ////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/recognition/src/linemod.cpp b/recognition/src/linemod.cpp index bbdf6be2122..8b47552e2b3 100644 --- a/recognition/src/linemod.cpp +++ b/recognition/src/linemod.cpp @@ -48,12 +48,7 @@ //#define LINEMOD_USE_SEPARATE_ENERGY_MAPS ////////////////////////////////////////////////////////////////////////////////////////////// -pcl::LINEMOD::LINEMOD () - : template_threshold_ (0.75f) - , use_non_max_suppression_ (false) - , average_detections_ (false) -{ -} +pcl::LINEMOD::LINEMOD () = default; ////////////////////////////////////////////////////////////////////////////////////////////// pcl::LINEMOD::~LINEMOD() = default; diff --git a/recognition/src/ransac_based/model_library.cpp b/recognition/src/ransac_based/model_library.cpp index 2f7bad0d9dd..dd3d3efdabc 100644 --- a/recognition/src/ransac_based/model_library.cpp +++ b/recognition/src/ransac_based/model_library.cpp @@ -51,8 +51,7 @@ using namespace pcl::recognition; ModelLibrary::ModelLibrary (float pair_width, float voxel_size, float max_coplanarity_angle) : pair_width_ (pair_width), voxel_size_ (voxel_size), - max_coplanarity_angle_ (max_coplanarity_angle), - ignore_coplanar_opps_ (true) + max_coplanarity_angle_ (max_coplanarity_angle) { num_of_cells_[0] = 60; num_of_cells_[1] = 60; diff --git a/recognition/src/ransac_based/obj_rec_ransac.cpp b/recognition/src/ransac_based/obj_rec_ransac.cpp index 7ba4c5137e8..a57b2d4bc6f 100644 --- a/recognition/src/ransac_based/obj_rec_ransac.cpp +++ b/recognition/src/ransac_based/obj_rec_ransac.cpp @@ -48,17 +48,8 @@ pcl::recognition::ObjRecRANSAC::ObjRecRANSAC (float pair_width, float voxel_size position_discretization_ (5.0f*voxel_size_), rotation_discretization_ (5.0f*AUX_DEG_TO_RADIANS), abs_zdist_thresh_ (1.5f*voxel_size_), - relative_obj_size_ (0.05f), - visibility_ (0.2f), - relative_num_of_illegal_pts_ (0.02f), - intersection_fraction_ (0.03f), max_coplanarity_angle_ (3.0f*AUX_DEG_TO_RADIANS), - scene_bounds_enlargement_factor_ (0.25f), // 25% enlargement - ignore_coplanar_opps_ (true), - frac_of_points_for_icp_refinement_ (0.3f), - do_icp_hypotheses_refinement_ (true), - model_library_ (pair_width, voxel_size, max_coplanarity_angle_), - rec_mode_ (ObjRecRANSAC::FULL_RECOGNITION) + model_library_ (pair_width, voxel_size, max_coplanarity_angle_) { } diff --git a/recognition/src/ransac_based/orr_octree.cpp b/recognition/src/ransac_based/orr_octree.cpp index e1b2fd48657..07e2ea88191 100644 --- a/recognition/src/ransac_based/orr_octree.cpp +++ b/recognition/src/ransac_based/orr_octree.cpp @@ -47,12 +47,7 @@ using namespace pcl::recognition; -pcl::recognition::ORROctree::ORROctree () -: voxel_size_ (-1.0), - tree_levels_ (-1), - root_ (nullptr) -{ -} +pcl::recognition::ORROctree::ORROctree () = default; //================================================================================================================================================================ diff --git a/registration/include/pcl/registration/correspondence_estimation.h b/registration/include/pcl/registration/correspondence_estimation.h index 3837e3ba5ea..bb1db6aab3a 100644 --- a/registration/include/pcl/registration/correspondence_estimation.h +++ b/registration/include/pcl/registration/correspondence_estimation.h @@ -98,10 +98,6 @@ class CorrespondenceEstimationBase : public PCLBase { , target_() , point_representation_() , input_transformed_() - , target_cloud_updated_(true) - , source_cloud_updated_(true) - , force_no_recompute_(false) - , force_no_recompute_reciprocal_(false) {} /** \brief Empty destructor */ @@ -354,18 +350,18 @@ class CorrespondenceEstimationBase : public PCLBase { /** \brief Variable that stores whether we have a new target cloud, meaning we need to * pre-process it again. This way, we avoid rebuilding the kd-tree for the target * cloud every time the determineCorrespondences () method is called. */ - bool target_cloud_updated_; + bool target_cloud_updated_{true}; /** \brief Variable that stores whether we have a new source cloud, meaning we need to * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the * source cloud every time the determineCorrespondences () method is called. */ - bool source_cloud_updated_; + bool source_cloud_updated_{true}; /** \brief A flag which, if set, means the tree operating on the target cloud * will never be recomputed*/ - bool force_no_recompute_; + bool force_no_recompute_{false}; /** \brief A flag which, if set, means the tree operating on the source cloud * will never be recomputed*/ - bool force_no_recompute_reciprocal_; + bool force_no_recompute_reciprocal_{false}; }; /** \brief @b CorrespondenceEstimation represents the base class for diff --git a/registration/include/pcl/registration/correspondence_estimation_backprojection.h b/registration/include/pcl/registration/correspondence_estimation_backprojection.h index eb695201c93..479b5a60386 100644 --- a/registration/include/pcl/registration/correspondence_estimation_backprojection.h +++ b/registration/include/pcl/registration/correspondence_estimation_backprojection.h @@ -99,7 +99,7 @@ class CorrespondenceEstimationBackProjection * Sets the number of neighbors to be considered in the target point cloud (k_) to 10. */ CorrespondenceEstimationBackProjection() - : source_normals_(), source_normals_transformed_(), target_normals_(), k_(10) + : source_normals_(), source_normals_transformed_(), target_normals_() { corr_name_ = "CorrespondenceEstimationBackProjection"; } @@ -250,7 +250,7 @@ class CorrespondenceEstimationBackProjection NormalsConstPtr target_normals_; /** \brief The number of neighbours to be considered in the target point cloud */ - unsigned int k_; + unsigned int k_{10}; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h index e0e8ab424b5..cab09d4b43d 100644 --- a/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h +++ b/registration/include/pcl/registration/correspondence_estimation_normal_shooting.h @@ -132,7 +132,7 @@ class CorrespondenceEstimationNormalShooting * Sets the number of neighbors to be considered in the target point cloud (k_) to 10. */ CorrespondenceEstimationNormalShooting() - : source_normals_(), source_normals_transformed_(), k_(10) + : source_normals_(), source_normals_transformed_() { corr_name_ = "CorrespondenceEstimationNormalShooting"; } @@ -248,7 +248,7 @@ class CorrespondenceEstimationNormalShooting NormalsPtr source_normals_transformed_; /** \brief The number of neighbours to be considered in the target point cloud */ - unsigned int k_; + unsigned int k_{10}; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h index 97bf14ab188..e7e39e85cc0 100644 --- a/registration/include/pcl/registration/correspondence_estimation_organized_projection.h +++ b/registration/include/pcl/registration/correspondence_estimation_organized_projection.h @@ -90,11 +90,7 @@ class CorrespondenceEstimationOrganizedProjection /** \brief Empty constructor that sets all the intrinsic calibration to the default * Kinect values. */ CorrespondenceEstimationOrganizedProjection() - : fx_(525.f) - , fy_(525.f) - , cx_(319.5f) - , cy_(239.5f) - , src_to_tgt_transformation_(Eigen::Matrix4f::Identity()) + : src_to_tgt_transformation_(Eigen::Matrix4f::Identity()) , depth_threshold_(std::numeric_limits::max()) , projection_matrix_(Eigen::Matrix3f::Identity()) {} @@ -223,8 +219,8 @@ class CorrespondenceEstimationOrganizedProjection bool initCompute(); - float fx_, fy_; - float cx_, cy_; + float fx_{525.f}, fy_{525.f}; + float cx_{319.5f}, cy_{239.5f}; Eigen::Matrix4f src_to_tgt_transformation_; float depth_threshold_; diff --git a/registration/include/pcl/registration/correspondence_rejection.h b/registration/include/pcl/registration/correspondence_rejection.h index 1392d6f6e9b..f68882ab665 100644 --- a/registration/include/pcl/registration/correspondence_rejection.h +++ b/registration/include/pcl/registration/correspondence_rejection.h @@ -198,7 +198,7 @@ class CorrespondenceRejector { protected: /** \brief The name of the rejection method. */ - std::string rejection_name_; + std::string rejection_name_{}; /** \brief The input correspondences. */ CorrespondencesConstPtr input_correspondences_; @@ -254,8 +254,6 @@ class DataContainer : public DataContainerInterface { , tree_(new pcl::search::KdTree) , class_name_("DataContainer") , needs_normals_(needs_normals) - , target_cloud_updated_(true) - , force_no_recompute_(false) {} /** \brief Empty destructor */ @@ -420,11 +418,11 @@ class DataContainer : public DataContainerInterface { /** \brief Variable that stores whether we have a new target cloud, meaning we need to * pre-process it again. This way, we avoid rebuilding the kd-tree */ - bool target_cloud_updated_; + bool target_cloud_updated_{true}; /** \brief A flag which, if set, means the tree operating on the target cloud * will never be recomputed*/ - bool force_no_recompute_; + bool force_no_recompute_{false}; /** \brief Get a string representation of the name of this class. */ inline const std::string& diff --git a/registration/include/pcl/registration/correspondence_rejection_median_distance.h b/registration/include/pcl/registration/correspondence_rejection_median_distance.h index 0d5f00c60bd..16edbbbca95 100644 --- a/registration/include/pcl/registration/correspondence_rejection_median_distance.h +++ b/registration/include/pcl/registration/correspondence_rejection_median_distance.h @@ -68,7 +68,7 @@ class PCL_EXPORTS CorrespondenceRejectorMedianDistance : public CorrespondenceRe using ConstPtr = shared_ptr; /** \brief Empty constructor. */ - CorrespondenceRejectorMedianDistance() : median_distance_(0), factor_(1.0) + CorrespondenceRejectorMedianDistance() { rejection_name_ = "CorrespondenceRejectorMedianDistance"; } @@ -193,12 +193,12 @@ class PCL_EXPORTS CorrespondenceRejectorMedianDistance : public CorrespondenceRe /** \brief The median distance threshold between two correspondent points in source * <-> target. */ - double median_distance_; + double median_distance_{0}; /** \brief The factor for correspondence rejection. Points with distance greater than * median times factor will be rejected */ - double factor_; + double factor_{1.0}; using DataContainerPtr = DataContainerInterface::Ptr; diff --git a/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h b/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h index 25ec0d9581e..23662a515a5 100644 --- a/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h +++ b/registration/include/pcl/registration/correspondence_rejection_organized_boundary.h @@ -59,9 +59,7 @@ class PCL_EXPORTS CorrespondenceRejectionOrganizedBoundary : public CorrespondenceRejector { public: /** @brief Empty constructor. */ - CorrespondenceRejectionOrganizedBoundary() - : boundary_nans_threshold_(8), window_size_(5), depth_step_threshold_(0.025f) - {} + CorrespondenceRejectionOrganizedBoundary() = default; void getRemainingCorrespondences(const pcl::Correspondences& original_correspondences, @@ -141,9 +139,9 @@ class PCL_EXPORTS CorrespondenceRejectionOrganizedBoundary getRemainingCorrespondences(*input_correspondences_, correspondences); } - int boundary_nans_threshold_; - int window_size_; - float depth_step_threshold_; + int boundary_nans_threshold_{8}; + int window_size_{5}; + float depth_step_threshold_{0.025f}; using DataContainerPtr = DataContainerInterface::Ptr; DataContainerPtr data_container_; diff --git a/registration/include/pcl/registration/correspondence_rejection_poly.h b/registration/include/pcl/registration/correspondence_rejection_poly.h index a5615118c97..16ad6ca841b 100644 --- a/registration/include/pcl/registration/correspondence_rejection_poly.h +++ b/registration/include/pcl/registration/correspondence_rejection_poly.h @@ -78,14 +78,7 @@ class PCL_EXPORTS CorrespondenceRejectorPoly : public CorrespondenceRejector { using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr; /** \brief Empty constructor */ - CorrespondenceRejectorPoly() - : iterations_(10000) - , cardinality_(3) - , similarity_threshold_(0.75f) - , similarity_threshold_squared_(0.75f * 0.75f) - { - rejection_name_ = "CorrespondenceRejectorPoly"; - } + CorrespondenceRejectorPoly() { rejection_name_ = "CorrespondenceRejectorPoly"; } /** \brief Get a list of valid correspondences after rejection from the original set * of correspondences. @@ -371,17 +364,17 @@ class PCL_EXPORTS CorrespondenceRejectorPoly : public CorrespondenceRejector { PointCloudTargetConstPtr target_; /** \brief Number of iterations to run */ - int iterations_; + int iterations_{10000}; /** \brief The polygon cardinality used during rejection */ - int cardinality_; + int cardinality_{3}; /** \brief Lower edge length threshold in [0,1] used for verifying polygon * similarities, where 1 is a perfect match */ - float similarity_threshold_; + float similarity_threshold_{0.75f}; /** \brief Squared value if \ref similarity_threshold_, only for internal use */ - float similarity_threshold_squared_; + float similarity_threshold_squared_{0.75f * 0.75f}; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h b/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h index 2920b3325c4..1b464c9bc87 100644 --- a/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h +++ b/registration/include/pcl/registration/correspondence_rejection_sample_consensus.h @@ -67,14 +67,7 @@ class CorrespondenceRejectorSampleConsensus : public CorrespondenceRejector { /** \brief Empty constructor. Sets the inlier threshold to 5cm (0.05m), * and the maximum number of iterations to 1000. */ - CorrespondenceRejectorSampleConsensus() - : inlier_threshold_(0.05) - , max_iterations_(1000) // std::numeric_limits::max () - , input_() - , input_transformed_() - , target_() - , refine_(false) - , save_inliers_(false) + CorrespondenceRejectorSampleConsensus() : input_(), input_transformed_(), target_() { rejection_name_ = "CorrespondenceRejectorSampleConsensus"; } @@ -256,9 +249,9 @@ class CorrespondenceRejectorSampleConsensus : public CorrespondenceRejector { getRemainingCorrespondences(*input_correspondences_, correspondences); } - double inlier_threshold_; + double inlier_threshold_{0.05}; - int max_iterations_; + int max_iterations_{1000}; PointCloudConstPtr input_; PointCloudPtr input_transformed_; @@ -266,9 +259,9 @@ class CorrespondenceRejectorSampleConsensus : public CorrespondenceRejector { Eigen::Matrix4f best_transformation_; - bool refine_; + bool refine_{false}; pcl::Indices inlier_indices_; - bool save_inliers_; + bool save_inliers_{false}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/registration/include/pcl/registration/correspondence_rejection_surface_normal.h b/registration/include/pcl/registration/correspondence_rejection_surface_normal.h index 520276105c1..d2795748e5f 100644 --- a/registration/include/pcl/registration/correspondence_rejection_surface_normal.h +++ b/registration/include/pcl/registration/correspondence_rejection_surface_normal.h @@ -67,7 +67,7 @@ class PCL_EXPORTS CorrespondenceRejectorSurfaceNormal : public CorrespondenceRej using ConstPtr = shared_ptr; /** \brief Empty constructor. Sets the threshold to 1.0. */ - CorrespondenceRejectorSurfaceNormal() : threshold_(1.0) + CorrespondenceRejectorSurfaceNormal() { rejection_name_ = "CorrespondenceRejectorSurfaceNormal"; } @@ -342,7 +342,7 @@ class PCL_EXPORTS CorrespondenceRejectorSurfaceNormal : public CorrespondenceRej /** \brief The median distance threshold between two correspondent points in source * <-> target. */ - double threshold_; + double threshold_{1.0}; using DataContainerPtr = DataContainerInterface::Ptr; /** \brief A pointer to the DataContainer object containing the input and target point diff --git a/registration/include/pcl/registration/correspondence_rejection_trimmed.h b/registration/include/pcl/registration/correspondence_rejection_trimmed.h index 1b037bfe7de..202ca9d566a 100644 --- a/registration/include/pcl/registration/correspondence_rejection_trimmed.h +++ b/registration/include/pcl/registration/correspondence_rejection_trimmed.h @@ -68,10 +68,7 @@ class PCL_EXPORTS CorrespondenceRejectorTrimmed : public CorrespondenceRejector using ConstPtr = shared_ptr; /** \brief Empty constructor. */ - CorrespondenceRejectorTrimmed() : overlap_ratio_(0.5f), nr_min_correspondences_(0) - { - rejection_name_ = "CorrespondenceRejectorTrimmed"; - } + CorrespondenceRejectorTrimmed() { rejection_name_ = "CorrespondenceRejectorTrimmed"; } /** \brief Destructor. */ ~CorrespondenceRejectorTrimmed() override = default; @@ -135,10 +132,10 @@ class PCL_EXPORTS CorrespondenceRejectorTrimmed : public CorrespondenceRejector } /** Overlap Ratio in [0..1] */ - float overlap_ratio_; + float overlap_ratio_{0.5f}; /** Minimum number of correspondences. */ - unsigned int nr_min_correspondences_; + unsigned int nr_min_correspondences_{0}; }; } // namespace registration diff --git a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h index e5b5c7a7aa6..7d7607fa9cb 100644 --- a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h +++ b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h @@ -73,7 +73,6 @@ class PCL_EXPORTS CorrespondenceRejectorVarTrimmed : public CorrespondenceReject /** \brief Empty constructor. */ CorrespondenceRejectorVarTrimmed() - : trimmed_distance_(0), factor_(), min_ratio_(0.05), max_ratio_(0.95), lambda_(0.95) { rejection_name_ = "CorrespondenceRejectorVarTrimmed"; } @@ -224,26 +223,26 @@ class PCL_EXPORTS CorrespondenceRejectorVarTrimmed : public CorrespondenceReject /** \brief The inlier distance threshold (based on the computed trim factor) between * two correspondent points in source <-> target. */ - double trimmed_distance_; + double trimmed_distance_{0}; /** \brief The factor for correspondence rejection. Only factor times the total points * sorted based on the correspondence distances will be considered as inliers. * Remaining points are rejected. This factor is computed internally */ - double factor_; + double factor_{0.0}; /** \brief The minimum overlap ratio between the input and target clouds */ - double min_ratio_; + double min_ratio_{0.05}; /** \brief The maximum overlap ratio between the input and target clouds */ - double max_ratio_; + double max_ratio_{0.95}; /** \brief part of the term that balances the root mean square difference. This is an * internal parameter */ - double lambda_; + double lambda_{0.95}; using DataContainerPtr = DataContainerInterface::Ptr; diff --git a/registration/include/pcl/registration/default_convergence_criteria.h b/registration/include/pcl/registration/default_convergence_criteria.h index dd742438587..b8cbd795ad6 100644 --- a/registration/include/pcl/registration/default_convergence_criteria.h +++ b/registration/include/pcl/registration/default_convergence_criteria.h @@ -97,17 +97,6 @@ class DefaultConvergenceCriteria : public ConvergenceCriteria { : iterations_(iterations) , transformation_(transform) , correspondences_(correspondences) - , correspondences_prev_mse_(std::numeric_limits::max()) - , correspondences_cur_mse_(std::numeric_limits::max()) - , max_iterations_(100) // 100 iterations - , failure_after_max_iter_(false) - , rotation_threshold_(0.99999) // 0.256 degrees - , translation_threshold_(3e-4 * 3e-4) // 0.0003 meters - , mse_threshold_relative_(0.00001) // 0.001% of the previous MSE (relative error) - , mse_threshold_absolute_(1e-12) // MSE (absolute error) - , iterations_similar_transforms_(0) - , max_iterations_similar_transforms_(0) - , convergence_state_(CONVERGENCE_CRITERIA_NOT_CONVERGED) {} /** \brief Empty destructor */ @@ -291,45 +280,45 @@ class DefaultConvergenceCriteria : public ConvergenceCriteria { const pcl::Correspondences& correspondences_; /** \brief The MSE for the previous set of correspondences. */ - double correspondences_prev_mse_; + double correspondences_prev_mse_{std::numeric_limits::max()}; /** \brief The MSE for the current set of correspondences. */ - double correspondences_cur_mse_; + double correspondences_cur_mse_{std::numeric_limits::max()}; /** \brief The maximum nuyyGmber of iterations that the registration loop is to be * executed. */ - int max_iterations_; + int max_iterations_{100}; /** \brief Specifys if the registration fails or converges when the maximum number of * iterations is reached. */ - bool failure_after_max_iter_; + bool failure_after_max_iter_{false}; /** \brief The rotation threshold is the relative rotation between two iterations (as * angle cosine). */ - double rotation_threshold_; + double rotation_threshold_{0.99999}; /** \brief The translation threshold is the relative translation between two * iterations (0 if no translation). */ - double translation_threshold_; + double translation_threshold_{3e-4 * 3e-4}; // 0.0003 meters /** \brief The relative change from the previous MSE for the current set of * correspondences, e.g. .1 means 10% change. */ - double mse_threshold_relative_; + double mse_threshold_relative_{0.00001}; /** \brief The absolute change from the previous MSE for the current set of * correspondences. */ - double mse_threshold_absolute_; + double mse_threshold_absolute_{1e-12}; /** \brief Internal counter for the number of iterations that the internal * rotation, translation, and MSE differences are allowed to be similar. */ - int iterations_similar_transforms_; + int iterations_similar_transforms_{0}; /** \brief The maximum number of iterations that the internal rotation, * translation, and MSE differences are allowed to be similar. */ - int max_iterations_similar_transforms_; + int max_iterations_similar_transforms_{0}; /** \brief The state of the convergence (e.g., why did the registration converge). */ - ConvergenceState convergence_state_; + ConvergenceState convergence_state_{CONVERGENCE_CRITERIA_NOT_CONVERGED}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/registration/include/pcl/registration/elch.h b/registration/include/pcl/registration/elch.h index 5453b0c8ca9..5e4a897512b 100644 --- a/registration/include/pcl/registration/elch.h +++ b/registration/include/pcl/registration/elch.h @@ -90,7 +90,6 @@ class ELCH : public PCLBase { , loop_start_(0) , loop_end_(0) , reg_(new pcl::IterativeClosestPoint) - , compute_loop_(true) , vd_(){}; /** \brief Empty destructor */ @@ -239,7 +238,7 @@ class ELCH : public PCLBase { /** \brief The transformation between that start and end of the loop. */ Eigen::Matrix4f loop_transform_; - bool compute_loop_; + bool compute_loop_{true}; /** \brief previously added node in the loop_graph_. */ typename boost::graph_traits::vertex_descriptor vd_; diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index b0fad8046cb..53811b29e99 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -116,14 +116,7 @@ class GeneralizedIterativeClosestPoint PCL_MAKE_ALIGNED_OPERATOR_NEW /** \brief Empty constructor. */ - GeneralizedIterativeClosestPoint() - : k_correspondences_(20) - , gicp_epsilon_(0.001) - , rotation_epsilon_(2e-3) - , mahalanobis_(0) - , max_inner_iterations_(20) - , translation_gradient_tolerance_(1e-2) - , rotation_gradient_tolerance_(1e-2) + GeneralizedIterativeClosestPoint() : mahalanobis_(0) { min_number_correspondences_ = 4; reg_name_ = "GeneralizedIterativeClosestPoint"; @@ -332,19 +325,19 @@ class GeneralizedIterativeClosestPoint /** \brief The number of neighbors used for covariances computation. * default: 20 */ - int k_correspondences_; + int k_correspondences_{20}; /** \brief The epsilon constant for gicp paper; this is NOT the convergence * tolerance * default: 0.001 */ - double gicp_epsilon_; + double gicp_epsilon_{0.001}; /** The epsilon constant for rotation error. (In GICP the transformation epsilon * is split in rotation part and translation part). * default: 2e-3 */ - double rotation_epsilon_; + double rotation_epsilon_{2e-3}; /** \brief base transformation */ Matrix4 base_transformation_; @@ -371,13 +364,13 @@ class GeneralizedIterativeClosestPoint std::vector mahalanobis_; /** \brief maximum number of optimizations */ - int max_inner_iterations_; + int max_inner_iterations_{20}; /** \brief minimal translation gradient for early optimization stop */ - double translation_gradient_tolerance_; + double translation_gradient_tolerance_{1e-2}; /** \brief minimal rotation gradient for early optimization stop */ - double rotation_gradient_tolerance_; + double rotation_gradient_tolerance_{1e-2}; /** \brief compute points covariances matrices according to the K nearest * neighbors. K is set via setCorrespondenceRandomness() method. diff --git a/registration/include/pcl/registration/ia_fpcs.h b/registration/include/pcl/registration/ia_fpcs.h index 220a58b6b20..abff434f527 100644 --- a/registration/include/pcl/registration/ia_fpcs.h +++ b/registration/include/pcl/registration/ia_fpcs.h @@ -470,10 +470,10 @@ class FPCSInitialAlignment : public Registration full cloud). */ - int nr_samples_; + int nr_samples_{0}; /** \brief Maximum normal difference of corresponding point pairs in degrees (standard * = 90). */ - float max_norm_diff_; + float max_norm_diff_{90.f}; /** \brief Maximum allowed computation time in seconds (standard = 0 => ~unlimited). */ - int max_runtime_; + int max_runtime_{0}; /** \brief Resulting fitness score of the best match. */ float fitness_score_; /** \brief Estimated diameter of the target point cloud. */ - float diameter_; + float diameter_{0.0f}; /** \brief Estimated squared metric overlap between source and target. * \note Internally calculated using the estimated overlap and the extent of the * source cloud. It is used to derive the minimum sampling distance of the base points * as well as to calculated the number of tries to reliably find a correct match. */ - float max_base_diameter_sqr_; + float max_base_diameter_sqr_{0.0f}; /** \brief Use normals flag. */ - bool use_normals_; + bool use_normals_{false}; /** \brief Normalize delta flag. */ - bool normalize_delta_; + bool normalize_delta_{true}; /** \brief A pointer to the vector of source point indices to use after sampling. */ pcl::IndicesPtr source_indices_; @@ -529,30 +529,30 @@ class FPCSInitialAlignment : public Registration) , error_functor_() { @@ -313,14 +310,14 @@ class SampleConsensusInitialAlignment : public Registration::ConstPtr& cloud std::vector dists_sqr(2); pcl::utils::ignore(nr_threads); -#pragma omp parallel for \ - default(none) \ - shared(tree, cloud) \ - firstprivate(ids, dists_sqr) \ - reduction(+:mean_dist, num) \ - firstprivate(s, max_dist_sqr) \ - num_threads(nr_threads) +#pragma omp parallel for default(none) shared(tree, cloud) \ + firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) \ + firstprivate(s, max_dist_sqr) num_threads(nr_threads) for (int i = 0; i < 1000; i++) { tree.nearestKSearch((*cloud)[rand() % s], 2, ids, dists_sqr); if (dists_sqr[1] < max_dist_sqr) { @@ -105,19 +101,11 @@ pcl::getMeanPointDensity(const typename pcl::PointCloud::ConstPtr& cloud pcl::utils::ignore(nr_threads); #if OPENMP_LEGACY_CONST_DATA_SHARING_RULE -#pragma omp parallel for \ - default(none) \ - shared(tree, cloud, indices) \ - firstprivate(ids, dists_sqr) \ - reduction(+:mean_dist, num) \ - num_threads(nr_threads) +#pragma omp parallel for default(none) shared(tree, cloud, indices) \ + firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads) #else -#pragma omp parallel for \ - default(none) \ - shared(tree, cloud, indices, s, max_dist_sqr) \ - firstprivate(ids, dists_sqr) \ - reduction(+:mean_dist, num) \ - num_threads(nr_threads) +#pragma omp parallel for default(none) shared(tree, cloud, indices, s, max_dist_sqr) \ + firstprivate(ids, dists_sqr) reduction(+ : mean_dist, num) num_threads(nr_threads) #endif for (int i = 0; i < 1000; i++) { tree.nearestKSearch((*cloud)[indices[rand() % s]], 2, ids, dists_sqr); @@ -136,24 +124,8 @@ pcl::registration::FPCSInitialAlignment::max()) -, nr_samples_(0) -, max_norm_diff_(90.f) -, max_runtime_(0) , fitness_score_(std::numeric_limits::max()) -, diameter_() -, max_base_diameter_sqr_() -, use_normals_(false) -, normalize_delta_(true) -, max_pair_diff_() -, max_edge_diff_() -, coincidation_limit_() -, max_mse_() -, max_inlier_dist_sqr_() -, small_error_(0.00001f) { reg_name_ = "pcl::registration::FPCSInitialAlignment"; max_iterations_ = 0; diff --git a/registration/include/pcl/registration/impl/ia_kfpcs.hpp b/registration/include/pcl/registration/impl/ia_kfpcs.hpp index 7d0973b4265..93a9bc570ee 100644 --- a/registration/include/pcl/registration/impl/ia_kfpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_kfpcs.hpp @@ -46,11 +46,7 @@ namespace registration { template KFPCSInitialAlignment:: KFPCSInitialAlignment() -: lower_trl_boundary_(-1.f) -, upper_trl_boundary_(-1.f) -, lambda_(0.5f) -, use_trl_score_(false) -, indices_validation_(new pcl::Indices) +: indices_validation_(new pcl::Indices) { reg_name_ = "pcl::registration::KFPCSInitialAlignment"; } diff --git a/registration/include/pcl/registration/impl/ndt.hpp b/registration/include/pcl/registration/impl/ndt.hpp index 5b6c15313ff..e3192073d68 100644 --- a/registration/include/pcl/registration/impl/ndt.hpp +++ b/registration/include/pcl/registration/impl/ndt.hpp @@ -46,13 +46,7 @@ namespace pcl { template NormalDistributionsTransform:: NormalDistributionsTransform() -: target_cells_() -, resolution_(1.0f) -, step_size_(0.1) -, outlier_ratio_(0.55) -, gauss_d1_() -, gauss_d2_() -, trans_likelihood_() +: target_cells_(), trans_likelihood_() { reg_name_ = "NormalDistributionsTransform"; diff --git a/registration/include/pcl/registration/impl/ndt_2d.hpp b/registration/include/pcl/registration/impl/ndt_2d.hpp index 1aeb6d1bdb0..a4b5dd42241 100644 --- a/registration/include/pcl/registration/impl/ndt_2d.hpp +++ b/registration/include/pcl/registration/impl/ndt_2d.hpp @@ -99,7 +99,7 @@ class NormalDist { using PointCloud = pcl::PointCloud; public: - NormalDist() : min_n_(3), n_(0) {} + NormalDist() = default; /** \brief Store a point index to use later for estimating distribution parameters. * \param[in] i Point index to store @@ -203,9 +203,9 @@ class NormalDist { } protected: - const std::size_t min_n_; + const std::size_t min_n_{3}; - std::size_t n_; + std::size_t n_{0}; std::vector pt_indices_; Eigen::Vector2d mean_; Eigen::Matrix2d covar_inv_; diff --git a/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp b/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp index 0440178457a..ba7b4eebd0a 100644 --- a/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp +++ b/registration/include/pcl/registration/impl/pyramid_feature_matching.hpp @@ -131,12 +131,7 @@ PyramidFeatureHistogram::comparePyramidFeatureHistograms( template PyramidFeatureHistogram::PyramidFeatureHistogram() -: nr_dimensions(0) -, nr_levels(0) -, nr_features(0) -, feature_representation_(new DefaultPointRepresentation) -, is_computed_(false) -, hist_levels() +: feature_representation_(new DefaultPointRepresentation), hist_levels() {} template diff --git a/registration/include/pcl/registration/impl/transformation_estimation_lm.hpp b/registration/include/pcl/registration/impl/transformation_estimation_lm.hpp index fe01a34a633..21ccee1f76a 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_lm.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_lm.hpp @@ -50,8 +50,6 @@ pcl::registration::TransformationEstimationLM){}; ////////////////////////////////////////////////////////////////////////////////////////////// @@ -294,7 +292,7 @@ pcl::registration::TransformationEstimationLM; +// #define PCL_INSTANTIATE_TransformationEstimationLM(T,U) template class PCL_EXPORTS +// pcl::registration::TransformationEstimationLM; #endif /* PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_LM_HPP_ */ diff --git a/registration/include/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp b/registration/include/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp index ffa983dfd42..a31b8ec010f 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_point_to_plane_weighted.hpp @@ -53,10 +53,8 @@ pcl::registration::TransformationEstimationPointToPlaneWeighted< MatScalar>::TransformationEstimationPointToPlaneWeighted() : tmp_src_() , tmp_tgt_() -, tmp_idx_src_() -, tmp_idx_tgt_() , warp_point_(new WarpPointRigid6D) -, use_correspondence_weights_(true){}; +{} ////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/registration/include/pcl/registration/lum.h b/registration/include/pcl/registration/lum.h index 97d2df64408..f6354ae047b 100644 --- a/registration/include/pcl/registration/lum.h +++ b/registration/include/pcl/registration/lum.h @@ -139,7 +139,7 @@ class LUM { /** \brief Empty constructor. */ - LUM() : slam_graph_(new SLAMGraph), max_iterations_(5), convergence_threshold_(0.0) {} + LUM() : slam_graph_(new SLAMGraph) {} /** \brief Set the internal SLAM graph structure. * \details All data used and produced by LUM is stored in this boost::adjacency_list. @@ -343,10 +343,10 @@ class LUM { SLAMGraphPtr slam_graph_; /** \brief The maximum number of iterations for the compute() method. */ - int max_iterations_; + int max_iterations_{5}; /** \brief The convergence threshold for the summed vector lengths of all poses. */ - float convergence_threshold_; + float convergence_threshold_{0.0}; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index 81788ed687d..7fbb6403b32 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -557,18 +557,18 @@ class NormalDistributionsTransform TargetGrid target_cells_; /** \brief The side length of voxels. */ - float resolution_; + float resolution_{1.0f}; /** \brief The maximum step length. */ - double step_size_; + double step_size_{0.1}; /** \brief The ratio of outliers of points w.r.t. a normal distribution, * Equation 6.7 [Magnusson 2009]. */ - double outlier_ratio_; + double outlier_ratio_{0.55}; /** \brief The normalization constants used fit the point distribution to a * normal distribution, Equation 6.8 [Magnusson 2009]. */ - double gauss_d1_, gauss_d2_; + double gauss_d1_{0.0}, gauss_d2_{0.0}; /** \brief The likelihood score of the transform applied to the input cloud, * Equation 6.9 and 6.10 [Magnusson 2009]. */ @@ -577,7 +577,7 @@ class NormalDistributionsTransform 16, "`trans_probability_` has been renamed to `trans_likelihood_`.") double trans_probability_; - double trans_likelihood_; + double trans_likelihood_{0.0}; }; /** \brief Precomputed Angular Gradient diff --git a/registration/include/pcl/registration/ppf_registration.h b/registration/include/pcl/registration/ppf_registration.h index 0e4bacea2ec..fbb5ed39f93 100644 --- a/registration/include/pcl/registration/ppf_registration.h +++ b/registration/include/pcl/registration/ppf_registration.h @@ -92,10 +92,8 @@ class PCL_EXPORTS PPFHashMapSearch { static_cast(M_PI), float distance_discretization_step = 0.01f) : feature_hash_map_(new FeatureHashMapType) - , internals_initialized_(false) , angle_discretization_step_(angle_discretization_step) , distance_discretization_step_(distance_discretization_step) - , max_dist_(-1.0f) {} /** \brief Method that sets the feature cloud to be inserted in the hash map @@ -155,10 +153,10 @@ class PCL_EXPORTS PPFHashMapSearch { private: FeatureHashMapTypePtr feature_hash_map_; - bool internals_initialized_; + bool internals_initialized_{false}; float angle_discretization_step_, distance_discretization_step_; - float max_dist_; + float max_dist_{-1.0f}; }; /** \brief Class that registers two point clouds based on their sets of PPFSignatures. @@ -212,8 +210,6 @@ class PPFRegistration : public Registration { * default values */ PPFRegistration() : Registration() - , scene_reference_point_sampling_rate_(5) - , clustering_position_diff_threshold_(0.01f) , clustering_rotation_diff_threshold_(20.0f / 180.0f * static_cast(M_PI)) {} @@ -323,12 +319,12 @@ class PPFRegistration : public Registration { PPFHashMapSearch::Ptr search_method_; /** \brief parameter for the sampling rate of the scene reference points */ - uindex_t scene_reference_point_sampling_rate_; + uindex_t scene_reference_point_sampling_rate_{5}; /** \brief position and rotation difference thresholds below which two * poses are considered to be in the same cluster (for the clustering phase of the * algorithm) */ - float clustering_position_diff_threshold_, clustering_rotation_diff_threshold_; + float clustering_position_diff_threshold_{0.01f}, clustering_rotation_diff_threshold_; /** \brief use a kd-tree with range searches of range max_dist to skip an O(N) pass * through the point cloud */ diff --git a/registration/include/pcl/registration/pyramid_feature_matching.h b/registration/include/pcl/registration/pyramid_feature_matching.h index 8a243559d59..b16b9a9edd8 100644 --- a/registration/include/pcl/registration/pyramid_feature_matching.h +++ b/registration/include/pcl/registration/pyramid_feature_matching.h @@ -153,10 +153,10 @@ class PyramidFeatureHistogram : public PCLBase { const PyramidFeatureHistogramPtr& pyramid_b); private: - std::size_t nr_dimensions, nr_levels, nr_features; + std::size_t nr_dimensions{0}, nr_levels{0}, nr_features{0}; std::vector> dimension_range_input_, dimension_range_target_; FeatureRepresentationConstPtr feature_representation_; - bool is_computed_; + bool is_computed_{false}; /** \brief Checks for input inconsistencies and initializes the underlying data * structures */ diff --git a/registration/include/pcl/registration/registration.h b/registration/include/pcl/registration/registration.h index e702b944c3c..da80847ff7a 100644 --- a/registration/include/pcl/registration/registration.h +++ b/registration/include/pcl/registration/registration.h @@ -109,27 +109,15 @@ class Registration : public PCLBase { Registration() : tree_(new KdTree) , tree_reciprocal_(new KdTreeReciprocal) - , nr_iterations_(0) - , max_iterations_(10) - , ransac_iterations_(0) , target_() , final_transformation_(Matrix4::Identity()) , transformation_(Matrix4::Identity()) , previous_transformation_(Matrix4::Identity()) - , transformation_epsilon_(0.0) - , transformation_rotation_epsilon_(0.0) , euclidean_fitness_epsilon_(-std::numeric_limits::max()) , corr_dist_threshold_(std::sqrt(std::numeric_limits::max())) - , inlier_threshold_(0.05) - , converged_(false) - , min_number_correspondences_(3) , correspondences_(new Correspondences) , transformation_estimation_() , correspondence_estimation_() - , target_cloud_updated_(true) - , source_cloud_updated_(true) - , force_no_recompute_(false) - , force_no_recompute_reciprocal_(false) , point_representation_() {} @@ -567,15 +555,15 @@ class Registration : public PCLBase { /** \brief The number of iterations the internal optimization ran for (used * internally). */ - int nr_iterations_; + int nr_iterations_{0}; /** \brief The maximum number of iterations the internal optimization should run for. * The default value is 10. */ - int max_iterations_; + int max_iterations_{10}; /** \brief The number of iterations RANSAC should run for. */ - int ransac_iterations_; + int ransac_iterations_{0}; /** \brief The input point cloud dataset target. */ PointCloudTargetConstPtr target_; @@ -594,12 +582,12 @@ class Registration : public PCLBase { /** \brief The maximum difference between two consecutive transformations in order to * consider convergence (user defined). */ - double transformation_epsilon_; + double transformation_epsilon_{0.0}; /** \brief The maximum rotation difference between two consecutive transformations in * order to consider convergence (user defined). */ - double transformation_rotation_epsilon_; + double transformation_rotation_epsilon_{0.0}; /** \brief The maximum allowed Euclidean error between two consecutive steps in the * ICP loop, before the algorithm is considered to have converged. The error is @@ -619,15 +607,15 @@ class Registration : public PCLBase { * target data index and the transformed source index is smaller than the given inlier * distance threshold. The default value is 0.05. */ - double inlier_threshold_; + double inlier_threshold_{0.05}; /** \brief Holds internal convergence state, given user parameters. */ - bool converged_; + bool converged_{false}; /** \brief The minimum number of correspondences that the algorithm needs before * attempting to estimate the transformation. The default value is 3. */ - unsigned int min_number_correspondences_; + unsigned int min_number_correspondences_{3}; /** \brief The set of correspondences determined at this ICP step. */ CorrespondencesPtr correspondences_; @@ -646,18 +634,18 @@ class Registration : public PCLBase { /** \brief Variable that stores whether we have a new target cloud, meaning we need to * pre-process it again. This way, we avoid rebuilding the kd-tree for the target * cloud every time the determineCorrespondences () method is called. */ - bool target_cloud_updated_; + bool target_cloud_updated_{true}; /** \brief Variable that stores whether we have a new source cloud, meaning we need to * pre-process it again. This way, we avoid rebuilding the reciprocal kd-tree for the * source cloud every time the determineCorrespondences () method is called. */ - bool source_cloud_updated_; + bool source_cloud_updated_{true}; /** \brief A flag which, if set, means the tree operating on the target cloud * will never be recomputed*/ - bool force_no_recompute_; + bool force_no_recompute_{false}; /** \brief A flag which, if set, means the tree operating on the source cloud * will never be recomputed*/ - bool force_no_recompute_reciprocal_; + bool force_no_recompute_reciprocal_{false}; /** \brief Callback function to update intermediate source point cloud position during * it's registration to the target point cloud. diff --git a/registration/include/pcl/registration/sample_consensus_prerejective.h b/registration/include/pcl/registration/sample_consensus_prerejective.h index f2b4e8cac6e..3d67b293092 100644 --- a/registration/include/pcl/registration/sample_consensus_prerejective.h +++ b/registration/include/pcl/registration/sample_consensus_prerejective.h @@ -121,11 +121,8 @@ class SampleConsensusPrerejective : public Registration) , correspondence_rejector_poly_(new CorrespondenceRejectorPoly) - , inlier_fraction_(0.0f) { reg_name_ = "SampleConsensusPrerejective"; correspondence_rejector_poly_->setSimilarityThreshold(0.6f); @@ -305,11 +302,11 @@ class SampleConsensusPrerejective : public Registration::Ptr 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 8d42452bdbb..6b4453f63b3 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 @@ -198,20 +198,20 @@ class TransformationEstimationPointToPlaneWeighted } protected: - bool use_correspondence_weights_; - mutable std::vector correspondence_weights_; + bool use_correspondence_weights_{true}; + mutable std::vector correspondence_weights_{}; /** \brief Temporary pointer to the source dataset. */ - mutable const PointCloudSource* tmp_src_; + mutable const PointCloudSource* tmp_src_{nullptr}; /** \brief Temporary pointer to the target dataset. */ - mutable const PointCloudTarget* tmp_tgt_; + mutable const PointCloudTarget* tmp_tgt_{nullptr}; /** \brief Temporary pointer to the source dataset indices. */ - mutable const pcl::Indices* tmp_idx_src_; + mutable const pcl::Indices* tmp_idx_src_{nullptr}; /** \brief Temporary pointer to the target dataset indices. */ - mutable const pcl::Indices* tmp_idx_tgt_; + mutable const pcl::Indices* tmp_idx_tgt_{nullptr}; /** \brief The parameterized function used to warp the source to the target. */ typename pcl::registration::WarpPointRigid::Ptr 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 057fa2bb26f..bb22c94aadd 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 @@ -71,8 +71,7 @@ class TransformationEstimationSymmetricPointToPlaneLLS typename TransformationEstimation::Matrix4; using Vector6 = Eigen::Matrix; - TransformationEstimationSymmetricPointToPlaneLLS() - : enforce_same_direction_normals_(true){}; + TransformationEstimationSymmetricPointToPlaneLLS() = default; ~TransformationEstimationSymmetricPointToPlaneLLS() override = default; /** \brief Estimate a rigid rotation transformation between a source and a target @@ -161,7 +160,7 @@ class TransformationEstimationSymmetricPointToPlaneLLS /** \brief Whether or not to negate source and/or target normals such that they point * in the same direction */ - bool enforce_same_direction_normals_; + bool enforce_same_direction_normals_{true}; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/transformation_validation_euclidean.h b/registration/include/pcl/registration/transformation_validation_euclidean.h index b22ed68adaf..83ffeb2657c 100644 --- a/registration/include/pcl/registration/transformation_validation_euclidean.h +++ b/registration/include/pcl/registration/transformation_validation_euclidean.h @@ -101,7 +101,6 @@ class TransformationValidationEuclidean { : max_range_(std::numeric_limits::max()) , threshold_(std::numeric_limits::quiet_NaN()) , tree_(new pcl::search::KdTree) - , force_no_recompute_(false) {} virtual ~TransformationValidationEuclidean() = default; @@ -229,7 +228,7 @@ class TransformationValidationEuclidean { /** \brief A flag which, if set, means the tree operating on the target cloud * will never be recomputed*/ - bool force_no_recompute_; + bool force_no_recompute_{false}; /** \brief Internal point representation uses only 3D coordinates for L2 */ class MyPointRepresentation : public pcl::PointRepresentation { diff --git a/search/include/pcl/search/flann_search.h b/search/include/pcl/search/flann_search.h index 8d994895c59..f093a572809 100644 --- a/search/include/pcl/search/flann_search.h +++ b/search/include/pcl/search/flann_search.h @@ -348,22 +348,22 @@ namespace pcl /** Epsilon for approximate NN search. */ - float eps_; + float eps_{0.0f}; /** Number of checks to perform for approximate NN search using the multiple randomized tree index */ - int checks_; + int checks_{32}; - bool input_copied_for_flann_; + bool input_copied_for_flann_{false}; - PointRepresentationConstPtr point_representation_; + PointRepresentationConstPtr point_representation_{nullptr}; - int dim_; + int dim_{0}; Indices index_mapping_; - bool identity_mapping_; + bool identity_mapping_{false}; - std::size_t total_nr_points_; + std::size_t total_nr_points_{0}; }; } diff --git a/search/include/pcl/search/impl/flann_search.hpp b/search/include/pcl/search/impl/flann_search.hpp index 218fd690998..2026db79e9b 100644 --- a/search/include/pcl/search/impl/flann_search.hpp +++ b/search/include/pcl/search/impl/flann_search.hpp @@ -76,8 +76,7 @@ pcl::search::FlannSearch::KdTreeMultiIndexCreator::create ////////////////////////////////////////////////////////////////////////////////////////////// template pcl::search::FlannSearch::FlannSearch(bool sorted, FlannIndexCreatorPtr creator) : pcl::search::Search ("FlannSearch",sorted), - index_(), creator_ (creator), eps_ (0), checks_ (32), input_copied_for_flann_ (false), point_representation_ (new DefaultPointRepresentation), - dim_ (0), identity_mapping_() + index_(), creator_ (creator), point_representation_ (new DefaultPointRepresentation) { dim_ = point_representation_->getNumberOfDimensions (); } diff --git a/simulation/include/pcl/simulation/range_likelihood.h b/simulation/include/pcl/simulation/range_likelihood.h index aab4bbb4249..0bd2b8a851b 100644 --- a/simulation/include/pcl/simulation/range_likelihood.h +++ b/simulation/include/pcl/simulation/range_likelihood.h @@ -276,31 +276,31 @@ class PCL_EXPORTS RangeLikelihood { float z_far_; // For caching only, not part of observable state. - mutable bool depth_buffer_dirty_; - mutable bool color_buffer_dirty_; - mutable bool score_buffer_dirty_; + mutable bool depth_buffer_dirty_{true}; + mutable bool color_buffer_dirty_{true}; + mutable bool score_buffer_dirty_{true}; int which_cost_function_; double floor_proportion_; double sigma_; - GLuint fbo_; + GLuint fbo_{0}; GLuint score_fbo_; - GLuint depth_render_buffer_; - GLuint color_render_buffer_; + GLuint depth_render_buffer_{0}; + GLuint color_render_buffer_{0}; GLuint color_texture_; - GLuint depth_texture_; - GLuint score_texture_; - GLuint score_summarized_texture_; - GLuint sensor_texture_; - GLuint likelihood_texture_; - - bool compute_likelihood_on_cpu_; - bool aggregate_on_cpu_; - bool use_instancing_; + GLuint depth_texture_{0}; + GLuint score_texture_{0}; + GLuint score_summarized_texture_{0}; + GLuint sensor_texture_{0}; + GLuint likelihood_texture_{0}; + + bool compute_likelihood_on_cpu_{false}; + bool aggregate_on_cpu_{false}; + bool use_instancing_{false}; bool generate_color_image_; - bool use_color_; + bool use_color_{true}; gllib::Program::Ptr likelihood_program_; GLuint quad_vbo_; diff --git a/simulation/src/range_likelihood.cpp b/simulation/src/range_likelihood.cpp index f09315593dc..34961f9f58d 100644 --- a/simulation/src/range_likelihood.cpp +++ b/simulation/src/range_likelihood.cpp @@ -279,21 +279,6 @@ pcl::simulation::RangeLikelihood::RangeLikelihood( , cols_(cols) , row_height_(row_height) , col_width_(col_width) -, depth_buffer_dirty_(true) -, color_buffer_dirty_(true) -, score_buffer_dirty_(true) -, fbo_(0) -, depth_render_buffer_(0) -, color_render_buffer_(0) -, depth_texture_(0) -, score_texture_(0) -, score_summarized_texture_(0) -, sensor_texture_(0) -, likelihood_texture_(0) -, compute_likelihood_on_cpu_(false) -, aggregate_on_cpu_(false) -, use_instancing_(false) -, use_color_(true) , sum_reduce_(cols * col_width, rows * row_height, max_level(col_width, row_height)) { height_ = rows_ * row_height; diff --git a/test/common/test_transforms.cpp b/test/common/test_transforms.cpp index 36f4a62deed..cfac20d6700 100644 --- a/test/common/test_transforms.cpp +++ b/test/common/test_transforms.cpp @@ -61,10 +61,7 @@ class Transforms : public ::testing::Test { public: using Scalar = typename Transform::Scalar; - Transforms () - : ABS_ERROR (std::numeric_limits::epsilon () * 10) - , CLOUD_SIZE (100) { Eigen::Matrix r = Eigen::Matrix::Random (); Eigen::Transform transform; @@ -93,9 +90,8 @@ class Transforms : public ::testing::Test indices[i] = i * 2; } - const Scalar ABS_ERROR; - const std::size_t CLOUD_SIZE; - + const Scalar ABS_ERROR{std::numeric_limits::epsilon () * 10}; + const std::size_t CLOUD_SIZE{100}; Transform tf; // Random point clouds and their expected transformed versions diff --git a/test/octree/test_octree_iterator.cpp b/test/octree/test_octree_iterator.cpp index 07332be6ab1..a7fbb988cdb 100644 --- a/test/octree/test_octree_iterator.cpp +++ b/test/octree/test_octree_iterator.cpp @@ -1467,7 +1467,6 @@ struct OctreePointCloudSierpinskiTest // Methods OctreePointCloudSierpinskiTest () : oct_ (1) - , depth_ (7) {} void SetUp () override @@ -1597,7 +1596,7 @@ struct OctreePointCloudSierpinskiTest // Members OctreeT oct_; - const unsigned depth_; + const unsigned depth_{7}; }; /** \brief Octree test based on a Sierpinski fractal diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index fe70dfa7e8c..cb5cfff4aca 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -394,7 +394,7 @@ class OutofcoreTest : public testing::Test { protected: - OutofcoreTest () : smallest_voxel_dim () {} + OutofcoreTest () = default; void SetUp () override { @@ -420,7 +420,7 @@ class OutofcoreTest : public testing::Test } - double smallest_voxel_dim; + double smallest_voxel_dim{3.0f}; }; From 39286608163487d4b5eb7ff81b7e7f3139732f0a Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Tue, 24 Oct 2023 19:39:29 +0200 Subject: [PATCH 141/288] Add test for GICP with BFGS optimizer --- test/registration/test_registration.cpp | 62 +++++++++++++++++++++++++ 1 file changed, 62 insertions(+) diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index 8b90cab08b7..0b2d33712aa 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -585,6 +585,68 @@ TEST (PCL, GeneralizedIterativeClosestPoint) EXPECT_LT (reg.getFitnessScore (), 0.0001); } +TEST (PCL, GeneralizedIterativeClosestPointBFGS) +{ // same as above, but uses BFGS optimizer + using PointT = PointXYZ; + PointCloud::Ptr src (new PointCloud); + copyPointCloud (cloud_source, *src); + PointCloud::Ptr tgt (new PointCloud); + copyPointCloud (cloud_target, *tgt); + PointCloud output; + + GeneralizedIterativeClosestPoint reg; + reg.useBFGS (); + reg.setInputSource (src); + reg.setInputTarget (tgt); + reg.setMaximumIterations (50); + reg.setTransformationEpsilon (1e-8); + + // Register + reg.align (output); + EXPECT_EQ (output.size (), cloud_source.size ()); + EXPECT_LT (reg.getFitnessScore (), 0.0001); + + // Check again, for all possible caching schemes + for (int iter = 0; iter < 4; iter++) + { + bool force_cache = static_cast (iter/2); + bool force_cache_reciprocal = static_cast (iter%2); + pcl::search::KdTree::Ptr tree(new pcl::search::KdTree); + // Ensure that, when force_cache is not set, we are robust to the wrong input + if (force_cache) + tree->setInputCloud (tgt); + reg.setSearchMethodTarget (tree, force_cache); + + pcl::search::KdTree::Ptr tree_recip (new pcl::search::KdTree); + if (force_cache_reciprocal) + tree_recip->setInputCloud (src); + reg.setSearchMethodSource (tree_recip, force_cache_reciprocal); + + // Register + reg.align (output); + EXPECT_EQ (output.size (), cloud_source.size ()); + EXPECT_LT (reg.getFitnessScore (), 0.001); + } + + // Test guess matrix + Eigen::Isometry3f transform = Eigen::Isometry3f (Eigen::AngleAxisf (0.25 * M_PI, Eigen::Vector3f::UnitX ()) + * Eigen::AngleAxisf (0.50 * M_PI, Eigen::Vector3f::UnitY ()) + * Eigen::AngleAxisf (0.33 * M_PI, Eigen::Vector3f::UnitZ ())); + transform.translation () = Eigen::Vector3f (0.1, 0.2, 0.3); + PointCloud::Ptr transformed_tgt (new PointCloud); + pcl::transformPointCloud (*tgt, *transformed_tgt, transform.matrix ()); // transformed_tgt is now a copy of tgt with a transformation matrix applied + + GeneralizedIterativeClosestPoint reg_guess; + reg_guess.useBFGS (); + reg_guess.setInputSource (src); + reg_guess.setInputTarget (transformed_tgt); + reg_guess.setMaximumIterations (50); + reg_guess.setTransformationEpsilon (1e-8); + reg_guess.align (output, transform.matrix ()); + EXPECT_EQ (output.size (), cloud_source.size ()); + EXPECT_LT (reg.getFitnessScore (), 0.0001); +} + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, GeneralizedIterativeClosestPoint6D) { From b9360ef989a41481e20d5677e031244c5a6c24cd Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 25 Oct 2023 14:56:03 +0200 Subject: [PATCH 142/288] GreedyProjectionTriangulation: add hint about PointInT --- surface/include/pcl/surface/gp3.h | 1 + 1 file changed, 1 insertion(+) diff --git a/surface/include/pcl/surface/gp3.h b/surface/include/pcl/surface/gp3.h index 27be42ccacc..e588845e6f8 100644 --- a/surface/include/pcl/surface/gp3.h +++ b/surface/include/pcl/surface/gp3.h @@ -123,6 +123,7 @@ namespace pcl /** \brief GreedyProjectionTriangulation is an implementation of a greedy triangulation algorithm for 3D points * based on local 2D projections. It assumes locally smooth surfaces and relatively smooth transitions between * areas with different point densities. + * \tparam PointInT Point type must have XYZ and normal information, for example `pcl::PointNormal` or `pcl::PointXYZRGBNormal` or `pcl::PointXYZINormal` * \author Zoltan Csaba Marton * \ingroup surface */ From 81b92a50f21b63c8a3bce9c900dfe6d247ee51e4 Mon Sep 17 00:00:00 2001 From: Rasmus Date: Mon, 30 Oct 2023 21:10:52 +0100 Subject: [PATCH 143/288] Fix PCD load crashes on empty files (#5855) * return -1 from PCDReader::readHeader() when input file is completely empty * Return empty string from getFieldsList() if input cloud has no fields * Update io/src/pcd_io.cpp Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> * Update common/include/pcl/common/io.h --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- common/include/pcl/common/io.h | 10 ++++++++-- io/src/pcd_io.cpp | 9 ++++++++- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index f6e846e26c9..984b7306553 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -109,8 +109,14 @@ namespace pcl inline std::string getFieldsList (const pcl::PCLPointCloud2 &cloud) { - return std::accumulate(std::next (cloud.fields.begin ()), cloud.fields.end (), cloud.fields[0].name, - [](const auto& acc, const auto& field) { return acc + " " + field.name; }); + if (cloud.fields.empty()) + { + return ""; + } else + { + return std::accumulate(std::next (cloud.fields.begin ()), cloud.fields.end (), cloud.fields[0].name, + [](const auto& acc, const auto& field) { return acc + " " + field.name; }); + } } /** \brief Obtains the size of a specific field data type in bytes diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 7cd5be9cf15..2a90664c841 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -397,7 +397,14 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c fs.open (file_name.c_str (), std::ios::binary); if (!fs.is_open () || fs.fail ()) { - PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror (errno)); + PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror (errno)); + fs.close (); + return (-1); + } + + if (fs.peek() == std::ifstream::traits_type::eof()) + { + PCL_ERROR ("[pcl::PCDReader::readHeader] File '%s' is empty.\n", file_name.c_str ()); fs.close (); return (-1); } From 508ec6373e0bd10a156df316ed7cf3df766e983b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 7 Nov 2023 20:24:43 +0100 Subject: [PATCH 144/288] CI: update MacOS from 11 to 12 --- .ci/azure-pipelines/azure-pipelines.yaml | 6 +++--- README.md | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index c40dbae510d..1645e5b4028 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -73,9 +73,9 @@ stages: vmImage: '$(VMIMAGE)' strategy: matrix: - Big Sur 11: - VMIMAGE: 'macOS-11' - OSX_VERSION: '11' + Monterey 12: + VMIMAGE: 'macOS-12' + OSX_VERSION: '12' Ventura 13: VMIMAGE: 'macOS-13' OSX_VERSION: '13' diff --git a/README.md b/README.md index 5301c088978..836ca00c1ae 100644 --- a/README.md +++ b/README.md @@ -26,7 +26,7 @@ Continuous integration [ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2023.04%20GCC&label=Ubuntu%2023.04%20GCC [ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86 [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64 -[ci-macos-11]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Big%20Sur%2011&label=macOS%20Big%20Sur%2011 +[ci-macos-12]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Monterey%2012&label=macOS%20Monterey%2012 [ci-macos-13]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Ventura%2013&label=macOS%20Ventura%2013 [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 @@ -35,7 +35,7 @@ Build Platform | Status ------------------------ | ------------------------------------------------------------------------------------------------- | Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
      [![Status][ci-ubuntu-22.04]][ci-latest-build]
      [![Status][ci-ubuntu-23.04]][ci-latest-build] | Windows | [![Status][ci-windows-x86]][ci-latest-build]
      [![Status][ci-windows-x64]][ci-latest-build] | -macOS | [![Status][ci-macos-11]][ci-latest-build]
      [![Status][ci-macos-13]][ci-latest-build] | +macOS | [![Status][ci-macos-12]][ci-latest-build]
      [![Status][ci-macos-13]][ci-latest-build] | Documentation | [![Status][ci-docs]][ci-latest-docs] | Community From 41ff06f97ede61f0d8fbd371405241fca3b329e3 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 5 Nov 2023 18:18:38 +0100 Subject: [PATCH 145/288] VoxelGridOcclusionEstimation: fix behaviour if sensor origin is inside the voxel grid --- .../filters/impl/voxel_grid_occlusion_estimation.hpp | 10 ++++++++-- .../pcl/filters/voxel_grid_occlusion_estimation.h | 10 +++++++++- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp index 5a6d3974014..63fac68a267 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp @@ -62,6 +62,13 @@ pcl::VoxelGridOcclusionEstimation::initializeVoxelGrid () // set the sensor origin and sensor orientation sensor_origin_ = filtered_cloud_.sensor_origin_; sensor_orientation_ = filtered_cloud_.sensor_orientation_; + + Eigen::Vector3i ijk = this->getGridCoordinates(sensor_origin_.x(), sensor_origin_.y(), sensor_origin_.z()); + // first check whether the sensor origin is within the voxel grid bounding box, then whether it is occupied + if((ijk[0]>=min_b_[0] && ijk[1]>=min_b_[1] && ijk[2]>=min_b_[2] && ijk[0]<=max_b_[0] && ijk[1]<=max_b_[1] && ijk[2]<=max_b_[2]) && this->getCentroidIndexAt (ijk) != -1) { + PCL_WARN ("[VoxelGridOcclusionEstimation::initializeVoxelGrid] The voxel containing the sensor origin (%g, %g, %g) is marked as occupied. We will instead assume that it is free, to be able to perform the occlusion estimation.\n", sensor_origin_.x(), sensor_origin_.y(), sensor_origin_.z()); + this->leaf_layout_[((Eigen::Vector4i() << ijk, 0).finished() - min_b_).dot (this->divb_mul_)] = -1; + } } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -233,8 +240,7 @@ pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vect tmin = tzmin; if (tzmax < tmax) tmax = tzmax; - - return tmin; + return std::max(tmin, 0.0f); // We only want to go in "positive" direction here, not in negative. This is relevant if the origin is inside the bounding box } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index ffa585ee614..a55b84b3f30 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -47,7 +47,15 @@ namespace pcl /** \brief VoxelGrid to estimate occluded space in the scene. * The ray traversal algorithm is implemented by the work of * 'John Amanatides and Andrew Woo, A Fast Voxel Traversal Algorithm for Ray Tracing' - * + * Example code: + * \code + * pcl::VoxelGridOcclusionEstimation vg; + * vg.setInputCloud (input_cloud); + * vg.setLeafSize (leaf_x, leaf_y, leaf_z); + * vg.initializeVoxelGrid (); + * std::vector > occluded_voxels; + * vg.occlusionEstimationAll (occluded_voxels); + * \endcode * \author Christian Potthast * \ingroup filters */ From 190ae4120d3a0d1aadc5ca609b5ee6d8a24858b9 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 5 Nov 2023 18:30:13 +0100 Subject: [PATCH 146/288] Fix VoxelGridOcclusionEstimation tool - call Update() on vtk classes, otherwise the shown window is empty - use the filtered cloud instead of whole input cloud, otherwise processing is very slow for larger clouds - use the fixed RenderWindowInteractor --- tools/voxel_grid_occlusion_estimation.cpp | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/tools/voxel_grid_occlusion_estimation.cpp b/tools/voxel_grid_occlusion_estimation.cpp index 897c7f20e1f..b2409585b95 100644 --- a/tools/voxel_grid_occlusion_estimation.cpp +++ b/tools/voxel_grid_occlusion_estimation.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -79,6 +80,7 @@ getCuboid (double minX, double maxX, double minY, double maxY, double minZ, doub { vtkSmartPointer < vtkCubeSource > cube = vtkSmartPointer::New (); cube->SetBounds (minX, maxX, minY, maxY, minZ, maxZ); + cube->Update (); return cube->GetOutput (); } @@ -99,6 +101,7 @@ getVoxelActors (pcl::PointCloud& voxelCenters, treeWireframe->AddInputData (getCuboid (x - s, x + s, y - s, y + s, z - s, z + s)); } + treeWireframe->Update (); vtkSmartPointer < vtkLODActor > treeActor = vtkSmartPointer::New (); @@ -119,6 +122,7 @@ displayBoundingBox (Eigen::Vector3f& min_b, Eigen::Vector3f& max_b, { vtkSmartPointer < vtkAppendPolyData > treeWireframe = vtkSmartPointer::New (); treeWireframe->AddInputData (getCuboid (min_b[0], max_b[0], min_b[1], max_b[1], min_b[2], max_b[2])); + treeWireframe->Update(); vtkSmartPointer < vtkActor > treeActor = vtkSmartPointer::New (); @@ -218,17 +222,19 @@ int main (int argc, char** argv) (*occ_centroids)[i] = point; } + // we use the filtered cloud because it contains exactly one point per occupied voxel (avoids drawing the same voxel box multiple times) + CloudT filtered_cloud = vg.getFilteredPointCloud(); CloudT::Ptr cloud_centroids (new CloudT); - cloud_centroids->width = input_cloud->size (); + cloud_centroids->width = filtered_cloud.size (); cloud_centroids->height = 1; cloud_centroids->is_dense = false; - cloud_centroids->points.resize (input_cloud->size ()); + cloud_centroids->points.resize (filtered_cloud.size ()); - for (std::size_t i = 0; i < input_cloud->size (); ++i) + for (std::size_t i = 0; i < filtered_cloud.size (); ++i) { - float x = (*input_cloud)[i].x; - float y = (*input_cloud)[i].y; - float z = (*input_cloud)[i].z; + float x = filtered_cloud[i].x; + float y = filtered_cloud[i].y; + float z = filtered_cloud[i].z; Eigen::Vector3i c = vg.getGridCoordinates (x, y, z); Eigen::Vector4f xyz = vg.getCentroidCoordinate (c); PointT point; @@ -254,7 +260,7 @@ int main (int argc, char** argv) vtkSmartPointer::New(); renderWindow->AddRenderer (renderer); vtkSmartPointer renderWindowInteractor = - vtkSmartPointer::New(); + vtkSmartPointer::Take (vtkRenderWindowInteractorFixNew ()); renderWindowInteractor->SetRenderWindow (renderWindow); // Add the actors to the renderer, set the background and size From b4c975871267edb4827bd27fbf9a0a59a69d40ae Mon Sep 17 00:00:00 2001 From: Kyle Stewart <65791231+KStew8111@users.noreply.github.com> Date: Mon, 13 Nov 2023 01:49:48 -0700 Subject: [PATCH 147/288] remove deprecated code for 1.14 release (#5872) * remove deprecated code for 1.14 release * remove function definitions --- gpu/octree/include/pcl/gpu/octree/octree.hpp | 7 --- gpu/octree/src/octree.cpp | 6 --- .../segmentation/extract_labeled_clusters.h | 45 ------------------- .../impl/extract_labeled_clusters.hpp | 28 ------------ segmentation/src/extract_clusters.cpp | 1 - surface/include/pcl/surface/ear_clipping.h | 25 ----------- 6 files changed, 112 deletions(-) diff --git a/gpu/octree/include/pcl/gpu/octree/octree.hpp b/gpu/octree/include/pcl/gpu/octree/octree.hpp index 015f9ff95a4..5e222a5c38c 100644 --- a/gpu/octree/include/pcl/gpu/octree/octree.hpp +++ b/gpu/octree/include/pcl/gpu/octree/octree.hpp @@ -142,13 +142,6 @@ namespace pcl */ void radiusSearch(const Queries& centers, const Indices& indices, float radius, int max_results, NeighborIndices& result) const; - /** \brief Batch approximate nearest search on GPU - * \param[in] queries array of centers - * \param[out] result array of results ( one index for each query ) - */ - PCL_DEPRECATED(1, 14, "use approxNearestSearch() which returns square distances instead") - void approxNearestSearch(const Queries& queries, NeighborIndices& result) const; - /** \brief Batch approximate nearest search on GPU * \param[in] queries array of centers * \param[out] result array of results ( one index for each query ) diff --git a/gpu/octree/src/octree.cpp b/gpu/octree/src/octree.cpp index 4537179fbd4..63a7e738360 100644 --- a/gpu/octree/src/octree.cpp +++ b/gpu/octree/src/octree.cpp @@ -168,12 +168,6 @@ void pcl::gpu::Octree::radiusSearch(const Queries& queries, const Indices& indic static_cast(impl)->radiusSearch(q, indices, radius, results); } -void pcl::gpu::Octree::approxNearestSearch(const Queries& queries, NeighborIndices& results) const -{ - ResultSqrDists sqr_distance; - approxNearestSearch(queries, results, sqr_distance); -} - void pcl::gpu::Octree::approxNearestSearch(const Queries& queries, NeighborIndices& results, ResultSqrDists& sqr_distance) const { assert(queries.size() > 0); diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index d65beacad7d..fddf4d8d56d 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -40,33 +40,6 @@ namespace pcl { ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -/** \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) - * \param[in] max_pts_per_cluster maximum number of points that a cluster may contain - * (default: max int) - * \param[in] max_label - * \ingroup segmentation - */ -template -PCL_DEPRECATED(1, 14, "Use of max_label is deprecated") -void extractLabeledEuclideanClusters( - const PointCloud& cloud, - const typename search::Search::Ptr& tree, - float tolerance, - std::vector>& labeled_clusters, - unsigned int min_pts_per_cluster, - unsigned int max_pts_per_cluster, - 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 @@ -190,24 +163,6 @@ class LabeledEuclideanClusterExtraction : public PCLBase { return (max_pts_per_cluster_); } - /** \brief Set the maximum number of labels in the cloud. - * \param[in] max_label the maximum - */ - PCL_DEPRECATED(1, 14, "Max label is being deprecated") - inline void - setMaxLabels(unsigned int max_label) - { - max_label_ = max_label; - } - - /** \brief Get the maximum number of labels */ - PCL_DEPRECATED(1, 14, "Max label is being deprecated") - inline unsigned int - getMaxLabels() const - { - return (max_label_); - } - /** \brief Cluster extraction in a PointCloud given by \param[out] labeled_clusters the resultant point clusters */ diff --git a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp index 17463b778e0..1f6ea1d88d1 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp @@ -40,25 +40,6 @@ #include ////////////////////////////////////////////////////////////////////////////////////////////// -template -void -pcl::extractLabeledEuclideanClusters( - const PointCloud& cloud, - const typename search::Search::Ptr& tree, - float tolerance, - std::vector>& labeled_clusters, - unsigned int min_pts_per_cluster, - unsigned int max_pts_per_cluster, - unsigned int) -{ - pcl::extractLabeledEuclideanClusters(cloud, - tree, - tolerance, - labeled_clusters, - min_pts_per_cluster, - max_pts_per_cluster); -} - template void pcl::extractLabeledEuclideanClusters( @@ -179,15 +160,6 @@ pcl::LabeledEuclideanClusterExtraction::extract( #define PCL_INSTANTIATE_LabeledEuclideanClusterExtraction(T) \ template class PCL_EXPORTS pcl::LabeledEuclideanClusterExtraction; -#define PCL_INSTANTIATE_extractLabeledEuclideanClusters_deprecated(T) \ - template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters( \ - const pcl::PointCloud&, \ - const typename pcl::search::Search::Ptr&, \ - float, \ - std::vector>&, \ - unsigned int, \ - unsigned int, \ - unsigned int); #define PCL_INSTANTIATE_extractLabeledEuclideanClusters(T) \ template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters( \ const pcl::PointCloud&, \ diff --git a/segmentation/src/extract_clusters.cpp b/segmentation/src/extract_clusters.cpp index 85560542911..21bef031846 100644 --- a/segmentation/src/extract_clusters.cpp +++ b/segmentation/src/extract_clusters.cpp @@ -56,6 +56,5 @@ PCL_INSTANTIATE(extractEuclideanClusters, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(extractEuclideanClusters_indices, PCL_XYZ_POINT_TYPES) #endif PCL_INSTANTIATE(LabeledEuclideanClusterExtraction, PCL_XYZL_POINT_TYPES) -PCL_INSTANTIATE(extractLabeledEuclideanClusters_deprecated, PCL_XYZL_POINT_TYPES) PCL_INSTANTIATE(extractLabeledEuclideanClusters, PCL_XYZL_POINT_TYPES) diff --git a/surface/include/pcl/surface/ear_clipping.h b/surface/include/pcl/surface/ear_clipping.h index e2d1b920332..0f6530e9140 100644 --- a/surface/include/pcl/surface/ear_clipping.h +++ b/surface/include/pcl/surface/ear_clipping.h @@ -87,17 +87,6 @@ namespace pcl float area (const Indices& vertices); - /** \brief Compute the signed area of a polygon. - * \param[in] vertices the vertices representing the polygon - */ - template ::value, pcl::index_t> = 0> - PCL_DEPRECATED(1, 14, "This method creates a useless copy of the vertices vector. Use area method which accepts Indices instead") - float - area (const std::vector& vertices) - { - return area(Indices (vertices.cbegin(), vertices.cend())); - } - /** \brief Check if the triangle (u,v,w) is an ear. * \param[in] u the first triangle vertex * \param[in] v the second triangle vertex @@ -107,20 +96,6 @@ namespace pcl bool isEar (int u, int v, int w, const Indices& vertices); - /** \brief Check if the triangle (u,v,w) is an ear. - * \param[in] u the first triangle vertex - * \param[in] v the second triangle vertex - * \param[in] w the third triangle vertex - * \param[in] vertices a set of input vertices - */ - template ::value, pcl::index_t> = 0> - PCL_DEPRECATED(1, 14, "This method creates a useless copy of the vertices vector. Use isEar method which accepts Indices instead") - bool - isEar (int u, int v, int w, const std::vector& vertices) - { - return isEar(u, v, w, Indices (vertices.cbegin(), vertices.cend())); - } - /** \brief Check if p is inside the triangle (u,v,w). * \param[in] u the first triangle vertex * \param[in] v the second triangle vertex From 60549ec9b077642ce6c2e26c0ffcfdf4143304bf Mon Sep 17 00:00:00 2001 From: zhulingfeng <664675691@qq.com> Date: Tue, 14 Nov 2023 07:40:28 +0800 Subject: [PATCH 148/288] [surface] Speed up nurbs surface fitting Use Eigen function completeOrthogonalDecomposition instead of jacobiSvd to solve linear least squares systems to speed up nurbs surface fitting, see https://eigen.tuxfamily.org/dox/group__LeastSquares.html for details. By the way, it may fix segmemt fault on some machines caused by jacobiSvd call. --- surface/src/on_nurbs/nurbs_solve_eigen.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/surface/src/on_nurbs/nurbs_solve_eigen.cpp b/surface/src/on_nurbs/nurbs_solve_eigen.cpp index 0c28bf60fcb..9ed63491673 100644 --- a/surface/src/on_nurbs/nurbs_solve_eigen.cpp +++ b/surface/src/on_nurbs/nurbs_solve_eigen.cpp @@ -136,7 +136,7 @@ NurbsSolve::solve () { // m_xeig = m_Keig.colPivHouseholderQr().solve(m_feig); // Eigen::MatrixXd x = A.householderQr().solve(b); - m_xeig = m_Keig.jacobiSvd (Eigen::ComputeThinU | Eigen::ComputeThinV).solve (m_feig); + m_xeig = m_Keig.completeOrthogonalDecomposition().solve (m_feig); return true; } From a2e6f5458296068d431b9e70c88955c6b832e71a Mon Sep 17 00:00:00 2001 From: Sun-lay Gagneux Date: Tue, 14 Nov 2023 06:34:43 -0500 Subject: [PATCH 149/288] Fix freeze in hdl_grabber.cpp (#5826) * Fix freeze in hdl_grabber.cpp Close the udp socket before stopping HDLGrabber. Tested only on Windows. * Fix freeze in hdl_grabber.cpp Address PR comments to fix HDLGrabber freeze on Windows and Linux. --------- Co-authored-by: SunlayGGX --- io/src/hdl_grabber.cpp | 31 +++++++++++++++++++++++++++---- 1 file changed, 27 insertions(+), 4 deletions(-) diff --git a/io/src/hdl_grabber.cpp b/io/src/hdl_grabber.cpp index 72dd213598a..c54f68edf37 100644 --- a/io/src/hdl_grabber.cpp +++ b/io/src/hdl_grabber.cpp @@ -536,6 +536,20 @@ pcl::HDLGrabber::stop () terminate_read_packet_thread_ = true; hdl_data_.stopQueue (); + if (hdl_read_socket_ != nullptr) + { + try + { + hdl_read_socket_->shutdown (boost::asio::ip::tcp::socket::shutdown_both); + } + catch (const boost::system::system_error& e) + { + PCL_ERROR("[pcl::HDLGrabber::stop] Failed to shutdown the socket. %s\n", e.what ()); + } + + hdl_read_socket_->close (); + } + if (hdl_read_packet_thread_ != nullptr) { hdl_read_packet_thread_->join (); @@ -645,12 +659,21 @@ pcl::HDLGrabber::readPacketsFromSocket () while (!terminate_read_packet_thread_ && hdl_read_socket_->is_open ()) { - std::size_t length = hdl_read_socket_->receive_from (boost::asio::buffer (data, 1500), sender_endpoint); + try + { + std::size_t length = hdl_read_socket_->receive_from (boost::asio::buffer (data, 1500), sender_endpoint); - if (isAddressUnspecified (source_address_filter_) - || (source_address_filter_ == sender_endpoint.address () && source_port_filter_ == sender_endpoint.port ())) + if (isAddressUnspecified (source_address_filter_) + || (source_address_filter_ == sender_endpoint.address () && source_port_filter_ == sender_endpoint.port ())) + { + enqueueHDLPacket (data, length); + } + } + catch (const boost::system::system_error& e) { - enqueueHDLPacket (data, length); + // We must ignore those errors triggered on socket close/shutdown request. + if (!(e.code () == boost::asio::error::interrupted || e.code () == boost::asio::error::operation_aborted)) + throw; } } } From c37d57804c9de6426b96760b8db4968fe7783fd1 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 18 Nov 2023 14:34:22 +0100 Subject: [PATCH 150/288] Add readthedocs config files Readthedocs now requires special config files: https://blog.readthedocs.com/migrate-configuration-v2/ The builds on rtd have been failing since end of September because we do not have them yet. Also add a rtd batch in our main README so we notice failing builds sooner. --- README.md | 1 + doc/advanced/.readthedocs.yaml | 22 ++++++++++++++++++++++ doc/tutorials/.readthedocs.yaml | 22 ++++++++++++++++++++++ 3 files changed, 45 insertions(+) create mode 100644 doc/advanced/.readthedocs.yaml create mode 100644 doc/tutorials/.readthedocs.yaml diff --git a/README.md b/README.md index 836ca00c1ae..75482dc411a 100644 --- a/README.md +++ b/README.md @@ -37,6 +37,7 @@ Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
      [! Windows | [![Status][ci-windows-x86]][ci-latest-build]
      [![Status][ci-windows-x64]][ci-latest-build] | macOS | [![Status][ci-macos-12]][ci-latest-build]
      [![Status][ci-macos-13]][ci-latest-build] | Documentation | [![Status][ci-docs]][ci-latest-docs] | +Read the Docs | [![Documentation Status](https://readthedocs.org/projects/pcl-tutorials/badge/?version=master)](https://pcl.readthedocs.io/projects/tutorials/en/master/?badge=master) | Community --------- diff --git a/doc/advanced/.readthedocs.yaml b/doc/advanced/.readthedocs.yaml new file mode 100644 index 00000000000..c8d6adf3b64 --- /dev/null +++ b/doc/advanced/.readthedocs.yaml @@ -0,0 +1,22 @@ +# .readthedocs.yaml +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +# Required +version: 2 + +build: + os: ubuntu-22.04 + tools: + python: "3.11" + +sphinx: + configuration: doc/advanced/content/conf.py + +formats: + - epub + - pdf + +python: + install: + - requirements: doc/requirements.txt diff --git a/doc/tutorials/.readthedocs.yaml b/doc/tutorials/.readthedocs.yaml new file mode 100644 index 00000000000..e0ee8c8a34d --- /dev/null +++ b/doc/tutorials/.readthedocs.yaml @@ -0,0 +1,22 @@ +# .readthedocs.yaml +# Read the Docs configuration file +# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details + +# Required +version: 2 + +build: + os: ubuntu-22.04 + tools: + python: "3.11" + +sphinx: + configuration: doc/tutorials/content/conf.py + +formats: + - epub + - pdf + +python: + install: + - requirements: doc/requirements.txt From f06d1fb3b4d4c90c67ce49a1c93cc00898bcef4d Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 20 Nov 2023 13:32:02 +0100 Subject: [PATCH 151/288] Add sphinx-rtd-theme in doc requirements Currently, readthedocs is failing with the error: no theme named 'sphinx_rtd_theme' found (missing theme.conf?) --- doc/requirements.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/requirements.txt b/doc/requirements.txt index bf23e751b29..d8fb1391eff 100644 --- a/doc/requirements.txt +++ b/doc/requirements.txt @@ -1,2 +1,3 @@ sphinx>=3 sphinxcontrib-doxylink +sphinx-rtd-theme From 50c406455a72492dc6e53a8d488cdc12a8e7a602 Mon Sep 17 00:00:00 2001 From: Bhavesh Misra Date: Sat, 25 Nov 2023 17:30:25 +0530 Subject: [PATCH 152/288] Issue 4718 (#5851) * Initial_Commit_Creating_Benchmark_from_test * Changes * Changes_2 * Deleted_vscode * Ran_make_format * Ran_make_format * Pushing_changed_file_name * Deleted_format * Ran_make_format * Updated clang_format_14, and unmade_the_changes * Using_the_chrono_now_way * Ran_format.sh --------- Co-authored-by: Bhavesh Misra --- benchmarks/CMakeLists.txt | 5 ++ benchmarks/search/radius_search.cpp | 62 +++++++++++++++++++++++ test/search/test_organized_index.cpp | 75 ---------------------------- 3 files changed, 67 insertions(+), 75 deletions(-) create mode 100644 benchmarks/search/radius_search.cpp diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index b85bc0354ca..95f421db5f6 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -25,3 +25,8 @@ PCL_ADD_BENCHMARK(filters_voxel_grid FILES filters/voxel_grid.cpp ARGUMENTS "${PCL_SOURCE_DIR}/test/table_scene_mug_stereo_textured.pcd" "${PCL_SOURCE_DIR}/test/milk_cartoon_all_small_clorox.pcd") +PCL_ADD_BENCHMARK(search_radius_search FILES search/radius_search.cpp + LINK_WITH pcl_io pcl_search + ARGUMENTS "${PCL_SOURCE_DIR}/test/table_scene_mug_stereo_textured.pcd" + "${PCL_SOURCE_DIR}/test/milk_cartoon_all_small_clorox.pcd") + diff --git a/benchmarks/search/radius_search.cpp b/benchmarks/search/radius_search.cpp new file mode 100644 index 00000000000..9641375bed3 --- /dev/null +++ b/benchmarks/search/radius_search.cpp @@ -0,0 +1,62 @@ +#include +#include +#include +#include + +#include + +#include + +static void +BM_OrganizedNeighborSearch(benchmark::State& state, const std::string& file) +{ + pcl::PointCloud::Ptr cloudIn(new pcl::PointCloud); + pcl::PCDReader reader; + reader.read(file, *cloudIn); + + pcl::search::OrganizedNeighbor organizedNeighborSearch; + organizedNeighborSearch.setInputCloud(cloudIn); + + double radiusSearchTime = 0; + std::vector indices(cloudIn->size()); // Fixed indices from 0 to cloud size + std::iota(indices.begin(), indices.end(), 0); + int radiusSearchIdx = 0; + + for (auto _ : state) { + int searchIdx = indices[radiusSearchIdx++ % indices.size()]; + double searchRadius = 0.1; // or any fixed radius like 0.05 + + std::vector k_indices; + std::vector k_sqr_distances; + + auto start_time = std::chrono::high_resolution_clock::now(); + organizedNeighborSearch.radiusSearch( + (*cloudIn)[searchIdx], searchRadius, k_indices, k_sqr_distances); + auto end_time = std::chrono::high_resolution_clock::now(); + + radiusSearchTime += + std::chrono::duration_cast(end_time - start_time) + .count(); + } + + state.SetItemsProcessed(state.iterations()); + state.SetIterationTime( + radiusSearchTime / + (state.iterations() * indices.size())); // Normalize by total points processed +} + +int +main(int argc, char** argv) +{ + if (argc < 2) { + std::cerr << "No test file given. Please provide a PCD file for the benchmark." + << std::endl; + return -1; + } + + benchmark::RegisterBenchmark( + "BM_OrganizedNeighborSearch", &BM_OrganizedNeighborSearch, argv[1]) + ->Unit(benchmark::kMillisecond); + benchmark::Initialize(&argc, argv); + benchmark::RunSpecifiedBenchmarks(); +} diff --git a/test/search/test_organized_index.cpp b/test/search/test_organized_index.cpp index 582099e7bc5..6b63d00d204 100644 --- a/test/search/test_organized_index.cpp +++ b/test/search/test_organized_index.cpp @@ -340,81 +340,6 @@ 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; - const unsigned int seed = time (nullptr); - srand (seed); - - search::OrganizedNeighbor organizedNeighborSearch; - - std::vector k_indices; - std::vector k_sqr_distances; - - std::vector k_indices_bruteforce; - std::vector k_sqr_distances_bruteforce; - - // typical focal length from kinect - constexpr double oneOverFocalLength = 0.0018; - - for (unsigned int test_id = 0; test_id < test_runs; test_id++) - { - // generate point cloud - - PointCloud::Ptr cloudIn (new PointCloud ()); - - cloudIn->width = 1024; - cloudIn->height = 768; - cloudIn->points.clear(); - cloudIn->points.resize (cloudIn->width * cloudIn->height); - - int centerX = cloudIn->width >> 1; - int centerY = cloudIn->height >> 1; - - int idx = 0; - for (int ypos = -centerY; ypos < centerY; ypos++) - for (int xpos = -centerX; xpos < centerX; xpos++) - { - double z = 5.0 * ( (static_cast(rand ()) / static_cast(RAND_MAX)))+5; - double y = ypos*oneOverFocalLength*z; - double x = xpos*oneOverFocalLength*z; - - (*cloudIn)[idx++]= PointXYZ (x, y, z); - } - - const unsigned int randomIdx = rand() % (cloudIn->width * cloudIn->height); - - const PointXYZ& searchPoint = (*cloudIn)[randomIdx]; - - const double searchRadius = 1.0 * (static_cast(rand ()) / static_cast(RAND_MAX)); - - // bruteforce radius search - std::vector cloudSearchBruteforce; - cloudSearchBruteforce.clear(); - - for (auto it = cloudIn->points.cbegin(); it != cloudIn->points.cend(); ++it) - { - const auto pointDist = pcl_tests::point_distance(*it, searchPoint); - - if (pointDist <= searchRadius) - { - // add point candidates to vector list - cloudSearchBruteforce.push_back (std::distance(cloudIn->points.cbegin(), it)); - } - } - - pcl::Indices cloudNWRSearch; - std::vector cloudNWRRadius; - - organizedNeighborSearch.setInputCloud (cloudIn); - organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits::max()); - - organizedNeighborSearch.setInputCloud (cloudIn); - organizedNeighborSearch.radiusSearch ((*cloudIn)[randomIdx], searchRadius, cloudNWRSearch, cloudNWRRadius, std::numeric_limits::max()); - } -} - TEST (PCL, Organized_Neighbor_Search_Pointcloud_Neighbours_Within_Radius_Search_Kinect_Data) { From c9b83fb277500121bed10f3f38c7342d02292f6c Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:05:28 +0530 Subject: [PATCH 153/288] Checked PCL_MAKE_ALIGNED_OPERATOR_NEW; --- apps/include/pcl/apps/manual_registration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/include/pcl/apps/manual_registration.h b/apps/include/pcl/apps/manual_registration.h index d8421e32bbc..2a2d22fc5fb 100644 --- a/apps/include/pcl/apps/manual_registration.h +++ b/apps/include/pcl/apps/manual_registration.h @@ -59,7 +59,7 @@ class ManualRegistration : public QMainWindow { using CloudPtr = Cloud::Ptr; using CloudConstPtr = Cloud::ConstPtr; - PCL_MAKE_ALIGNED_OPERATOR_NEW; + PCL_MAKE_ALIGNED_OPERATOR_NEW ManualRegistration(float voxel_size); From 78f6882b6e970770d9877b6739410b6a487dbc4a Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:06:58 +0530 Subject: [PATCH 154/288] Checked PCL_ADD_RGB; --- common/include/pcl/impl/point_types.hpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 793c5c53ce5..fa7ce8d882a 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -365,7 +365,7 @@ namespace pcl #endif struct _RGB { - PCL_ADD_RGB; + PCL_ADD_RGB }; PCL_EXPORTS std::ostream& operator << (std::ostream& os, const RGB& p); @@ -528,7 +528,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGBA { PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_RGB; + PCL_ADD_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -575,14 +575,14 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGB { PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_RGB; + PCL_ADD_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; struct EIGEN_ALIGN16 _PointXYZRGBL { PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_RGB; + PCL_ADD_RGB std::uint32_t label; PCL_MAKE_ALIGNED_OPERATOR_NEW }; From 47c0e68ea11c6e1ac68d218954db2fa8cb24d9d7 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:08:56 +0530 Subject: [PATCH 155/288] Checked PCL_ADD_POINT4D; --- common/include/pcl/impl/point_types.hpp | 36 +++++++++---------- .../include/pcl/tracking/impl/tracking.hpp | 10 +++--- 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index fa7ce8d882a..5f7bbed52af 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -338,7 +338,7 @@ namespace pcl struct _PointXYZ { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -469,7 +469,7 @@ namespace pcl */ struct EIGEN_ALIGN16 _PointXYZI { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { struct @@ -496,7 +496,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZL { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) std::uint32_t label; PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -527,7 +527,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGBA { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -574,14 +574,14 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGB { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; struct EIGEN_ALIGN16 _PointXYZRGBL { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_RGB std::uint32_t label; PCL_MAKE_ALIGNED_OPERATOR_NEW @@ -666,7 +666,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZLAB { - PCL_ADD_POINT4D; // this adds the members x,y,z + PCL_ADD_POINT4D // this adds the members x,y,z union { struct @@ -701,7 +701,7 @@ namespace pcl 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]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { struct @@ -787,7 +787,7 @@ namespace pcl // @TODO: inheritance trick like on other PointTypes struct EIGEN_ALIGN16 InterestPoint { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { struct @@ -858,7 +858,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointNormal { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { @@ -893,7 +893,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGBNormal { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { @@ -979,7 +979,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZINormal { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { @@ -1022,7 +1022,7 @@ namespace pcl //---- struct EIGEN_ALIGN16 _PointXYZLNormal { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { @@ -1067,7 +1067,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointWithRange { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { struct @@ -1098,7 +1098,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointWithViewpoint { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { struct @@ -1633,7 +1633,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointWithScale { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) union { @@ -1673,7 +1673,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointSurfel { - PCL_ADD_POINT4D; // This adds the members x,y,z which can also be accessed using the point (which is float[4]) + PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { @@ -1717,7 +1717,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointDEM { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D float intensity; float intensity_variance; float height_variance; diff --git a/tracking/include/pcl/tracking/impl/tracking.hpp b/tracking/include/pcl/tracking/impl/tracking.hpp index 1c5a2a73736..91c29e8c473 100644 --- a/tracking/include/pcl/tracking/impl/tracking.hpp +++ b/tracking/include/pcl/tracking/impl/tracking.hpp @@ -9,7 +9,7 @@ namespace pcl { namespace tracking { struct _ParticleXYZRPY { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D union { struct { float roll; @@ -236,7 +236,7 @@ operator-(const ParticleXYZRPY& a, const ParticleXYZRPY& b) namespace pcl { namespace tracking { struct _ParticleXYZR { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D union { struct { float roll; @@ -420,7 +420,7 @@ operator-(const ParticleXYZR& a, const ParticleXYZR& b) namespace pcl { namespace tracking { struct _ParticleXYRPY { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D union { struct { float roll; @@ -610,7 +610,7 @@ operator-(const ParticleXYRPY& a, const ParticleXYRPY& b) namespace pcl { namespace tracking { struct _ParticleXYRP { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D union { struct { float roll; @@ -797,7 +797,7 @@ operator-(const ParticleXYRP& a, const ParticleXYRP& b) namespace pcl { namespace tracking { struct _ParticleXYR { - PCL_ADD_POINT4D; + PCL_ADD_POINT4D union { struct { float roll; From da64870d53df5afd27e532f7e17f25291d121897 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:10:25 +0530 Subject: [PATCH 156/288] Checked PCL_ADD_INTENSITY; --- common/include/pcl/impl/point_types.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 5f7bbed52af..9b0fdccbd73 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -401,7 +401,7 @@ namespace pcl struct _Intensity { - PCL_ADD_INTENSITY; + PCL_ADD_INTENSITY }; PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Intensity& p); From 60787ba7133c4cf648b176a4cea0b5d055634088 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:11:24 +0530 Subject: [PATCH 157/288] Checked PCL_ADD_NORMAL4D; --- common/include/pcl/impl/point_types.hpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 9b0fdccbd73..94eeccff5ba 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -803,7 +803,7 @@ namespace pcl struct EIGEN_ALIGN16 _Normal { - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct @@ -835,7 +835,7 @@ namespace pcl struct EIGEN_ALIGN16 _Axis { - PCL_ADD_NORMAL4D; + PCL_ADD_NORMAL4D PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -859,7 +859,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointNormal { PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct @@ -894,7 +894,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZRGBNormal { PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct @@ -980,7 +980,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZINormal { PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct @@ -1023,7 +1023,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointXYZLNormal { PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct @@ -1674,7 +1674,7 @@ namespace pcl struct EIGEN_ALIGN16 _PointSurfel { PCL_ADD_POINT4D // This adds the members x,y,z which can also be accessed using the point (which is float[4]) - PCL_ADD_NORMAL4D; // This adds the member normal[3] which can also be accessed using the point (which is float[4]) + PCL_ADD_NORMAL4D // This adds the member normal[3] which can also be accessed using the point (which is float[4]) union { struct From 49ec50247cc5e0bafbbebf3c992a6e4fd2a77c17 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:11:59 +0530 Subject: [PATCH 158/288] Checked PCL_ADD_EIGEN_MAPS_RGB; --- common/include/pcl/impl/point_types.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 94eeccff5ba..103f1a94a90 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -904,7 +904,7 @@ namespace pcl }; float data_c[4]; }; - PCL_ADD_EIGEN_MAPS_RGB; + PCL_ADD_EIGEN_MAPS_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; @@ -1686,7 +1686,7 @@ namespace pcl }; float data_c[4]; }; - PCL_ADD_EIGEN_MAPS_RGB; + PCL_ADD_EIGEN_MAPS_RGB PCL_MAKE_ALIGNED_OPERATOR_NEW }; From afda84ea2b9b4ce64dec33a9e8220a2d41352570 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Sun, 26 Nov 2023 04:13:58 +0530 Subject: [PATCH 159/288] Ran format.sh --- common/include/pcl/impl/point_types.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 103f1a94a90..8695670849a 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -1616,7 +1616,6 @@ namespace pcl inline constexpr IntensityGradient (): IntensityGradient (0.f, 0.f, 0.f) {} inline constexpr IntensityGradient (float _x, float _y, float _z): gradient_x (_x), gradient_y (_y), gradient_z (_z) {} - friend std::ostream& operator << (std::ostream& os, const IntensityGradient& p); }; From 90e8bace2221c087711e93a54429bd1d8cb43332 Mon Sep 17 00:00:00 2001 From: Zekrom_7780 Date: Mon, 27 Nov 2023 00:39:10 +0530 Subject: [PATCH 160/288] Changed PCL_ADD_UNION_RGB; --- common/include/pcl/impl/point_types.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 8695670849a..cb08b4deb25 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -899,7 +899,7 @@ namespace pcl { struct { - PCL_ADD_UNION_RGB; + PCL_ADD_UNION_RGB float curvature; }; float data_c[4]; @@ -1678,7 +1678,7 @@ namespace pcl { struct { - PCL_ADD_UNION_RGB; + PCL_ADD_UNION_RGB float radius; float confidence; float curvature; From 2938ed027b33133c22e38427592590e343ff0556 Mon Sep 17 00:00:00 2001 From: Bhavesh Misra Date: Tue, 28 Nov 2023 20:38:29 +0530 Subject: [PATCH 161/288] Issue documentation change (#5889) * Made_Changes * Made_Changes * Ran format.sh * Reset the changes * Added filter.set_negative * Final_Changes_made * Added_the_Changes --- filters/include/pcl/filters/model_outlier_removal.h | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/filters/include/pcl/filters/model_outlier_removal.h b/filters/include/pcl/filters/model_outlier_removal.h index 73963449d6e..8fbe3dce188 100644 --- a/filters/include/pcl/filters/model_outlier_removal.h +++ b/filters/include/pcl/filters/model_outlier_removal.h @@ -48,20 +48,24 @@ namespace pcl { /** \brief @b ModelOutlierRemoval filters points in a cloud based on the distance between model and point. * \details Iterates through the entire input once, automatically filtering non-finite points and the points outside - * the model specified by setSampleConsensusModelPointer() and the threshold specified by setThreholdFunctionPointer(). *

      * Usage example: * \code + * * pcl::ModelCoefficients model_coeff; * model_coeff.values.resize(4); - * model_coeff.values[0] = 0; model_coeff.values[1] = 0; model_coeff.values[2] = 1.5; model_coeff.values[3] = 0.5; + * model_coeff.values[0] = 0; + * model_coeff.values[1] = 0; + * model_coeff.values[2] = 1; + * model_coeff.values[3] = 0.5; * pcl::ModelOutlierRemoval filter; * filter.setModelCoefficients (model_coeff); * filter.setThreshold (0.1); * filter.setModelType (pcl::SACMODEL_PLANE); * filter.setInputCloud (*cloud_in); - * filter.setFilterLimitsNegative (false); + * filter.setNegative (false); * filter.filter (*cloud_out); + * \endcode */ template From 29a33b69f8a812b33c62578803ce5785545fb651 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 28 Nov 2023 17:14:41 +0100 Subject: [PATCH 162/288] Update windows docker to .net 4.8 and ltsc2022 (#5801) Update windows docker to .net 4.8 and ltsc2022 --- .ci/azure-pipelines/azure-pipelines.yaml | 2 +- .ci/azure-pipelines/env.yml | 10 +++++----- .dev/docker/windows/Dockerfile | 7 ++++--- 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 1645e5b4028..598bafb14fd 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -143,7 +143,7 @@ stages: - job: Windows displayName: Windows Build pool: - vmImage: 'windows-2019' + vmImage: 'windows-2022' strategy: matrix: x86: diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index eed0902a185..a6559a22301 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -107,17 +107,17 @@ jobs: timeoutInMinutes: 360 displayName: "Env" pool: - vmImage: 'windows-2019' + vmImage: 'windows-2022' strategy: matrix: Winx86: PLATFORM: x86 - TAG: winx86 + TAG: windows2022-x86 GENERATOR: "'Visual Studio 16 2019' -A Win32" - VCPKGCOMMIT: fd766eba2b4cf59c7123d46189be373e2cee959d + VCPKGCOMMIT: 8eb57355a4ffb410a2e94c07b4dca2dffbee8e50 Winx64: PLATFORM: x64 - TAG: winx64 + TAG: windows2022-x64 GENERATOR: "'Visual Studio 16 2019' -A x64" VCPKGCOMMIT: master steps: @@ -132,7 +132,7 @@ jobs: -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; diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index f8be7aaa059..ae6fc94be86 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -1,6 +1,6 @@ # escape=` -FROM mcr.microsoft.com/windows/servercore:ltsc2019 +FROM mcr.microsoft.com/windows/servercore:ltsc2022 # Use "--build-arg platform=x64" for 64 bit or x86 for 32 bit. ARG PLATFORM @@ -30,7 +30,7 @@ RUN wget $Env:CHANNEL_BASE_URL/vs_buildtools.exe -OutFile 'C:\TEMP\vs_buildtools "C:\TEMP\VisualStudio.chman", ` "--add", ` "Microsoft.VisualStudio.Workload.VCTools", ` - "Microsoft.Net.Component.4.7.2.SDK", ` + "Microsoft.Net.Component.4.8.SDK", ` "Microsoft.VisualStudio.Component.VC.ATLMFC", ` "--includeRecommended" ` -Wait -PassThru; ` @@ -48,4 +48,5 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm RUN cd .\vcpkg; ` .\bootstrap-vcpkg.bat; ` - .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build; + .\vcpkg install boost flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; ` + From c5f24cdb7bfacfc61a073fd1e229e17b6347dff1 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 29 Nov 2023 07:33:07 +0100 Subject: [PATCH 163/288] Use new images. --- .ci/azure-pipelines/azure-pipelines.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 598bafb14fd..bc6d7501820 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -17,9 +17,9 @@ pr: resources: containers: - container: winx86 - image: pointcloudlibrary/env:winx86 + image: pointcloudlibrary/env:windows2022-x86 - container: winx64 - image: pointcloudlibrary/env:winx64 + image: pointcloudlibrary/env:windows2022-x64 - container: env2004 image: pointcloudlibrary/env:20.04 - container: env2204 From e2656ed9ab65cb7b19950799be73c81249e3b75c Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Sat, 2 Dec 2023 01:02:15 -0800 Subject: [PATCH 164/288] Part G of transition to support modernize-use-default-member-init (#5860) * Part G of transition to support modernize-use-default-member-init * Fixed clang-tidy, clang-format CI issues * Made changes per inspection * Made changes per review * Made more changes per review * Addressed review comments * Addressed CI errors, omitted review comments * Addressed more build errors * Addressed additional review comment --- .../include/pcl/registration/impl/ndt.hpp | 2 +- ...oximate_progressive_morphological_filter.h | 16 ++--- .../conditional_euclidean_clustering.h | 15 ++--- .../pcl/segmentation/cpc_segmentation.h | 14 ++-- .../pcl/segmentation/extract_clusters.h | 14 ++-- .../segmentation/extract_labeled_clusters.h | 17 ++--- .../extract_polygonal_prism_data.h | 16 ++--- .../pcl/segmentation/grabcut_segmentation.h | 39 +++++------ ...imate_progressive_morphological_filter.hpp | 12 +--- .../segmentation/impl/cpc_segmentation.hpp | 10 +-- .../segmentation/impl/lccp_segmentation.hpp | 14 +--- .../impl/min_cut_segmentation.hpp | 21 +----- .../impl/progressive_morphological_filter.hpp | 11 +--- .../pcl/segmentation/impl/region_growing.hpp | 21 +----- .../segmentation/impl/region_growing_rgb.hpp | 4 -- .../impl/supervoxel_clustering.hpp | 19 +++--- .../segmentation/impl/unary_classifier.hpp | 9 +-- .../pcl/segmentation/lccp_segmentation.h | 33 +++++----- .../pcl/segmentation/min_cut_segmentation.h | 40 ++++++------ .../organized_multi_plane_segmentation.h | 27 +++----- .../progressive_morphological_filter.h | 14 ++-- .../include/pcl/segmentation/region_growing.h | 34 +++++----- .../pcl/segmentation/region_growing_rgb.h | 8 +-- .../pcl/segmentation/sac_segmentation.h | 65 +++++++------------ .../segmentation/seeded_hue_segmentation.h | 9 ++- .../pcl/segmentation/segment_differences.h | 10 ++- .../pcl/segmentation/supervoxel_clustering.h | 18 +++-- .../pcl/segmentation/unary_classifier.h | 14 ++-- segmentation/src/grabcut_segmentation.cpp | 1 - .../pcl/stereo/digital_elevation_map.h | 6 +- .../pcl/stereo/disparity_map_converter.h | 16 ++--- .../stereo/impl/disparity_map_converter.hpp | 10 +-- stereo/src/digital_elevation_map.cpp | 4 +- tools/obj_rec_ransac_accepted_hypotheses.cpp | 7 +- tools/octree_viewer.cpp | 13 ++-- tools/openni_image.cpp | 3 +- tools/openni_viewer.cpp | 14 ++-- tools/ply2obj.cpp | 14 ++-- tools/ply2ply.cpp | 12 ++-- tools/ply2raw.cpp | 23 ++----- 40 files changed, 231 insertions(+), 418 deletions(-) diff --git a/registration/include/pcl/registration/impl/ndt.hpp b/registration/include/pcl/registration/impl/ndt.hpp index e3192073d68..15ac5d68e4b 100644 --- a/registration/include/pcl/registration/impl/ndt.hpp +++ b/registration/include/pcl/registration/impl/ndt.hpp @@ -46,7 +46,7 @@ namespace pcl { template NormalDistributionsTransform:: NormalDistributionsTransform() -: target_cells_(), trans_likelihood_() +: target_cells_() { reg_name_ = "NormalDistributionsTransform"; diff --git a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h index bc99e831d48..77bf58926f5 100644 --- a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h @@ -144,28 +144,28 @@ namespace pcl protected: /** \brief Maximum window size to be used in filtering ground returns. */ - int max_window_size_; + int max_window_size_{33}; /** \brief Slope value to be used in computing the height threshold. */ - float slope_; + float slope_{0.7f}; /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */ - float max_distance_; + float max_distance_{10.0f}; /** \brief Initial height above the parameterized ground surface to be considered a ground return. */ - float initial_distance_; + float initial_distance_{0.15f}; /** \brief Cell size. */ - float cell_size_; + float cell_size_{1.0f}; /** \brief Base to be used in computing progressive window sizes. */ - float base_; + float base_{2.0f}; /** \brief Exponentially grow window sizes? */ - bool exponential_; + bool exponential_{true}; /** \brief Number of threads to be used. */ - unsigned int threads_; + unsigned int threads_{0}; }; } diff --git a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h index dd7157867f3..a922e1b74c6 100644 --- a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h +++ b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h @@ -99,9 +99,6 @@ namespace pcl ConditionalEuclideanClustering (bool extract_removed_clusters = false) : searcher_ (), condition_function_ (), - cluster_tolerance_ (0.0f), - min_cluster_size_ (1), - max_cluster_size_ (std::numeric_limits::max ()), extract_removed_clusters_ (extract_removed_clusters), small_clusters_ (new pcl::IndicesClusters), large_clusters_ (new pcl::IndicesClusters) @@ -237,28 +234,28 @@ namespace pcl private: /** \brief A pointer to the spatial search object */ - SearcherPtr searcher_; + SearcherPtr searcher_{nullptr}; /** \brief The condition function that needs to hold for clustering */ std::function condition_function_; /** \brief The distance to scan for cluster candidates (default = 0.0) */ - float cluster_tolerance_; + float cluster_tolerance_{0.0f}; /** \brief The minimum cluster size (default = 1) */ - int min_cluster_size_; + int min_cluster_size_{1}; /** \brief The maximum cluster size (default = unlimited) */ - int max_cluster_size_; + int max_cluster_size_{std::numeric_limits::max ()}; /** \brief Set to true if you want to be able to extract the clusters that are too large or too small (default = false) */ bool extract_removed_clusters_; /** \brief The resultant clusters that contain less than min_cluster_size points */ - pcl::IndicesClustersPtr small_clusters_; + pcl::IndicesClustersPtr small_clusters_{nullptr}; /** \brief The resultant clusters that contain more than max_cluster_size points */ - pcl::IndicesClustersPtr large_clusters_; + pcl::IndicesClustersPtr large_clusters_{nullptr}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/segmentation/include/pcl/segmentation/cpc_segmentation.h b/segmentation/include/pcl/segmentation/cpc_segmentation.h index cb665b0b7f4..897070e3522 100644 --- a/segmentation/include/pcl/segmentation/cpc_segmentation.h +++ b/segmentation/include/pcl/segmentation/cpc_segmentation.h @@ -138,25 +138,25 @@ namespace pcl /// *** Parameters *** /// /** \brief Maximum number of cuts */ - std::uint32_t max_cuts_; + std::uint32_t max_cuts_{20}; /** \brief Minimum segment size for cutting */ - std::uint32_t min_segment_size_for_cutting_; + std::uint32_t min_segment_size_for_cutting_{400}; /** \brief Cut_score threshold */ - float min_cut_score_; + float min_cut_score_{0.16}; /** \brief Use local constrains for cutting */ - bool use_local_constrains_; + bool use_local_constrains_{true}; /** \brief Use directed weights for the cutting */ - bool use_directed_weights_; + bool use_directed_weights_{true}; /** \brief Use clean cutting */ - bool use_clean_cutting_; + bool use_clean_cutting_{false}; /** \brief Iterations for RANSAC */ - std::uint32_t ransac_itrs_; + std::uint32_t ransac_itrs_{10000}; /******************************************* Directional weighted RANSAC declarations ******************************************************************/ diff --git a/segmentation/include/pcl/segmentation/extract_clusters.h b/segmentation/include/pcl/segmentation/extract_clusters.h index b62b93cb8bf..cbda2cdf952 100644 --- a/segmentation/include/pcl/segmentation/extract_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_clusters.h @@ -337,11 +337,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - EuclideanClusterExtraction () : tree_ (), - cluster_tolerance_ (0), - min_pts_per_cluster_ (1), - max_pts_per_cluster_ (std::numeric_limits::max ()) - {}; + EuclideanClusterExtraction () = default; /** \brief Provide a pointer to the search object. * \param[in] tree a pointer to the spatial search object. @@ -423,16 +419,16 @@ namespace pcl using BasePCLBase::deinitCompute; /** \brief A pointer to the spatial search object. */ - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_; + double cluster_tolerance_{0.0}; /** \brief The minimum number of points that a cluster needs to contain in order to be considered valid (default = 1). */ - pcl::uindex_t min_pts_per_cluster_; + pcl::uindex_t 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). */ - pcl::uindex_t max_pts_per_cluster_; + pcl::uindex_t max_pts_per_cluster_{std::numeric_limits::max()}; /** \brief Class getName method. */ virtual std::string getClassName () const { return ("EuclideanClusterExtraction"); } diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index fddf4d8d56d..48356ba5122 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -88,12 +88,7 @@ class LabeledEuclideanClusterExtraction : public PCLBase { ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - LabeledEuclideanClusterExtraction() - : tree_() - , cluster_tolerance_(0) - , min_pts_per_cluster_(1) - , max_pts_per_cluster_(std::numeric_limits::max()) - , max_label_(std::numeric_limits::max()){}; + LabeledEuclideanClusterExtraction() = default; /** \brief Provide a pointer to the search object. * \param[in] tree a pointer to the spatial search object. @@ -177,22 +172,22 @@ class LabeledEuclideanClusterExtraction : public PCLBase { using BasePCLBase::input_; /** \brief A pointer to the spatial search object. */ - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /** \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 The maximum number of labels we can find in this pointcloud (default = * MAXINT)*/ - unsigned int max_label_; + unsigned int max_label_{std::numeric_limits::max()}; /** \brief Class getName method. */ virtual std::string diff --git a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h index c35e28dbe94..e322599ca93 100644 --- a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h +++ b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h @@ -115,11 +115,7 @@ namespace pcl using PointIndicesConstPtr = PointIndices::ConstPtr; /** \brief Empty constructor. */ - ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3), - height_limit_min_ (0), - height_limit_max_(std::numeric_limits::max()), - vpx_ (0), vpy_ (0), vpz_ (0) - {}; + ExtractPolygonalPrismData () = default; /** \brief Provide a pointer to the input planar hull dataset. * \note Please see the example in the class description for how to obtain this. @@ -187,23 +183,23 @@ namespace pcl protected: /** \brief A pointer to the input planar hull dataset. */ - PointCloudConstPtr planar_hull_; + PointCloudConstPtr planar_hull_{nullptr}; /** \brief The minimum number of points needed on the convex hull. */ - int min_pts_hull_; + int min_pts_hull_{3}; /** \brief The minimum allowed height (distance to the model) a point * will be considered from. */ - double height_limit_min_; + double height_limit_min_{0.0}; /** \brief The maximum allowed height (distance to the model) a point * will be considered from. */ - double height_limit_max_; + double height_limit_max_{std::numeric_limits::max()}; /** \brief Values describing the data acquisition viewpoint. Default: 0,0,0. */ - float vpx_, vpy_, vpz_; + float vpx_{0}, vpy_{0}, vpz_{0}; /** \brief Class getName method. */ virtual std::string diff --git a/segmentation/include/pcl/segmentation/grabcut_segmentation.h b/segmentation/include/pcl/segmentation/grabcut_segmentation.h index 6734b46b12e..13d20d77a82 100644 --- a/segmentation/include/pcl/segmentation/grabcut_segmentation.h +++ b/segmentation/include/pcl/segmentation/grabcut_segmentation.h @@ -157,7 +157,7 @@ namespace pcl /// nodes and their outgoing internal edges std::vector nodes_; /// current flow value (includes constant) - double flow_value_; + double flow_value_{0.0}; /// identifies which side of the cut a node falls std::vector cut_; @@ -256,12 +256,9 @@ namespace pcl class GaussianFitter { public: - GaussianFitter (float epsilon = 0.0001) - : sum_ (Eigen::Vector3f::Zero ()) - , accumulator_ (Eigen::Matrix3f::Zero ()) - , count_ (0) - , epsilon_ (epsilon) - { } + GaussianFitter (float epsilon = 0.0001f) + : epsilon_ (epsilon) + {} /// Add a color sample void @@ -281,11 +278,11 @@ namespace pcl private: /// sum of r,g, and b - Eigen::Vector3f sum_; + Eigen::Vector3f sum_{Eigen::Vector3f::Zero ()}; /// matrix of products (i.e. r*r, r*g, r*b), some values are duplicated. - Eigen::Matrix3f accumulator_; + Eigen::Matrix3f accumulator_{Eigen::Matrix3f::Zero ()}; /// count of color samples added to the gaussian - std::uint32_t count_; + std::uint32_t count_{0}; /// small value to add to covariance matrix diagonal to avoid singular values float epsilon_; PCL_MAKE_ALIGNED_OPERATOR_NEW @@ -329,12 +326,8 @@ namespace pcl using PCLBase::fake_indices_; /// Constructor - GrabCut (std::uint32_t K = 5, float lambda = 50.f) - : K_ (K) - , lambda_ (lambda) - , nb_neighbours_ (9) - , initialized_ (false) - {} + GrabCut(std::uint32_t K = 5, float lambda = 50.f) : K_(K), lambda_(lambda) {} + /// Destructor ~GrabCut () override = default; // /// Set input cloud @@ -399,12 +392,12 @@ namespace pcl // Storage for N-link weights, each pixel stores links to nb_neighbours struct NLinks { - NLinks () : nb_links (0), indices (0), dists (0), weights (0) {} + NLinks () = default; - int nb_links; - Indices indices; - std::vector dists; - std::vector weights; + int nb_links{0}; + Indices indices{}; + std::vector dists{}; + std::vector weights{}; }; bool initCompute (); @@ -460,9 +453,9 @@ namespace pcl /// Pointer to the spatial search object. KdTreePtr tree_; /// Number of neighbours - int nb_neighbours_; + int nb_neighbours_{9}; /// is segmentation initialized - bool initialized_; + bool initialized_{false}; /// Precomputed N-link weights std::vector n_links_; /// Converted input diff --git a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp index 4a98b2e33bf..8a054c54c1d 100644 --- a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -49,17 +49,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::ApproximateProgressiveMorphologicalFilter::ApproximateProgressiveMorphologicalFilter () : - max_window_size_ (33), - slope_ (0.7f), - max_distance_ (10.0f), - initial_distance_ (0.15f), - cell_size_ (1.0f), - base_ (2.0f), - exponential_ (true), - threads_ (0) -{ -} +pcl::ApproximateProgressiveMorphologicalFilter::ApproximateProgressiveMorphologicalFilter () = default; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp index 05e8ff94214..f1aca882eca 100644 --- a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp @@ -42,15 +42,7 @@ #include template -pcl::CPCSegmentation::CPCSegmentation () : - max_cuts_ (20), - min_segment_size_for_cutting_ (400), - min_cut_score_ (0.16), - use_local_constrains_ (true), - use_directed_weights_ (true), - ransac_itrs_ (10000) -{ -} +pcl::CPCSegmentation::CPCSegmentation () = default; template pcl::CPCSegmentation::~CPCSegmentation () = default; diff --git a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp index 3bf0777282f..8f1f6033670 100644 --- a/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/lccp_segmentation.hpp @@ -51,19 +51,7 @@ template -pcl::LCCPSegmentation::LCCPSegmentation () : - concavity_tolerance_threshold_ (10), - grouping_data_valid_ (false), - supervoxels_set_ (false), - use_smoothness_check_ (false), - smoothness_threshold_ (0.1), - use_sanity_check_ (false), - seed_resolution_ (0), - voxel_resolution_ (0), - k_factor_ (0), - min_segment_size_ (0) -{ -} +pcl::LCCPSegmentation::LCCPSegmentation () = default; template pcl::LCCPSegmentation::~LCCPSegmentation () = default; diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index 0288a260497..0ec614a8e53 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -47,26 +47,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::MinCutSegmentation::MinCutSegmentation () : - inverse_sigma_ (16.0), - binary_potentials_are_valid_ (false), - epsilon_ (0.0001), - radius_ (16.0), - unary_potentials_are_valid_ (false), - source_weight_ (0.8), - search_ (), - number_of_neighbours_ (14), - graph_is_valid_ (false), - foreground_points_ (0), - background_points_ (0), - clusters_ (0), - vertices_ (0), - edge_marker_ (0), - source_ (),///////////////////////////////// - sink_ (),/////////////////////////////////// - max_flow_ (0.0) -{ -} +pcl::MinCutSegmentation::MinCutSegmentation () = default; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp index 1c1ee2e0148..68a3d3cd240 100644 --- a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp @@ -48,16 +48,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::ProgressiveMorphologicalFilter::ProgressiveMorphologicalFilter () : - max_window_size_ (33), - slope_ (0.7f), - max_distance_ (10.0f), - initial_distance_ (0.15f), - cell_size_ (1.0f), - base_ (2.0f), - exponential_ (true) -{ -} +pcl::ProgressiveMorphologicalFilter::ProgressiveMorphologicalFilter () = default; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index be75d0cf7ba..0677cfbe17e 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -54,26 +54,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::RegionGrowing::RegionGrowing () : - min_pts_per_cluster_ (1), - max_pts_per_cluster_ (std::numeric_limits::max ()), - smooth_mode_flag_ (true), - curvature_flag_ (true), - residual_flag_ (false), - theta_threshold_ (30.0f / 180.0f * static_cast (M_PI)), - residual_threshold_ (0.05f), - curvature_threshold_ (0.05f), - neighbour_number_ (30), - search_ (), - normals_ (), - point_neighbours_ (0), - point_labels_ (0), - normal_flag_ (true), - num_pts_in_segment_ (0), - clusters_ (0), - number_of_segments_ (0) -{ -} +pcl::RegionGrowing::RegionGrowing() = default; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp index b53a704b09c..2c240d37c46 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing_rgb.hpp @@ -50,10 +50,6 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template pcl::RegionGrowingRGB::RegionGrowingRGB () : - color_p2p_threshold_ (1225.0f), - color_r2r_threshold_ (10.0f), - distance_threshold_ (0.05f), - region_neighbour_number_ (100), point_distances_ (0), segment_neighbours_ (0), segment_distances_ (0), diff --git a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp index 54aed117bbe..9d627c600ff 100644 --- a/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/supervoxel_clustering.hpp @@ -45,17 +45,14 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::SupervoxelClustering::SupervoxelClustering (float voxel_resolution, float seed_resolution) : - resolution_ (voxel_resolution), - seed_resolution_ (seed_resolution), - adjacency_octree_ (), - voxel_centroid_cloud_ (), - color_importance_ (0.1f), - spatial_importance_ (0.4f), - normal_importance_ (1.0f), - use_default_transform_behaviour_ (true) -{ - adjacency_octree_.reset (new OctreeAdjacencyT (resolution_)); +pcl::SupervoxelClustering::SupervoxelClustering(float voxel_resolution, + float seed_resolution) +: resolution_(voxel_resolution) +, seed_resolution_(seed_resolution) +, adjacency_octree_() +, voxel_centroid_cloud_() +{ + adjacency_octree_.reset(new OctreeAdjacencyT(resolution_)); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp index 38f2cd59cda..dc4ef677a38 100644 --- a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp +++ b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp @@ -52,14 +52,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::UnaryClassifier::UnaryClassifier () : - input_cloud_ (new pcl::PointCloud), - label_field_ (false), - normal_radius_search_ (0.01f), - fpfh_radius_search_ (0.05f), - feature_threshold_ (5.0) -{ -} +pcl::UnaryClassifier::UnaryClassifier() = default; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/segmentation/include/pcl/segmentation/lccp_segmentation.h b/segmentation/include/pcl/segmentation/lccp_segmentation.h index ed04968159c..8e9a82c8802 100644 --- a/segmentation/include/pcl/segmentation/lccp_segmentation.h +++ b/segmentation/include/pcl/segmentation/lccp_segmentation.h @@ -60,21 +60,18 @@ namespace pcl struct EdgeProperties { /** \brief Describes the difference of normals of the two supervoxels being connected*/ - float normal_difference; + float normal_difference{0.0f}; /** \brief Describes if a connection is convex or concave*/ - bool is_convex; + bool is_convex{false}; /** \brief Describes if a connection is valid for the segment growing. Usually convex connections are and concave connection are not. Due to k-concavity a convex connection can be invalidated*/ - bool is_valid; + bool is_valid{false}; /** \brief Additional member used for the CPC algorithm. If edge has already induced a cut, it should be ignored for further cutting.*/ - bool used_for_cutting; + bool used_for_cutting{false}; - EdgeProperties () : - normal_difference (0), is_convex (false), is_valid (false), used_for_cutting (false) - { - } + EdgeProperties () = default; }; public: @@ -297,34 +294,34 @@ namespace pcl /// *** Parameters *** /// /** \brief Normal Threshold in degrees [0,180] used for merging */ - float concavity_tolerance_threshold_; + float concavity_tolerance_threshold_{10}; /** \brief Marks if valid grouping data (\ref sv_adjacency_list_, \ref sv_label_to_seg_label_map_, \ref processed_) is available */ - bool grouping_data_valid_; + bool grouping_data_valid_{false}; /** \brief Marks if supervoxels have been set by calling \ref setInputSupervoxels */ - bool supervoxels_set_; + bool supervoxels_set_{false}; /** \brief Determines if the smoothness check is used during segmentation*/ - bool use_smoothness_check_; + bool use_smoothness_check_{false}; /** \brief Two supervoxels are unsmooth if their plane-to-plane distance DIST > (expected_distance + smoothness_threshold_*voxel_resolution_). For parallel supervoxels, the expected_distance is zero. */ - float smoothness_threshold_; + float smoothness_threshold_{0.1}; /** \brief Determines if we use the sanity check which tries to find and invalidate singular connected patches*/ - bool use_sanity_check_; + bool use_sanity_check_{false}; /** \brief Seed resolution of the supervoxels (used only for smoothness check) */ - float seed_resolution_; + float seed_resolution_{0}; /** \brief Voxel resolution used to build the supervoxels (used only for smoothness check)*/ - float voxel_resolution_; + float voxel_resolution_{0}; /** \brief Factor used for k-convexity */ - std::uint32_t k_factor_; + std::uint32_t k_factor_{0}; /** \brief Minimum segment size */ - std::uint32_t min_segment_size_; + std::uint32_t min_segment_size_{0}; /** \brief Stores which supervoxel labels were already visited during recursive grouping. * \note processed_[sv_Label] = false (default)/true (already processed) */ diff --git a/segmentation/include/pcl/segmentation/min_cut_segmentation.h b/segmentation/include/pcl/segmentation/min_cut_segmentation.h index 3059f9e517e..0e56705ff52 100644 --- a/segmentation/include/pcl/segmentation/min_cut_segmentation.h +++ b/segmentation/include/pcl/segmentation/min_cut_segmentation.h @@ -261,64 +261,64 @@ namespace pcl protected: /** \brief Stores the sigma coefficient. It is used for finding smooth costs. More information can be found in the article. */ - double inverse_sigma_; + double inverse_sigma_{16.0}; /** \brief Signalizes if the binary potentials are valid. */ - bool binary_potentials_are_valid_; + bool binary_potentials_are_valid_{false}; /** \brief Used for comparison of the floating point numbers. */ - double epsilon_; + double epsilon_{0.0001}; /** \brief Stores the distance to the background. */ - double radius_; + double radius_{16.0}; /** \brief Signalizes if the unary potentials are valid. */ - bool unary_potentials_are_valid_; + bool unary_potentials_are_valid_{false}; /** \brief Stores the weight for every edge that comes from source point. */ - double source_weight_; + double source_weight_{0.8}; /** \brief Stores the search method that will be used for finding K nearest neighbors. Neighbours are used for building the graph. */ - KdTreePtr search_; + KdTreePtr search_{nullptr}; /** \brief Stores the number of neighbors to find. */ - unsigned int number_of_neighbours_; + unsigned int number_of_neighbours_{14}; /** \brief Signalizes if the graph is valid. */ - bool graph_is_valid_; + bool graph_is_valid_{false}; /** \brief Stores the points that are known to be in the foreground. */ - std::vector > foreground_points_; + std::vector > foreground_points_{}; /** \brief Stores the points that are known to be in the background. */ - std::vector > background_points_; + std::vector > background_points_{}; /** \brief After the segmentation it will contain the segments. */ - std::vector clusters_; + std::vector clusters_{}; /** \brief Stores the graph for finding the maximum flow. */ - mGraphPtr graph_; + mGraphPtr graph_{nullptr}; /** \brief Stores the capacity of every edge in the graph. */ - std::shared_ptr capacity_; + std::shared_ptr capacity_{nullptr}; /** \brief Stores reverse edges for every edge in the graph. */ - std::shared_ptr reverse_edges_; + std::shared_ptr reverse_edges_{nullptr}; /** \brief Stores the vertices of the graph. */ - std::vector< VertexDescriptor > vertices_; + std::vector< VertexDescriptor > vertices_{}; /** \brief Stores the information about the edges that were added to the graph. It is used to avoid the duplicate edges. */ - std::vector< std::set > edge_marker_; + std::vector< std::set > edge_marker_{}; /** \brief Stores the vertex that serves as source. */ - VertexDescriptor source_; + VertexDescriptor source_{}; /** \brief Stores the vertex that serves as sink. */ - VertexDescriptor sink_; + VertexDescriptor sink_{}; /** \brief Stores the maximum flow value that was calculated during the segmentation. */ - double max_flow_; + double max_flow_{0.0}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h index 462e5e1fa95..79a872a25f3 100644 --- a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h @@ -89,16 +89,7 @@ namespace pcl using PlaneRefinementComparatorConstPtr = typename PlaneRefinementComparator::ConstPtr; /** \brief Constructor for OrganizedMultiPlaneSegmentation. */ - OrganizedMultiPlaneSegmentation () : - normals_ (), - min_inliers_ (1000), - angular_threshold_ (pcl::deg2rad (3.0)), - distance_threshold_ (0.02), - maximum_curvature_ (0.001), - project_points_ (false), - compare_ (new PlaneComparator ()), refinement_compare_ (new PlaneRefinementComparator ()) - { - } + OrganizedMultiPlaneSegmentation() = default; /** \brief Destructor for OrganizedMultiPlaneSegmentation. */ @@ -279,28 +270,28 @@ namespace pcl protected: /** \brief A pointer to the input normals */ - PointCloudNConstPtr normals_; + PointCloudNConstPtr normals_{nullptr}; /** \brief The minimum number of inliers required for each plane. */ - unsigned min_inliers_; + unsigned min_inliers_{1000}; /** \brief The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. */ - double angular_threshold_; + double angular_threshold_{pcl::deg2rad (3.0)}; /** \brief The tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. */ - double distance_threshold_; + double distance_threshold_{0.02}; /** \brief The tolerance for maximum curvature after fitting a plane. Used to remove smooth, but non-planar regions. */ - double maximum_curvature_; + double maximum_curvature_{0.001}; /** \brief Whether or not points should be projected to the plane, or left in the original 3D space. */ - bool project_points_; + bool project_points_{false}; /** \brief A comparator for comparing neighboring pixels' plane equations. */ - PlaneComparatorPtr compare_; + PlaneComparatorPtr compare_{new PlaneComparator}; /** \brief A comparator for use on the refinement step. Compares points to regions segmented in the first pass. */ - PlaneRefinementComparatorPtr refinement_compare_; + PlaneRefinementComparatorPtr refinement_compare_{new PlaneRefinementComparator}; /** \brief Class getName method. */ virtual std::string diff --git a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h index f48f25a1282..894412fb03a 100644 --- a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h @@ -137,25 +137,25 @@ namespace pcl protected: /** \brief Maximum window size to be used in filtering ground returns. */ - int max_window_size_; + int max_window_size_{33}; /** \brief Slope value to be used in computing the height threshold. */ - float slope_; + float slope_{0.7f}; /** \brief Maximum height above the parameterized ground surface to be considered a ground return. */ - float max_distance_; + float max_distance_{10.0f}; /** \brief Initial height above the parameterized ground surface to be considered a ground return. */ - float initial_distance_; + float initial_distance_{0.15f}; /** \brief Cell size. */ - float cell_size_; + float cell_size_{1.0f}; /** \brief Base to be used in computing progressive window sizes. */ - float base_; + float base_{2.0f}; /** \brief Exponentially grow window sizes? */ - bool exponential_; + bool exponential_{true}; }; } diff --git a/segmentation/include/pcl/segmentation/region_growing.h b/segmentation/include/pcl/segmentation/region_growing.h index 30e6876637d..6db56268b20 100644 --- a/segmentation/include/pcl/segmentation/region_growing.h +++ b/segmentation/include/pcl/segmentation/region_growing.h @@ -279,57 +279,57 @@ namespace pcl protected: /** \brief Stores the minimum number of points that a cluster needs to contain in order to be considered valid. */ - pcl::uindex_t min_pts_per_cluster_; + pcl::uindex_t min_pts_per_cluster_{1}; /** \brief Stores the maximum number of points that a cluster needs to contain in order to be considered valid. */ - pcl::uindex_t max_pts_per_cluster_; + pcl::uindex_t max_pts_per_cluster_{std::numeric_limits::max()}; /** \brief Flag that signalizes if the smoothness constraint will be used. */ - bool smooth_mode_flag_; + bool smooth_mode_flag_{true}; /** \brief If set to true then curvature test will be done during segmentation. */ - bool curvature_flag_; + bool curvature_flag_{true}; /** \brief If set to true then residual test will be done during segmentation. */ - bool residual_flag_; + bool residual_flag_{false}; /** \brief Threshold used for testing the smoothness between points. */ - float theta_threshold_; + float theta_threshold_{30.0f / 180.0f * static_cast(M_PI)}; /** \brief Threshold used in residual test. */ - float residual_threshold_; + float residual_threshold_{0.05f}; /** \brief Threshold used in curvature test. */ - float curvature_threshold_; + float curvature_threshold_{0.05f}; /** \brief Number of neighbours to find. */ - unsigned int neighbour_number_; + unsigned int neighbour_number_{30}; /** \brief Search method that will be used for KNN. */ - KdTreePtr search_; + KdTreePtr search_{nullptr}; /** \brief Contains normals of the points that will be segmented. */ - NormalPtr normals_; + NormalPtr normals_{nullptr}; /** \brief Contains neighbours of each point. */ - std::vector point_neighbours_; + std::vector point_neighbours_{}; /** \brief Point labels that tells to which segment each point belongs. */ - std::vector point_labels_; + std::vector point_labels_{}; /** \brief If set to true then normal/smoothness test will be done during segmentation. * It is always set to true for the usual region growing algorithm. It is used for turning on/off the test * for smoothness in the child class RegionGrowingRGB.*/ - bool normal_flag_; + bool normal_flag_{true}; /** \brief Tells how much points each segment contains. Used for reserving memory. */ - std::vector num_pts_in_segment_; + std::vector num_pts_in_segment_{}; /** \brief After the segmentation it will contain the segments. */ - std::vector clusters_; + std::vector clusters_{}; /** \brief Stores the number of segments. */ - int number_of_segments_; + int number_of_segments_{0}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/segmentation/include/pcl/segmentation/region_growing_rgb.h b/segmentation/include/pcl/segmentation/region_growing_rgb.h index e409d80d69a..68670d379a8 100644 --- a/segmentation/include/pcl/segmentation/region_growing_rgb.h +++ b/segmentation/include/pcl/segmentation/region_growing_rgb.h @@ -252,16 +252,16 @@ namespace pcl protected: /** \brief Thershold used in color test for points. */ - float color_p2p_threshold_; + float color_p2p_threshold_{1225.0f}; /** \brief Thershold used in color test for regions. */ - float color_r2r_threshold_; + float color_r2r_threshold_{10.0f}; /** \brief Threshold that tells which points we need to assume neighbouring. */ - float distance_threshold_; + float distance_threshold_{0.05f}; /** \brief Number of neighbouring segments to find. */ - unsigned int region_neighbour_number_; + unsigned int region_neighbour_number_{100}; /** \brief Stores distances for the point neighbours from point_neighbours_ */ std::vector< std::vector > point_distances_; diff --git a/segmentation/include/pcl/segmentation/sac_segmentation.h b/segmentation/include/pcl/segmentation/sac_segmentation.h index aa3bdbf146d..3f8047905b5 100644 --- a/segmentation/include/pcl/segmentation/sac_segmentation.h +++ b/segmentation/include/pcl/segmentation/sac_segmentation.h @@ -81,25 +81,9 @@ namespace pcl /** \brief Empty constructor. * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) */ - SACSegmentation (bool random = false) - : model_ () - , sac_ () - , model_type_ (-1) - , method_type_ (0) - , threshold_ (0) - , optimize_coefficients_ (true) - , radius_min_ (-std::numeric_limits::max ()) - , radius_max_ (std::numeric_limits::max ()) - , samples_radius_ (0.0) - , samples_radius_search_ () - , eps_angle_ (0.0) - , axis_ (Eigen::Vector3f::Zero ()) - , max_iterations_ (50) - , threads_ (-1) - , probability_ (0.99) - , random_ (random) - { - } + SACSegmentation(bool random = false) + : random_(random) + {} /** \brief Empty destructor. */ ~SACSegmentation () override = default; @@ -264,46 +248,46 @@ namespace pcl initSAC (const int method_type); /** \brief The model that needs to be segmented. */ - SampleConsensusModelPtr model_; + SampleConsensusModelPtr model_{nullptr}; /** \brief The sample consensus segmentation method. */ - SampleConsensusPtr sac_; + SampleConsensusPtr sac_{nullptr}; /** \brief The type of model to use (user given parameter). */ - int model_type_; + int model_type_{-1}; /** \brief The type of sample consensus method to use (user given parameter). */ - int method_type_; + int method_type_{0}; /** \brief Distance to the model threshold (user given parameter). */ - double threshold_; + double threshold_{0}; /** \brief Set to true if a coefficient refinement is required. */ - bool optimize_coefficients_; + bool optimize_coefficients_{true}; /** \brief The minimum and maximum radius limits for the model. Applicable to all models that estimate a radius. */ - double radius_min_, radius_max_; + double radius_min_{-std::numeric_limits::max()}, radius_max_{std::numeric_limits::max()}; /** \brief The maximum distance of subsequent samples from the first (radius search) */ - double samples_radius_; + double samples_radius_{0.0}; /** \brief The search object for picking subsequent samples using radius search */ - SearchPtr samples_radius_search_; + SearchPtr samples_radius_search_{nullptr}; /** \brief The maximum allowed difference between the model normal and the given axis. */ - double eps_angle_; + double eps_angle_{0.0}; /** \brief The axis along which we need to search for a model perpendicular to. */ - Eigen::Vector3f axis_; + Eigen::Vector3f axis_{Eigen::Vector3f::Zero()}; /** \brief Maximum number of iterations before giving up (user given parameter). */ - int max_iterations_; + int max_iterations_{50}; /** \brief The number of threads the scheduler should use, or a negative number if no parallelization is wanted. */ - int threads_; + int threads_{-1}; /** \brief Desired probability of choosing at least one sample free from outliers (user given parameter). */ - double probability_; + double probability_{0.99}; /** \brief Set to true if we need a random seed. */ bool random_; @@ -349,11 +333,6 @@ namespace pcl */ SACSegmentationFromNormals (bool random = false) : SACSegmentation (random) - , normals_ () - , distance_weight_ (0.1) - , distance_from_origin_ (0) - , min_angle_ (0.0) - , max_angle_ (M_PI_2) {}; /** \brief Provide a pointer to the input dataset that contains the point normals of @@ -410,19 +389,19 @@ namespace pcl protected: /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */ - PointCloudNConstPtr normals_; + PointCloudNConstPtr normals_{nullptr}; /** \brief The relative weight (between 0 and 1) to give to the angular * distance (0 to pi/2) between point normals and the plane normal. */ - double distance_weight_; + double distance_weight_{0.1}; /** \brief The distance from the template plane to the origin. */ - double distance_from_origin_; + double distance_from_origin_{0}; /** \brief The minimum and maximum allowed opening angle of valid cone model. */ - double min_angle_; - double max_angle_; + double min_angle_{0.0}; + double max_angle_{M_PI_2}; /** \brief Initialize the Sample Consensus model and set its parameters. * \param[in] model_type the type of SAC model that is to be used diff --git a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h index 0a8826cea14..a89ee2d3754 100644 --- a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h +++ b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h @@ -107,8 +107,7 @@ namespace pcl ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ - SeededHueSegmentation () : cluster_tolerance_ (0), delta_hue_ (0.0) - {}; + SeededHueSegmentation () = default; /** \brief Provide a pointer to the search object. * \param[in] tree a pointer to the spatial search object. @@ -155,13 +154,13 @@ namespace pcl using BasePCLBase::deinitCompute; /** \brief A pointer to the spatial search object. */ - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /** \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 ("seededHueSegmentation"); } diff --git a/segmentation/include/pcl/segmentation/segment_differences.h b/segmentation/include/pcl/segmentation/segment_differences.h index 9b89cd2a033..6cc2d90a547 100755 --- a/segmentation/include/pcl/segmentation/segment_differences.h +++ b/segmentation/include/pcl/segmentation/segment_differences.h @@ -85,9 +85,7 @@ namespace pcl using PointIndicesConstPtr = PointIndices::ConstPtr; /** \brief Empty constructor. */ - SegmentDifferences () : - tree_ (), target_ (), distance_threshold_ (0) - {}; + SegmentDifferences () = default; /** \brief Provide a pointer to the target dataset against which we * compare the input cloud given in setInputCloud @@ -139,15 +137,15 @@ namespace pcl using BasePCLBase::deinitCompute; /** \brief A pointer to the spatial search object. */ - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /** \brief The input target point cloud dataset. */ - PointCloudConstPtr target_; + PointCloudConstPtr target_{nullptr}; /** \brief The distance tolerance (squared) as a measure in the L2 * Euclidean space between corresponding points. */ - double distance_threshold_; + double distance_threshold_{0.0}; /** \brief Class getName method. */ virtual std::string diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index e46239c50af..78cbf00ba9f 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -139,9 +139,7 @@ namespace pcl xyz_ (0.0f, 0.0f, 0.0f), rgb_ (0.0f, 0.0f, 0.0f), normal_ (0.0f, 0.0f, 0.0f, 0.0f), - curvature_ (0.0f), - distance_(0), - idx_(0), + owner_ (nullptr) {} @@ -160,9 +158,9 @@ namespace pcl Eigen::Vector3f xyz_; Eigen::Vector3f rgb_; Eigen::Vector4f normal_; - float curvature_; - float distance_; - int idx_; + float curvature_{0.0f}; + float distance_{0}; + int idx_{0}; SupervoxelHelper* owner_; public: @@ -373,11 +371,11 @@ namespace pcl typename NormalCloudT::ConstPtr input_normals_; /** \brief Importance of color in clustering */ - float color_importance_; + float color_importance_{0.1f}; /** \brief Importance of distance from seed center in clustering */ - float spatial_importance_; + float spatial_importance_{0.4f}; /** \brief Importance of similarity in normals for clustering */ - float normal_importance_; + float normal_importance_{1.0f}; /** \brief Whether or not to use the transform compressing depth in Z * This is only checked if it has been manually set by the user. @@ -385,7 +383,7 @@ namespace pcl */ bool use_single_camera_transform_; /** \brief Whether to use default transform behavior or not */ - bool use_default_transform_behaviour_; + bool use_default_transform_behaviour_{true}; /** \brief Internal storage class for supervoxels * \note Stores pointers to leaves of clustering internal octree, diff --git a/segmentation/include/pcl/segmentation/unary_classifier.h b/segmentation/include/pcl/segmentation/unary_classifier.h index 52ed89e90d5..f6025c6a171 100644 --- a/segmentation/include/pcl/segmentation/unary_classifier.h +++ b/segmentation/include/pcl/segmentation/unary_classifier.h @@ -145,18 +145,18 @@ namespace pcl /** \brief Contains the input cloud */ - typename pcl::PointCloud::Ptr input_cloud_; + typename pcl::PointCloud::Ptr input_cloud_{new pcl::PointCloud}; - bool label_field_; + bool label_field_{false}; - unsigned int cluster_size_; + unsigned int cluster_size_{0}; - float normal_radius_search_; - float fpfh_radius_search_; - float feature_threshold_; + float normal_radius_search_{0.01f}; + float fpfh_radius_search_{0.05f}; + float feature_threshold_{5.0}; - std::vector::Ptr> trained_features_; + std::vector::Ptr> trained_features_{}; /** \brief Contains normals of the points that will be segmented. */ //typename pcl::PointCloud::Ptr normals_; diff --git a/segmentation/src/grabcut_segmentation.cpp b/segmentation/src/grabcut_segmentation.cpp index e6d309f63ca..ea2b75c7704 100644 --- a/segmentation/src/grabcut_segmentation.cpp +++ b/segmentation/src/grabcut_segmentation.cpp @@ -47,7 +47,6 @@ const int pcl::segmentation::grabcut::BoykovKolmogorov::TERMINAL = -1; pcl::segmentation::grabcut::BoykovKolmogorov::BoykovKolmogorov (std::size_t max_nodes) - : flow_value_(0.0) { if (max_nodes > 0) { diff --git a/stereo/include/pcl/stereo/digital_elevation_map.h b/stereo/include/pcl/stereo/digital_elevation_map.h index 9a4cd8c0afa..53df19b34d4 100644 --- a/stereo/include/pcl/stereo/digital_elevation_map.h +++ b/stereo/include/pcl/stereo/digital_elevation_map.h @@ -129,11 +129,11 @@ class PCL_EXPORTS DigitalElevationMapBuilder : public DisparityMapConverter::ConstPtr image_; /** \brief Vector for the disparity map. */ std::vector disparity_map_; /** \brief X-size of the disparity map. */ - std::size_t disparity_map_width_; + std::size_t disparity_map_width_{640}; /** \brief Y-size of the disparity map. */ - std::size_t disparity_map_height_; + std::size_t disparity_map_height_{480}; /** \brief Thresholds of the disparity. */ - float disparity_threshold_min_; + float disparity_threshold_min_{0.0f}; float disparity_threshold_max_; }; diff --git a/stereo/include/pcl/stereo/impl/disparity_map_converter.hpp b/stereo/include/pcl/stereo/impl/disparity_map_converter.hpp index 773a2870411..ce7db93ef84 100644 --- a/stereo/include/pcl/stereo/impl/disparity_map_converter.hpp +++ b/stereo/include/pcl/stereo/impl/disparity_map_converter.hpp @@ -47,15 +47,7 @@ template pcl::DisparityMapConverter::DisparityMapConverter() -: center_x_(0.0f) -, center_y_(0.0f) -, focal_length_(0.0f) -, baseline_(0.0f) -, is_color_(false) -, disparity_map_width_(640) -, disparity_map_height_(480) -, disparity_threshold_min_(0.0f) -, disparity_threshold_max_(std::numeric_limits::max()) +: disparity_threshold_max_(std::numeric_limits::max()) {} template diff --git a/stereo/src/digital_elevation_map.cpp b/stereo/src/digital_elevation_map.cpp index f5406942ccf..ef312c76e12 100644 --- a/stereo/src/digital_elevation_map.cpp +++ b/stereo/src/digital_elevation_map.cpp @@ -38,9 +38,7 @@ #include #include -pcl::DigitalElevationMapBuilder::DigitalElevationMapBuilder() -: resolution_column_(64), resolution_disparity_(32), min_points_in_cell_(1) -{} +pcl::DigitalElevationMapBuilder::DigitalElevationMapBuilder() = default; pcl::DigitalElevationMapBuilder::~DigitalElevationMapBuilder() = default; diff --git a/tools/obj_rec_ransac_accepted_hypotheses.cpp b/tools/obj_rec_ransac_accepted_hypotheses.cpp index ea5447ac2ea..f75bd66a750 100644 --- a/tools/obj_rec_ransac_accepted_hypotheses.cpp +++ b/tools/obj_rec_ransac_accepted_hypotheses.cpp @@ -85,9 +85,8 @@ class CallbackParameters viz_ (viz), points_ (points), normals_ (normals), - num_hypotheses_to_show_ (num_hypotheses_to_show), - show_models_ (true) - { } + num_hypotheses_to_show_ (num_hypotheses_to_show) + {} ObjRecRANSAC& objrec_; PCLVisualizer& viz_; @@ -95,7 +94,7 @@ class CallbackParameters PointCloud& normals_; int num_hypotheses_to_show_; std::list actors_, model_actors_; - bool show_models_; + bool show_models_{true}; }; //=============================================================================================================================== diff --git a/tools/octree_viewer.cpp b/tools/octree_viewer.cpp index 6381edbed0e..9962882c682 100644 --- a/tools/octree_viewer.cpp +++ b/tools/octree_viewer.cpp @@ -62,12 +62,7 @@ class OctreeViewer cloud (new pcl::PointCloud()), displayCloud (new pcl::PointCloud()), cloudVoxel (new pcl::PointCloud()), - octree (resolution), - wireframe (true), - show_cubes_ (true), - show_centroids_ (false), - show_original_points_ (false), - point_size_ (1.0) + octree (resolution) { //try to load the cloud @@ -126,9 +121,9 @@ class OctreeViewer //level int displayedDepth; //bool to decide what should be display - bool wireframe; - bool show_cubes_, show_centroids_, show_original_points_; - float point_size_; + bool wireframe{true}; + bool show_cubes_{true}, show_centroids_{false}, show_original_points_{false}; + float point_size_{1.0}; //======================================================== /* \brief Callback to interact with the keyboard diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 84a1d7c3281..5560ef682e2 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -549,7 +549,6 @@ class Viewer /////////////////////////////////////////////////////////////////////////////////////// Viewer (Buffer &buf) : buf_ (buf) - , image_cld_init_ (false), depth_image_cld_init_ (false) { image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI RGB image viewer")); depth_image_viewer_.reset (new visualization::ImageViewer ("PCL/OpenNI depth image viewer")); @@ -620,7 +619,7 @@ class Viewer Buffer &buf_; visualization::ImageViewer::Ptr image_viewer_; visualization::ImageViewer::Ptr depth_image_viewer_; - bool image_cld_init_, depth_image_cld_init_; + bool image_cld_init_{false}, depth_image_cld_init_{false}; }; void diff --git a/tools/openni_viewer.cpp b/tools/openni_viewer.cpp index 7098f4609ee..3b131c8a820 100644 --- a/tools/openni_viewer.cpp +++ b/tools/openni_viewer.cpp @@ -109,12 +109,10 @@ class OpenNIViewer using Cloud = pcl::PointCloud; using CloudConstPtr = typename Cloud::ConstPtr; - OpenNIViewer (pcl::Grabber& grabber) - : cloud_viewer_ (new pcl::visualization::PCLVisualizer ("PCL OpenNI cloud")) - , grabber_ (grabber) - , rgb_data_ (nullptr), rgb_data_size_ (0) - { - } + OpenNIViewer(pcl::Grabber& grabber) + : cloud_viewer_(new pcl::visualization::PCLVisualizer("PCL OpenNI cloud")) + , grabber_(grabber) + {} void cloud_callback (const CloudConstPtr& cloud) @@ -263,8 +261,8 @@ class OpenNIViewer CloudConstPtr cloud_; openni_wrapper::Image::Ptr image_; - unsigned char* rgb_data_; - unsigned rgb_data_size_; + unsigned char* rgb_data_{nullptr}; + unsigned rgb_data_size_{0}; }; // Create the PCLVisualizer object diff --git a/tools/ply2obj.cpp b/tools/ply2obj.cpp index f85b3db4280..5db70395c57 100644 --- a/tools/ply2obj.cpp +++ b/tools/ply2obj.cpp @@ -122,18 +122,14 @@ class ply_to_obj_converter void face_end (); - flags_type flags_; - std::ostream* ostream_; - double vertex_x_, vertex_y_, vertex_z_; - std::size_t face_vertex_indices_element_index_, face_vertex_indices_first_element_, face_vertex_indices_previous_element_; + flags_type flags_{0}; + std::ostream* ostream_{}; + double vertex_x_{0}, vertex_y_{0}, vertex_z_{0}; + std::size_t face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0}; }; ply_to_obj_converter::ply_to_obj_converter (flags_type flags) - : flags_ (flags), ostream_ (), - vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), - face_vertex_indices_element_index_ (), - face_vertex_indices_first_element_ (), - face_vertex_indices_previous_element_ () + : flags_ (flags) { } diff --git a/tools/ply2ply.cpp b/tools/ply2ply.cpp index b82c742d7ac..e749f4b2c69 100644 --- a/tools/ply2ply.cpp +++ b/tools/ply2ply.cpp @@ -65,10 +65,8 @@ class ply_to_ply_converter binary_big_endian_format, binary_little_endian_format }; - - ply_to_ply_converter(format_type format) : - format_(format), input_format_(), output_format_(), - bol_ (), ostream_ () {} + + ply_to_ply_converter(format_type format) : format_(format) {} bool convert (const std::string &filename, std::istream& istream, std::ostream& ostream); @@ -128,9 +126,9 @@ class ply_to_ply_converter end_header_callback(); format_type format_; - pcl::io::ply::format_type input_format_, output_format_; - bool bol_; - std::ostream* ostream_; + pcl::io::ply::format_type input_format_{}, output_format_{}; + bool bol_{false}; + std::ostream* ostream_{}; }; void diff --git a/tools/ply2raw.cpp b/tools/ply2raw.cpp index 9e1b70829c5..86ab736ea45 100644 --- a/tools/ply2raw.cpp +++ b/tools/ply2raw.cpp @@ -61,18 +61,9 @@ class ply_to_raw_converter { public: - ply_to_raw_converter () : - ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), - face_vertex_indices_element_index_ (), - face_vertex_indices_first_element_ (), - face_vertex_indices_previous_element_ () - {} - - ply_to_raw_converter (const ply_to_raw_converter &f) : - ostream_ (), vertex_x_ (0), vertex_y_ (0), vertex_z_ (0), - face_vertex_indices_element_index_ (), - face_vertex_indices_first_element_ (), - face_vertex_indices_previous_element_ () + ply_to_raw_converter() = default; + + ply_to_raw_converter (const ply_to_raw_converter &f) { *this = f; } @@ -144,10 +135,10 @@ class ply_to_raw_converter void face_end (); - std::ostream* ostream_; - pcl::io::ply::float32 vertex_x_, vertex_y_, vertex_z_; - pcl::io::ply::int32 face_vertex_indices_element_index_, face_vertex_indices_first_element_, face_vertex_indices_previous_element_; - std::vector > vertices_; + std::ostream* ostream_{}; + pcl::io::ply::float32 vertex_x_{0}, vertex_y_{0}, vertex_z_{0}; + pcl::io::ply::int32 face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0}; + std::vector > vertices_{}; }; void From d7317bb36b5f2b079c3e3e7cc867cd654c27ad6c Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 3 Dec 2023 20:18:16 +0100 Subject: [PATCH 165/288] Add instantiations for ICP and TransformationEstimationSVD Add explicit instantiations in the .cpp files, for very commonly used point types (while building pcl_registration). When using ICP or TransformationEstimationSVD in other files, the `extern template class ...` statements in the .h files tell the compiler to not instantiate the templates, and to use the previous instantiations instead (from pcl_registration). This decreases the compilation time for user code, and also for e.g. pcl tools and pcl apps (the pcl_icp tool for example compiles in 10s now vs 13s before). The compilation time of PCL as a whole decreases slightly (1.5 percent less in one configuration with clang). --- apps/3d_rec_framework/CMakeLists.txt | 2 +- apps/CMakeLists.txt | 2 +- registration/include/pcl/registration/icp.h | 9 ++++++++- .../registration/transformation_estimation_svd.h | 11 +++++++++++ registration/src/icp.cpp | 11 +++++++++++ registration/src/transformation_estimation_svd.cpp | 13 +++++++++++++ 6 files changed, 45 insertions(+), 3 deletions(-) diff --git a/apps/3d_rec_framework/CMakeLists.txt b/apps/3d_rec_framework/CMakeLists.txt index 56e4ee7a66d..3e8b8e997d7 100644 --- a/apps/3d_rec_framework/CMakeLists.txt +++ b/apps/3d_rec_framework/CMakeLists.txt @@ -90,7 +90,7 @@ PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSYS_NAME}/${SUBSUBSYS_NAME}/pipeline/ set(LIB_NAME "pcl_${SUBSUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSUBSYS_NAME} SOURCES ${srcs} ${impl_incs_pipeline} ${incs_utils} ${incs_fw} ${incs_fw_global} ${incs_fw_local} ${incc_tools_framework} ${incs_pipelines} ${incs_pc_source}) -target_link_libraries("${LIB_NAME}" pcl_apps pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search) +target_link_libraries("${LIB_NAME}" pcl_apps pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search pcl_registration) if(WITH_OPENNI) target_link_libraries("${LIB_NAME}" ${OPENNI_LIBRARIES}) diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index 4c88a7ab121..670f2d8fac1 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -92,7 +92,7 @@ if(VTK_FOUND) src/manual_registration/pcl_viewer_dialog.ui BUNDLE) - target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets) + target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface pcl_registration ${QTX}::Widgets) PCL_ADD_EXECUTABLE(pcl_pcd_video_player COMPONENT diff --git a/registration/include/pcl/registration/icp.h b/registration/include/pcl/registration/icp.h index bca1eaf3fc2..8127b10d029 100644 --- a/registration/include/pcl/registration/icp.h +++ b/registration/include/pcl/registration/icp.h @@ -47,7 +47,8 @@ #include #include #include -#include // for dynamic_pointer_cast, pcl::make_shared, shared_ptr +#include // for dynamic_pointer_cast, pcl::make_shared, shared_ptr +#include // for PCL_NO_PRECOMPILE namespace pcl { /** \brief @b IterativeClosestPoint provides a base implementation of the Iterative @@ -447,3 +448,9 @@ class IterativeClosestPointWithNormals } // namespace pcl #include + +#if !defined(PCL_NO_PRECOMPILE) && !defined(PCL_REGISTRATION_ICP_CPP_) +extern template class pcl::IterativeClosestPoint; +extern template class pcl::IterativeClosestPoint; +extern template class pcl::IterativeClosestPoint; +#endif // PCL_NO_PRECOMPILE diff --git a/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index d91f7e367a0..f9c56ea59a2 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -42,6 +42,7 @@ #include #include +#include // for PCL_NO_PRECOMPILE namespace pcl { namespace registration { @@ -154,3 +155,13 @@ class TransformationEstimationSVD } // namespace pcl #include + +#if !defined(PCL_NO_PRECOMPILE) && \ + !defined(PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_CPP_) +extern template class pcl::registration::TransformationEstimationSVD; +extern template class pcl::registration::TransformationEstimationSVD; +extern template class pcl::registration::TransformationEstimationSVD; +#endif // PCL_NO_PRECOMPILE diff --git a/registration/src/icp.cpp b/registration/src/icp.cpp index 0b2f60b4183..0ca020475f8 100644 --- a/registration/src/icp.cpp +++ b/registration/src/icp.cpp @@ -37,4 +37,15 @@ * */ +#define PCL_REGISTRATION_ICP_CPP_ #include +#include // for PCL_NO_PRECOMPILE + +#ifndef PCL_NO_PRECOMPILE +#include // for PCL_EXPORTS +#include +template class PCL_EXPORTS pcl::IterativeClosestPoint; +template class PCL_EXPORTS pcl::IterativeClosestPoint; +template class PCL_EXPORTS + pcl::IterativeClosestPoint; +#endif // PCL_NO_PRECOMPILE diff --git a/registration/src/transformation_estimation_svd.cpp b/registration/src/transformation_estimation_svd.cpp index 29895a6c378..674c2da5f93 100644 --- a/registration/src/transformation_estimation_svd.cpp +++ b/registration/src/transformation_estimation_svd.cpp @@ -36,4 +36,17 @@ * */ +#define PCL_REGISTRATION_TRANSFORMATION_ESTIMATION_SVD_CPP_ #include +#include // for PCL_NO_PRECOMPILE + +#ifndef PCL_NO_PRECOMPILE +#include // for PCL_EXPORTS +#include +template class PCL_EXPORTS + pcl::registration::TransformationEstimationSVD; +template class PCL_EXPORTS + pcl::registration::TransformationEstimationSVD; +template class PCL_EXPORTS + pcl::registration::TransformationEstimationSVD; +#endif // PCL_NO_PRECOMPILE From c0c00648e15a34016deec49fb0cfb16e659e62a0 Mon Sep 17 00:00:00 2001 From: 3Descape Date: Fri, 8 Dec 2023 17:30:27 +0100 Subject: [PATCH 166/288] Use real ALIAS(cmake >=3.18) target for flann to preserve properties on original target. (#5861) * Use real ALIAS target for flann to preserve properties on original target. With the current method all properties set on the flann::flann_cpp and flann::flann_cpp target are lost, as they are not copied to the new FLANN::FLANN interface target. However, there are cases, where we would like preserve these, e.g. to keep the INTERFACE_INCLUDE_DIRECTORIES property that includes the path to the LZ4 headers. Therefore this patch first checks for the appropriate SHARED or STATIC version and then aliases FLANN::FLANN to the respective library. * Use appropriate comparison operator Co-authored-by: Lars Glud * Only use ALIAS Target for CMAKE >= 3.18 * Use appropriate comparison operator Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --------- Co-authored-by: Lars Glud Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- cmake/Modules/FindFLANN.cmake | 26 +++++++++++++++++--------- 1 file changed, 17 insertions(+), 9 deletions(-) diff --git a/cmake/Modules/FindFLANN.cmake b/cmake/Modules/FindFLANN.cmake index 16ee72fbe8a..f42bca3f76e 100644 --- a/cmake/Modules/FindFLANN.cmake +++ b/cmake/Modules/FindFLANN.cmake @@ -48,33 +48,41 @@ if(flann_FOUND) unset(flann_FOUND) set(FLANN_FOUND ON) - # Create interface library that effectively becomes an alias for the appropriate (static/dynamic) imported FLANN target - add_library(FLANN::FLANN INTERFACE IMPORTED) - if(TARGET flann::flann_cpp_s AND TARGET flann::flann_cpp) if(PCL_FLANN_REQUIRED_TYPE MATCHES "SHARED") - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp) set(FLANN_LIBRARY_TYPE SHARED) elseif(PCL_FLANN_REQUIRED_TYPE MATCHES "STATIC") - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s) set(FLANN_LIBRARY_TYPE STATIC) else() if(PCL_SHARED_LIBS) - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp) set(FLANN_LIBRARY_TYPE SHARED) else() - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s) set(FLANN_LIBRARY_TYPE STATIC) endif() endif() elseif(TARGET flann::flann_cpp_s) - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s) set(FLANN_LIBRARY_TYPE STATIC) else() - set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp) set(FLANN_LIBRARY_TYPE SHARED) endif() + if(CMAKE_VERSION VERSION_LESS 3.18.0) + # Create interface library that effectively becomes an alias for the appropriate (static/dynamic) imported FLANN target + add_library(FLANN::FLANN INTERFACE IMPORTED) + + if(FLANN_LIBRARY_TYPE MATCHES SHARED) + set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp) + else() + set_property(TARGET FLANN::FLANN APPEND PROPERTY INTERFACE_LINK_LIBRARIES flann::flann_cpp_s) + endif() + else() + if(FLANN_LIBRARY_TYPE MATCHES SHARED) + add_library(FLANN::FLANN ALIAS flann::flann_cpp) + else() + add_library(FLANN::FLANN ALIAS flann::flann_cpp_s) + endif() + endif() + # Determine FLANN installation root based on the path to the processed Config file get_filename_component(_config_dir "${flann_CONFIG}" DIRECTORY) get_filename_component(FLANN_ROOT "${_config_dir}/../../.." ABSOLUTE) From 69a2392e4c5976bd4dc1e33cc4659fa210f68485 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 16 Dec 2023 11:43:56 +0100 Subject: [PATCH 167/288] Remove default(none) clause in some OpenMP for-loops clang 17 complains that in these loops, some variables do not have an explicitly defined data sharing attribute, e.g. `Eigen::Dynamic` (which is a `const int`). Explicitly defining it as shared would be weird since the use of `Eigen::Dynamic` is not obvious in those loops, and would also likely lead to problems with other compilers because const variables are implicitly shared (at least in OpenMP versions < 4.0), and defining them explicitly as shared leads to compiler errors (see also http://jakascorner.com/blog/2016/07/omp-default-none-and-const.html). Removing default(none) solves the problem. Generally, the use of default(none) is recommended while writing the code because it forces the programmer to think about whether each variable should be shared or private, but since the code is already finished, removing default(none) should have no downsides. --- .../3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp | 1 - .../3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp | 1 - .../pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp | 1 - common/src/range_image.cpp | 1 - keypoints/include/pcl/keypoints/impl/harris_3d.hpp | 1 - keypoints/src/narf_keypoint.cpp | 1 - tools/fast_bilateral_filter.cpp | 1 - tools/normal_estimation.cpp | 1 - 8 files changed, 8 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp index d6ca7cd4f38..bf6607eeae7 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp @@ -297,7 +297,6 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer::reco // clang-format off #pragma omp parallel for \ - default(none) \ shared(VOXEL_SIZE_ICP_, cloud_voxelized_icp) \ num_threads(omp_get_num_procs()) // clang-format on diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp index b3ea5716e9d..fdd83be86d7 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp @@ -456,7 +456,6 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer::rec // clang-format off #pragma omp parallel for \ - default(none) \ shared(cloud_voxelized_icp, VOXEL_SIZE_ICP_) \ num_threads(omp_get_num_procs()) // clang-format on diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp index e2476ef149f..3561c3036cd 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp @@ -371,7 +371,6 @@ pcl::rec_3d_framework::LocalRecognitionPipeline:: // clang-format off #pragma omp parallel for \ - default(none) \ shared(cloud_voxelized_icp) \ schedule(dynamic,1) \ num_threads(omp_get_num_procs()) diff --git a/common/src/range_image.cpp b/common/src/range_image.cpp index 615c753beb2..91ba59bf5fc 100644 --- a/common/src/range_image.cpp +++ b/common/src/range_image.cpp @@ -865,7 +865,6 @@ RangeImage::getOverlap (const RangeImage& other_range_image, const Eigen::Affine float max_distance_squared = max_distance*max_distance; #pragma omp parallel for \ - default(none) \ shared(max_distance_squared, other_range_image, pixel_step, relative_transformation, search_radius) \ schedule(dynamic, 1) \ reduction(+ : valid_points_counter) \ diff --git a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp index 1daf3875056..17c56ef55cf 100644 --- a/keypoints/include/pcl/keypoints/impl/harris_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/harris_3d.hpp @@ -506,7 +506,6 @@ pcl::HarrisKeypoint3D::refineCorners (PointCloudOu Eigen::Vector3f NNTp; constexpr unsigned max_iterations = 10; #pragma omp parallel for \ - default(none) \ shared(corners) \ firstprivate(nnT, NNT, NNTp) \ num_threads(threads_) diff --git a/keypoints/src/narf_keypoint.cpp b/keypoints/src/narf_keypoint.cpp index 088bcbceca6..35d5811d34a 100644 --- a/keypoints/src/narf_keypoint.cpp +++ b/keypoints/src/narf_keypoint.cpp @@ -478,7 +478,6 @@ NarfKeypoint::calculateSparseInterestImage () //double interest_value_calculation_start_time = getTime (); #pragma omp parallel for \ - default(none) \ shared(array_size, border_descriptions, increased_radius_squared, radius_reciprocal, radius_overhead_squared, range_image, search_radius, \ surface_change_directions, surface_change_scores) \ num_threads(parameters_.max_no_of_threads) \ diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index 0c3d8d2fa8c..8ec876ceeb7 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -114,7 +114,6 @@ int batchProcess (const std::vector &pcd_files, std::string &output_dir, float sigma_s, float sigma_r) { #pragma omp parallel for \ - default(none) \ shared(output_dir, pcd_files, sigma_r, sigma_s) // Disable lint since this 'for' is part of the pragma // NOLINTNEXTLINE(modernize-loop-convert) diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index aee26bf2aeb..49f69d66207 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -133,7 +133,6 @@ int batchProcess (const std::vector &pcd_files, std::string &output_dir, int k, double radius) { #pragma omp parallel for \ - default(none) \ shared(k, output_dir, pcd_files, radius) // Disable lint since this 'for' is part of the pragma // NOLINTNEXTLINE(modernize-loop-convert) From c1c907f842e6e5eced7382d7e1a983fa2a3810c2 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 16 Dec 2023 15:25:18 +0100 Subject: [PATCH 168/288] CI: install libomp-dev to make OpenMP available for Clang --- .ci/azure-pipelines/ubuntu-variety.yaml | 2 +- .dev/docker/env/Dockerfile | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml index e836a655c7b..24f34dbe349 100644 --- a/.ci/azure-pipelines/ubuntu-variety.yaml +++ b/.ci/azure-pipelines/ubuntu-variety.yaml @@ -32,7 +32,7 @@ jobs: POSSIBLE_VTK_VERSION=("9") \ POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \ POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \ - POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \ + POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang libomp-dev" "clang-13 libomp-13-dev" "clang-14 libomp-14-dev" "clang-15 libomp-15-dev" "clang-16 libomp-16-dev" "clang-17 libomp-17-dev") \ POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \ POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16" "clang++-17") \ CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \ diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index 75dc31f048c..27579269a1f 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -37,6 +37,7 @@ RUN apt-get update \ libflann-dev \ libglew-dev \ libgtest-dev \ + libomp-dev \ libopenni-dev \ libopenni2-dev \ libpcap-dev \ From 95f8d3ec6896c3b4685248110008276ebb610a1c Mon Sep 17 00:00:00 2001 From: Kino Date: Mon, 18 Dec 2023 03:27:33 +0800 Subject: [PATCH 169/288] replace deprecated boost filesystem basename (#5901) * replace deprecated boost filesystem basename * try to address CI clang-tidy issues * address CI clang-tidy issues * fix Windows build errors --- .../tools/standalone_texture_mapping.cpp | 2 +- io/src/image_grabber.cpp | 16 ++++++++-------- .../include/pcl/outofcore/impl/octree_base.hpp | 4 ++-- .../pcl/outofcore/impl/octree_base_node.hpp | 2 +- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index d1570464c87..e80b4cfc969 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -440,7 +440,7 @@ main (int argc, char** argv) { pcl::TextureMapping::Camera cam; readCamPoseFile(it->path ().string (), cam); - cam.texture_file = boost::filesystem::basename (it->path ()) + ".png"; + cam.texture_file = it->path ().stem ().string () + ".png"; my_cams.push_back (cam); } } diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 99511ec719c..53ff413e014 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -269,7 +269,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string { extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); pathname = itr->path ().string (); - basename = boost::filesystem::basename (itr->path ()); + basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) && isValidExtension (extension)) { @@ -312,7 +312,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string { extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); pathname = itr->path ().string (); - basename = boost::filesystem::basename (itr->path ()); + basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) && isValidExtension (extension)) { @@ -327,7 +327,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string { extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); pathname = itr->path ().string (); - basename = boost::filesystem::basename (itr->path ()); + basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) && isValidExtension (extension)) { @@ -368,7 +368,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir) { extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); pathname = itr->path ().string (); - basename = boost::filesystem::basename (itr->path ()); + basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) && isValidExtension (extension)) { @@ -429,7 +429,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getTimestampFromFilepath ( { // For now, we assume the file is of the form frame_[22-char POSIX timestamp]_* char timestamp_str[256]; - int result = std::sscanf (boost::filesystem::basename (filepath).c_str (), + int result = std::sscanf (boost::filesystem::path (filepath).stem ().string ().c_str (), "frame_%22s_%*s", timestamp_str); if (result > 0) @@ -971,7 +971,7 @@ pcl::ImageGrabberBase::getCurrentDepthFileName () const pathname = impl_->depth_pclzf_files_[impl_->cur_frame_]; else pathname = impl_->depth_image_files_[impl_->cur_frame_]; - std::string basename = boost::filesystem::basename (pathname); + std::string basename = boost::filesystem::path (pathname).stem ().string (); return (basename); } ////////////////////////////////////////////////////////////////////////////////////////// @@ -983,7 +983,7 @@ pcl::ImageGrabberBase::getPrevDepthFileName () const pathname = impl_->depth_pclzf_files_[impl_->cur_frame_-1]; else pathname = impl_->depth_image_files_[impl_->cur_frame_-1]; - std::string basename = boost::filesystem::basename (pathname); + std::string basename = boost::filesystem::path (pathname).stem ().string (); return (basename); } @@ -996,7 +996,7 @@ pcl::ImageGrabberBase::getDepthFileNameAtIndex (std::size_t idx) const pathname = impl_->depth_pclzf_files_[idx]; else pathname = impl_->depth_image_files_[idx]; - std::string basename = boost::filesystem::basename (pathname); + std::string basename = boost::filesystem::path (pathname).stem ().string (); return (basename); } diff --git a/outofcore/include/pcl/outofcore/impl/octree_base.hpp b/outofcore/include/pcl/outofcore/impl/octree_base.hpp index 257f620ea9d..958d27f2bca 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base.hpp @@ -93,7 +93,7 @@ namespace pcl root_node_->m_tree_ = this; // Set the path to the outofcore octree metadata (unique to the root folder) ending in .octree - boost::filesystem::path treepath = root_name.parent_path () / (boost::filesystem::basename (root_name) + TREE_EXTENSION_); + boost::filesystem::path treepath = root_name.parent_path () / (root_name.stem ().string () + TREE_EXTENSION_); //Load the JSON metadata metadata_->loadMetadataFromDisk (treepath); @@ -169,7 +169,7 @@ namespace pcl root_node_->m_tree_ = this; // Set root nodes file path - boost::filesystem::path treepath = dir / (boost::filesystem::basename (root_name) + TREE_EXTENSION_); + boost::filesystem::path treepath = dir / (root_name.stem ().string () + TREE_EXTENSION_); //fill the fields of the metadata metadata_->setCoordinateSystem (coord_sys); diff --git a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp index 8d947d8f4b8..1b2e9d02ddb 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp @@ -1937,7 +1937,7 @@ namespace pcl template void OutofcoreOctreeBaseNode::convertToXYZRecursive () { - std::string fname = boost::filesystem::basename (node_metadata_->getPCDFilename ()) + std::string (".dat.xyz"); + std::string fname = node_metadata_->getPCDFilename ().stem ().string () + ".dat.xyz"; boost::filesystem::path xyzfile = node_metadata_->getDirectoryPathname () / fname; payload_->convertToXYZ (xyzfile); From eccdbe814fa3b686ba910f9184e79a2ebd491ae3 Mon Sep 17 00:00:00 2001 From: Kino Date: Wed, 20 Dec 2023 17:59:22 +0800 Subject: [PATCH 170/288] replace deprecated boost filesystem extension (#5904) * replace deprecated boost filesystem extension * fix format error * replace more boost extension functions --- apps/in_hand_scanner/src/offline_integration.cpp | 2 +- .../content/sources/vfh_recognition/build_tree.cpp | 2 +- gpu/kinfu/tools/kinfu_app.cpp | 2 +- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 2 +- .../tools/standalone_texture_mapping.cpp | 2 +- gpu/people/tools/people_app.cpp | 2 +- io/src/ascii_io.cpp | 2 +- io/src/image_grabber.cpp | 8 ++++---- outofcore/include/pcl/outofcore/impl/octree_base.hpp | 4 ++-- outofcore/include/pcl/outofcore/impl/octree_base_node.hpp | 4 ++-- outofcore/tools/outofcore_print.cpp | 2 +- outofcore/tools/outofcore_viewer.cpp | 2 +- test/io/test_grabbers.cpp | 2 +- tools/fast_bilateral_filter.cpp | 2 +- tools/grid_min.cpp | 2 +- tools/local_max.cpp | 2 +- tools/morph.cpp | 2 +- tools/normal_estimation.cpp | 2 +- tools/passthrough_filter.cpp | 2 +- tools/pcd_grabber_viewer.cpp | 2 +- tools/progressive_morphological_filter.cpp | 2 +- tools/radius_filter.cpp | 2 +- tools/sac_segmentation_plane.cpp | 2 +- tools/unary_classifier_segment.cpp | 2 +- tools/uniform_sampling.cpp | 2 +- tools/virtual_scanner.cpp | 4 ++-- 26 files changed, 32 insertions(+), 32 deletions(-) diff --git a/apps/in_hand_scanner/src/offline_integration.cpp b/apps/in_hand_scanner/src/offline_integration.cpp index 113a499274e..853232dc7f6 100644 --- a/apps/in_hand_scanner/src/offline_integration.cpp +++ b/apps/in_hand_scanner/src/offline_integration.cpp @@ -195,7 +195,7 @@ pcl::ihs::OfflineIntegration::getFilesFromDirectory( boost::filesystem::directory_iterator it_end; for (boost::filesystem::directory_iterator it(path_dir); it != it_end; ++it) { if (!is_directory(it->status()) && - boost::algorithm::to_upper_copy(boost::filesystem::extension(it->path())) == + boost::algorithm::to_upper_copy(it->path().extension().string()) == boost::algorithm::to_upper_copy(extension)) { files.push_back(it->path().string()); } diff --git a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp index ecc6cf3e8a6..5ecb2325af5 100644 --- a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp @@ -78,7 +78,7 @@ loadFeatureModels (const boost::filesystem::path &base_dir, const std::string &e pcl::console::print_highlight ("Loading %s (%lu models loaded so far).\n", ss.str ().c_str (), (unsigned long)models.size ()); loadFeatureModels (it->path (), extension, models); } - if (boost::filesystem::is_regular_file (it->status ()) && boost::filesystem::extension (it->path ()) == extension) + if (boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) { vfh_model m; if (loadHist (base_dir / it->path ().filename (), m)) diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index af65de9337f..ffdb154ffaa 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -186,7 +186,7 @@ std::vector getPcdFilesInDir(const std::string& directory) for(; pos != end ; ++pos) if (fs::is_regular_file(pos->status()) ) - if (fs::extension(*pos) == ".pcd") + if (pos->path().extension().string() == ".pcd") { result.push_back (pos->path ().string ()); std::cout << "added: " << result.back() << std::endl; diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index f923dd0559f..28278195e42 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -136,7 +136,7 @@ std::vector getPcdFilesInDir(const std::string& directory) for(; pos != end ; ++pos) if (fs::is_regular_file(pos->status()) ) - if (fs::extension(*pos) == ".pcd") + if (pos->path().extension().string() == ".pcd") { result.push_back (pos->path ().string ()); std::cout << "added: " << result.back() << std::endl; diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index e80b4cfc969..6803bba3e3d 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -436,7 +436,7 @@ main (int argc, char** argv) std::string extension (".txt"); for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it) { - if(boost::filesystem::is_regular_file (it->status ()) && boost::filesystem::extension (it->path ()) == extension) + if(boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) { pcl::TextureMapping::Camera cam; readCamPoseFile(it->path ().string (), cam); diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index fe6f3fefa64..91308e4e263 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -78,7 +78,7 @@ std::vector getPcdFilesInDir(const std::string& directory) for(; pos != end ; ++pos) if (fs::is_regular_file(pos->status()) ) - if (fs::extension(*pos) == ".pcd") + if (pos->path().extension().string() == ".pcd") result.push_back(pos->path().string()); return result; diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index 9803c7f3322..486ef5aba18 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -95,7 +95,7 @@ pcl::ASCIIReader::readHeader (const std::string& file_name, PCL_ERROR ("[%s] File %s does not exist.\n", name_.c_str (), file_name.c_str ()); return (-1); } - if (boost::filesystem::extension (fpath) != extension_) + if (fpath.extension ().string () != extension_) { PCL_ERROR ("[%s] File does not have %s extension. \n", name_.c_str(), extension_.c_str()); return -1; diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 53ff413e014..de32f1f20de 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -267,7 +267,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string boost::filesystem::directory_iterator end_itr; for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr) { - extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); + extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) @@ -310,7 +310,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string // First iterate over depth images for (boost::filesystem::directory_iterator itr (depth_dir); itr != end_itr; ++itr) { - extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); + extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) @@ -325,7 +325,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string // Then iterate over RGB images for (boost::filesystem::directory_iterator itr (rgb_dir); itr != end_itr; ++itr) { - extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); + extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) @@ -366,7 +366,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir) boost::filesystem::directory_iterator end_itr; for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr) { - extension = boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())); + extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); if (!boost::filesystem::is_directory (itr->status ()) diff --git a/outofcore/include/pcl/outofcore/impl/octree_base.hpp b/outofcore/include/pcl/outofcore/impl/octree_base.hpp index 958d27f2bca..f3a8e6f3f0b 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base.hpp @@ -699,9 +699,9 @@ namespace pcl template bool OutofcoreOctreeBase::checkExtension (const boost::filesystem::path& path_name) { - if (boost::filesystem::extension (path_name) != OutofcoreOctreeBaseNode::node_index_extension) + if (path_name.extension ().string () != OutofcoreOctreeBaseNode::node_index_extension) { - PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBase] Wrong root node file extension: %s. The tree must have a root node ending in %s\n", boost::filesystem::extension (path_name).c_str (), OutofcoreOctreeBaseNode::node_index_extension.c_str () ); + PCL_ERROR ( "[pcl::outofcore::OutofcoreOctreeBase] Wrong root node file extension: %s. The tree must have a root node ending in %s\n", path_name.extension ().string ().c_str (), OutofcoreOctreeBaseNode::node_index_extension.c_str () ); return (false); } diff --git a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp index 1b2e9d02ddb..53778768ac8 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp @@ -151,7 +151,7 @@ namespace pcl if (!boost::filesystem::is_directory (file)) { - if (boost::filesystem::extension (file) == node_index_extension) + if (file.extension ().string () == node_index_extension) { b_loaded = node_metadata_->loadMetadataFromDisk (file); break; @@ -2050,7 +2050,7 @@ namespace pcl const boost::filesystem::path& file = *diter; if (!boost::filesystem::is_directory (file)) { - if (boost::filesystem::extension (file) == OutofcoreOctreeBaseNode::node_index_extension) + if (file.extension ().string () == OutofcoreOctreeBaseNode::node_index_extension) { thisnode->thisnodeindex_ = file; loaded = true; diff --git a/outofcore/tools/outofcore_print.cpp b/outofcore/tools/outofcore_print.cpp index 71b51934a28..885a8707697 100644 --- a/outofcore/tools/outofcore_print.cpp +++ b/outofcore/tools/outofcore_print.cpp @@ -299,7 +299,7 @@ main (int argc, char* argv[]) const boost::filesystem::path& file = *diter; if (!boost::filesystem::is_directory (file)) { - if (boost::filesystem::extension (file) == OctreeDiskNode::node_index_extension) + if (file.extension ().string () == OctreeDiskNode::node_index_extension) { tree_root = file; } diff --git a/outofcore/tools/outofcore_viewer.cpp b/outofcore/tools/outofcore_viewer.cpp index 795e03d7598..1a5c4775c1e 100644 --- a/outofcore/tools/outofcore_viewer.cpp +++ b/outofcore/tools/outofcore_viewer.cpp @@ -382,7 +382,7 @@ main (int argc, char* argv[]) const boost::filesystem::path& file = *diter; if (!boost::filesystem::is_directory (file)) { - if (boost::filesystem::extension (file) == octree_disk_node::node_index_extension) + if (file.extension ().string () == octree_disk_node::node_index_extension) { tree_root = file; } diff --git a/test/io/test_grabbers.cpp b/test/io/test_grabbers.cpp index a7c794aad00..09185f9f8d2 100644 --- a/test/io/test_grabbers.cpp +++ b/test/io/test_grabbers.cpp @@ -522,7 +522,7 @@ int boost::filesystem::directory_iterator end_itr; for (boost::filesystem::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr) { - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files_.push_back (itr->path ().string ()); std::cout << "added: " << itr->path ().string () << std::endl; diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index 8ec876ceeb7..ff9d49544a3 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -210,7 +210,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/grid_min.cpp b/tools/grid_min.cpp index 5111500a447..1a5c2fa913a 100644 --- a/tools/grid_min.cpp +++ b/tools/grid_min.cpp @@ -202,7 +202,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/local_max.cpp b/tools/local_max.cpp index e803aa31017..665aee3759c 100644 --- a/tools/local_max.cpp +++ b/tools/local_max.cpp @@ -203,7 +203,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/morph.cpp b/tools/morph.cpp index bf998ca26bc..7c33cdbd2fa 100644 --- a/tools/morph.cpp +++ b/tools/morph.cpp @@ -226,7 +226,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index 49f69d66207..149427c3d68 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -229,7 +229,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/passthrough_filter.cpp b/tools/passthrough_filter.cpp index c8f153131e6..f79a87f0d63 100644 --- a/tools/passthrough_filter.cpp +++ b/tools/passthrough_filter.cpp @@ -218,7 +218,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/pcd_grabber_viewer.cpp b/tools/pcd_grabber_viewer.cpp index f1ca85a7a24..b8216c3a82a 100644 --- a/tools/pcd_grabber_viewer.cpp +++ b/tools/pcd_grabber_viewer.cpp @@ -193,7 +193,7 @@ main (int argc, char** argv) boost::filesystem::directory_iterator end_itr; for (boost::filesystem::directory_iterator itr (path); itr != end_itr; ++itr) { - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); std::cout << "added: " << itr->path ().string () << std::endl; diff --git a/tools/progressive_morphological_filter.cpp b/tools/progressive_morphological_filter.cpp index 8a0bab0526a..943d5657c9d 100644 --- a/tools/progressive_morphological_filter.cpp +++ b/tools/progressive_morphological_filter.cpp @@ -304,7 +304,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/radius_filter.cpp b/tools/radius_filter.cpp index 3ab8e3b7d9a..be5c50dbd8b 100644 --- a/tools/radius_filter.cpp +++ b/tools/radius_filter.cpp @@ -208,7 +208,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/sac_segmentation_plane.cpp b/tools/sac_segmentation_plane.cpp index 38e2091549d..45554684055 100644 --- a/tools/sac_segmentation_plane.cpp +++ b/tools/sac_segmentation_plane.cpp @@ -283,7 +283,7 @@ main (int argc, char** argv) for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files - if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" ) + if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { pcd_files.push_back (itr->path ().string ()); PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ()); diff --git a/tools/unary_classifier_segment.cpp b/tools/unary_classifier_segment.cpp index 1a9c6e06fb5..cdec686d155 100644 --- a/tools/unary_classifier_segment.cpp +++ b/tools/unary_classifier_segment.cpp @@ -84,7 +84,7 @@ loadTrainedFeatures (std::vector &out, for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it) { if (!boost::filesystem::is_directory (it->status ()) && - boost::filesystem::extension (it->path ()) == ".pcd") + it->path ().extension ().string () == ".pcd") { const std::string path = it->path ().string (); diff --git a/tools/uniform_sampling.cpp b/tools/uniform_sampling.cpp index 2d92fd41f24..269552b16aa 100644 --- a/tools/uniform_sampling.cpp +++ b/tools/uniform_sampling.cpp @@ -129,7 +129,7 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output) PCDWriter w_pcd; PLYWriter w_ply; - std::string output_ext = boost::filesystem::extension (filename); + std::string output_ext = boost::filesystem::path (filename).extension ().string (); std::transform (output_ext.begin (), output_ext.end (), output_ext.begin (), ::tolower); if (output_ext == ".pcd") diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index d51937acbc0..d339a88413d 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -64,7 +64,7 @@ #include #include // for boost::is_any_of, boost::split, boost::token_compress_on, boost::trim -#include // for boost::filesystem::create_directories, boost::filesystem::exists, boost::filesystem::extension, boost::filesystem::path +#include // for boost::filesystem::create_directories, boost::filesystem::exists, boost::filesystem::path, boost::filesystem::path::extension using namespace pcl; @@ -87,7 +87,7 @@ struct ScanParameters vtkPolyData* loadDataSet (const char* file_name) { - std::string extension = boost::filesystem::extension (file_name); + std::string extension = boost::filesystem::path (file_name).extension ().string (); if (extension == ".ply") { vtkPLYReader* reader = vtkPLYReader::New (); From c750d074cdc5fbb5382ff302ba9afe43ce51a101 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 20 Dec 2023 20:46:47 +0100 Subject: [PATCH 171/288] Make PCL compatible with Boost 1.84 --- PCLConfig.cmake.in | 2 +- cmake/pcl_find_boost.cmake | 2 +- io/src/ply/ply_parser.cpp | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 1c8a1bd59c9..cf21c443742 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -96,7 +96,7 @@ macro(find_boost) set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" - "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" + "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index fb9ef5b71a1..770607f82dc 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -14,7 +14,7 @@ else() endif() set(Boost_ADDITIONAL_VERSIONS - "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" + "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/io/src/ply/ply_parser.cpp b/io/src/ply/ply_parser.cpp index 335c0fb1808..7e79d2d6162 100644 --- a/io/src/ply/ply_parser.cpp +++ b/io/src/ply/ply_parser.cpp @@ -40,6 +40,7 @@ #include +#include // for find_if #include // for ifstream #include // for istringstream From 4a389e1781498dd237a661713415bdf6669e8a27 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Thu, 21 Dec 2023 02:31:07 -0800 Subject: [PATCH 172/288] Part H of transition to support modernize-use-default-member-init (#5899) * Part H of transition to support modernize-use-default-member-init * Updated per inspection * Corrected formatting complaints * Addressed CI clang-tidy issues * Fixed another CI clang-tidy complaint * Fixed yet more CI clang-tidy issues * Made changes per review * Fixed some typos * Addressed more review changes * Fixed new clang-tidy CI complaints * Fixed clang-format CI complaint * Fixed another piecemeal clang-format complaint * Made more changes per review * Fixed missed review comment --- .clang-tidy | 2 + features/include/pcl/features/cvfh.h | 2 +- features/include/pcl/features/impl/esf.hpp | 24 +++--- io/include/pcl/io/ensenso_grabber.h | 6 +- io/include/pcl/io/openni2/openni2_device.h | 12 +-- io/include/pcl/io/openni2_grabber.h | 57 +++++++------ io/include/pcl/io/real_sense_2_grabber.h | 12 +-- io/src/ensenso_grabber.cpp | 5 +- io/src/openni2/openni2_device.cpp | 5 +- io/src/openni2_grabber.cpp | 18 ---- io/src/real_sense_2_grabber.cpp | 6 -- .../include/pcl/keypoints/impl/iss_3d.hpp | 2 +- keypoints/include/pcl/keypoints/keypoint.h | 4 +- ml/include/pcl/ml/svm_wrapper.h | 2 +- octree/include/pcl/octree/octree_pointcloud.h | 8 +- .../3rdparty/metslib/abstract-search.hh | 4 +- .../3rdparty/metslib/simulated-annealing.hh | 3 +- ...correspondence_rejection_median_distance.h | 2 +- .../correspondence_rejection_var_trimmed.h | 2 +- .../include/pcl/registration/impl/ia_fpcs.hpp | 2 +- .../segmentation/extract_labeled_clusters.h | 2 +- .../extract_polygonal_prism_data.h | 2 +- .../pcl/segmentation/grabcut_segmentation.h | 22 ++--- .../pcl/segmentation/lccp_segmentation.h | 4 +- .../pcl/segmentation/sac_segmentation.h | 4 +- .../segmentation/seeded_hue_segmentation.h | 4 +- .../pcl/segmentation/supervoxel_clustering.h | 2 +- .../pcl/surface/bilateral_upsampling.h | 9 +- surface/include/pcl/surface/concave_hull.h | 12 ++- surface/include/pcl/surface/convex_hull.h | 26 +++--- surface/include/pcl/surface/gp3.h | 83 +++++++------------ surface/include/pcl/surface/impl/mls.hpp | 2 +- surface/include/pcl/surface/impl/poisson.hpp | 24 +----- surface/include/pcl/surface/mls.h | 61 ++++++-------- .../include/pcl/surface/organized_fast_mesh.h | 42 ++++------ surface/include/pcl/surface/poisson.h | 44 +++++----- surface/include/pcl/surface/reconstruction.h | 8 +- surface/include/pcl/surface/texture_mapping.h | 30 +++---- .../vtk_mesh_quadric_decimation.h | 2 +- .../vtk_mesh_smoothing_laplacian.h | 24 ++---- .../vtk_mesh_smoothing_windowed_sinc.h | 24 ++---- .../vtk_smoothing/vtk_mesh_subdivision.h | 2 +- .../vtk_mesh_quadric_decimation.cpp | 5 +- .../vtk_smoothing/vtk_mesh_subdivision.cpp | 5 +- tools/openni2_viewer.cpp | 13 ++- tools/ply2obj.cpp | 2 +- tools/ply2raw.cpp | 2 +- .../include/pcl/tracking/distance_coherence.h | 4 +- .../tracking/kld_adaptive_particle_filter.h | 12 +-- .../nearest_pair_point_cloud_coherence.h | 7 +- .../include/pcl/tracking/normal_coherence.h | 4 +- .../include/pcl/tracking/particle_filter.h | 72 ++++++---------- .../pcl/visualization/common/actor_map.h | 6 +- .../pcl/visualization/histogram_visualizer.h | 6 +- .../include/pcl/visualization/image_viewer.h | 18 ++-- .../pcl/visualization/interactor_style.h | 35 ++++---- .../pcl/visualization/keyboard_event.h | 6 +- .../include/pcl/visualization/mouse_event.h | 6 +- .../pcl/visualization/pcl_visualizer.h | 14 ++-- .../visualization/registration_visualizer.h | 8 +- .../include/pcl/visualization/window.h | 10 +-- visualization/src/cloud_viewer.cpp | 10 +-- visualization/src/histogram_visualizer.cpp | 3 +- visualization/src/image_viewer.cpp | 6 +- visualization/src/pcl_visualizer.cpp | 8 -- visualization/src/window.cpp | 15 +--- 66 files changed, 352 insertions(+), 536 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 86977bd23a9..b4a145f8353 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -12,6 +12,8 @@ Checks: > modernize-return-braced-init-list, modernize-shrink-to-fit, modernize-use-auto, + modernize-use-bool-literals, + modernize-use-default-member-init, modernize-use-emplace, modernize-use-equals-default, modernize-use-equals-delete, diff --git a/features/include/pcl/features/cvfh.h b/features/include/pcl/features/cvfh.h index 1c6b0ed3a73..1fc498e9455 100644 --- a/features/include/pcl/features/cvfh.h +++ b/features/include/pcl/features/cvfh.h @@ -212,7 +212,7 @@ namespace pcl /** \brief Values describing the viewpoint ("pinhole" camera model assumed). * By default, the viewpoint is set to 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Size of the voxels after voxel gridding. IMPORTANT: Must match the voxel * size of the training data or the normalize_bins_ flag must be set to true. diff --git a/features/include/pcl/features/impl/esf.hpp b/features/include/pcl/features/impl/esf.hpp index 9f17be2ffad..f36826f5d19 100644 --- a/features/include/pcl/features/impl/esf.hpp +++ b/features/include/pcl/features/impl/esf.hpp @@ -66,18 +66,18 @@ pcl::ESFEstimation::computeESF ( wt_d2.reserve (sample_size * 3); wt_d3.reserve (sample_size); - float h_in[binsize] = {0}; - float h_out[binsize] = {0}; - float h_mix[binsize] = {0}; - float h_mix_ratio[binsize] = {0}; - - float h_a3_in[binsize] = {0}; - float h_a3_out[binsize] = {0}; - float h_a3_mix[binsize] = {0}; - - float h_d3_in[binsize] = {0}; - float h_d3_out[binsize] = {0}; - float h_d3_mix[binsize] = {0}; + float h_in[binsize] = {0.0f}; + float h_out[binsize] = {0.0f}; + float h_mix[binsize] = {0.0f}; + float h_mix_ratio[binsize] = {0.0f}; + + float h_a3_in[binsize] = {0.0f}; + float h_a3_out[binsize] = {0.0f}; + float h_a3_mix[binsize] = {0.0f}; + + float h_d3_in[binsize] = {0.0f}; + float h_d3_out[binsize] = {0.0f}; + float h_d3_mix[binsize] = {0.0f}; float ratio=0.0; float pih = static_cast(M_PI) / 2.0f; diff --git a/io/include/pcl/io/ensenso_grabber.h b/io/include/pcl/io/ensenso_grabber.h index 6fdf84c8b94..213aff53ebf 100644 --- a/io/include/pcl/io/ensenso_grabber.h +++ b/io/include/pcl/io/ensenso_grabber.h @@ -443,13 +443,13 @@ namespace pcl boost::signals2::signal* point_cloud_images_signal_; /** @brief Whether an Ensenso device is opened or not */ - bool device_open_; + bool device_open_{false}; /** @brief Whether an TCP port is opened or not */ - bool tcp_open_; + bool tcp_open_{false}; /** @brief Whether an Ensenso device is running or not */ - bool running_; + bool running_{false}; /** @brief Point cloud capture/processing frequency */ pcl::EventFrequency frequency_; diff --git a/io/include/pcl/io/openni2/openni2_device.h b/io/include/pcl/io/openni2/openni2_device.h index dd462785626..4abb5d28dd1 100644 --- a/io/include/pcl/io/openni2/openni2_device.h +++ b/io/include/pcl/io/openni2/openni2_device.h @@ -315,16 +315,16 @@ namespace pcl mutable std::vector color_video_modes_; mutable std::vector depth_video_modes_; - bool ir_video_started_; - bool color_video_started_; - bool depth_video_started_; + bool ir_video_started_{false}; + bool color_video_started_{false}; + bool depth_video_started_{false}; /** \brief distance between the projector and the IR camera in meters*/ - float baseline_; + float baseline_{0.0f}; /** the value for shadow (occluded pixels) */ - std::uint64_t shadow_value_; + std::uint64_t shadow_value_{0}; /** the value for pixels without a valid disparity measurement */ - std::uint64_t no_sample_value_; + std::uint64_t no_sample_value_{0}; }; PCL_EXPORTS std::ostream& operator<< (std::ostream& stream, const OpenNI2Device& device); diff --git a/io/include/pcl/io/openni2_grabber.h b/io/include/pcl/io/openni2_grabber.h index f4a54f09d0c..e42529b0c46 100644 --- a/io/include/pcl/io/openni2_grabber.h +++ b/io/include/pcl/io/openni2_grabber.h @@ -421,9 +421,9 @@ namespace pcl convertToXYZIPointCloud (const pcl::io::openni2::IRImage::Ptr &image, const pcl::io::openni2::DepthImage::Ptr &depth_image); - std::vector color_resize_buffer_; - std::vector depth_resize_buffer_; - std::vector ir_resize_buffer_; + std::vector color_resize_buffer_{}; + std::vector depth_resize_buffer_{}; + std::vector ir_resize_buffer_{}; // Stream callbacks ///////////////////////////////////////////////////// void @@ -444,25 +444,25 @@ namespace pcl std::string rgb_frame_id_; std::string depth_frame_id_; - unsigned image_width_; - unsigned image_height_; - unsigned depth_width_; - unsigned depth_height_; - - bool image_required_; - bool depth_required_; - bool ir_required_; - bool sync_required_; - - boost::signals2::signal* image_signal_; - boost::signals2::signal* depth_image_signal_; - boost::signals2::signal* ir_image_signal_; - boost::signals2::signal* image_depth_image_signal_; - boost::signals2::signal* ir_depth_image_signal_; - boost::signals2::signal* point_cloud_signal_; - boost::signals2::signal* point_cloud_i_signal_; - boost::signals2::signal* point_cloud_rgb_signal_; - boost::signals2::signal* point_cloud_rgba_signal_; + unsigned image_width_{0}; + unsigned image_height_{0}; + unsigned depth_width_{0}; + unsigned depth_height_{0}; + + bool image_required_{false}; + bool depth_required_{false}; + bool ir_required_{false}; + bool sync_required_{false}; + + boost::signals2::signal* image_signal_{}; + boost::signals2::signal* depth_image_signal_{}; + boost::signals2::signal* ir_image_signal_{}; + boost::signals2::signal* image_depth_image_signal_{}; + boost::signals2::signal* ir_depth_image_signal_{}; + boost::signals2::signal* point_cloud_signal_{}; + boost::signals2::signal* point_cloud_i_signal_{}; + boost::signals2::signal* point_cloud_rgb_signal_{}; + boost::signals2::signal* point_cloud_rgba_signal_{}; struct modeComp { @@ -483,14 +483,13 @@ namespace pcl // Mapping from config (enum) modes to native OpenNI modes std::map config2oni_map_; - pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_; - pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_; - pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_; - bool running_; + pcl::io::openni2::OpenNI2Device::CallbackHandle depth_callback_handle_{}; + pcl::io::openni2::OpenNI2Device::CallbackHandle image_callback_handle_{}; + pcl::io::openni2::OpenNI2Device::CallbackHandle ir_callback_handle_{}; + bool running_{false}; - - CameraParameters rgb_parameters_; - CameraParameters depth_parameters_; + CameraParameters rgb_parameters_{std::numeric_limits::quiet_NaN ()}; + CameraParameters depth_parameters_{std::numeric_limits::quiet_NaN ()}; public: PCL_MAKE_ALIGNED_OPERATOR_NEW diff --git a/io/include/pcl/io/real_sense_2_grabber.h b/io/include/pcl/io/real_sense_2_grabber.h index 646633adadd..50e305a9ae2 100644 --- a/io/include/pcl/io/real_sense_2_grabber.h +++ b/io/include/pcl/io/real_sense_2_grabber.h @@ -199,17 +199,17 @@ namespace pcl /** \brief Repeat playback when reading from file */ bool repeat_playback_; /** \brief controlling the state of the thread. */ - bool quit_; + bool quit_{false}; /** \brief Is the grabber running. */ - bool running_; + bool running_{false}; /** \brief Calculated FPS for the grabber. */ - float fps_; + float fps_{0.0f}; /** \brief Width for the depth and color sensor. Default 424*/ - std::uint32_t device_width_; + std::uint32_t device_width_{424}; /** \brief Height for the depth and color sensor. Default 240 */ - std::uint32_t device_height_; + std::uint32_t device_height_{240}; /** \brief Target FPS for the device. Default 30. */ - std::uint32_t target_fps_; + std::uint32_t target_fps_{30}; /** \brief Declare pointcloud object, for calculating pointclouds and texture mappings */ rs2::pointcloud pc_; /** \brief Declare RealSense pipeline, encapsulating the actual device and sensors */ diff --git a/io/src/ensenso_grabber.cpp b/io/src/ensenso_grabber.cpp index 1b3b6f09546..68feed4f43e 100644 --- a/io/src/ensenso_grabber.cpp +++ b/io/src/ensenso_grabber.cpp @@ -62,10 +62,7 @@ ensensoExceptionHandling (const NxLibException& ex, } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -pcl::EnsensoGrabber::EnsensoGrabber () : - device_open_ (false), - tcp_open_ (false), - running_ (false) +pcl::EnsensoGrabber::EnsensoGrabber () { point_cloud_signal_ = createSignal (); images_signal_ = createSignal (); diff --git a/io/src/openni2/openni2_device.cpp b/io/src/openni2/openni2_device.cpp index 027285bcb41..8d460471360 100644 --- a/io/src/openni2/openni2_device.cpp +++ b/io/src/openni2/openni2_device.cpp @@ -48,10 +48,7 @@ using namespace pcl::io::openni2; using openni::VideoMode; using std::vector; -pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI) : - ir_video_started_(false), - color_video_started_(false), - depth_video_started_(false) +pcl::io::openni2::OpenNI2Device::OpenNI2Device (const std::string& device_URI) { openni::Status status = openni::OpenNI::initialize (); if (status != openni::STATUS_OK) diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 25954dfdd7e..2ce1b603620 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -73,24 +73,6 @@ namespace ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// pcl::io::OpenNI2Grabber::OpenNI2Grabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode) - : color_resize_buffer_(0) - , depth_resize_buffer_(0) - , ir_resize_buffer_(0) - , image_width_ () - , image_height_ () - , depth_width_ () - , depth_height_ () - , image_required_ (false) - , depth_required_ (false) - , ir_required_ (false) - , sync_required_ (false) - , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ () - , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ () - , point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ () - , depth_callback_handle_ (), image_callback_handle_ (), ir_callback_handle_ () - , running_ (false) - , rgb_parameters_(std::numeric_limits::quiet_NaN () ) - , depth_parameters_(std::numeric_limits::quiet_NaN () ) { // initialize driver updateModeMaps (); // registering mapping from PCL enum modes to openni::VideoMode and vice versa diff --git a/io/src/real_sense_2_grabber.cpp b/io/src/real_sense_2_grabber.cpp index 9de6970857c..b034501bab4 100644 --- a/io/src/real_sense_2_grabber.cpp +++ b/io/src/real_sense_2_grabber.cpp @@ -56,12 +56,6 @@ namespace pcl , signal_PointXYZRGBA ( createSignal () ) , file_name_or_serial_number_ ( file_name_or_serial_number ) , repeat_playback_ ( repeat_playback ) - , quit_ ( false ) - , running_ ( false ) - , fps_ ( 0 ) - , device_width_ ( 424 ) - , device_height_ ( 240 ) - , target_fps_ ( 30 ) { } diff --git a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp index 744279f89a5..6c298c7b2c4 100644 --- a/keypoints/include/pcl/keypoints/impl/iss_3d.hpp +++ b/keypoints/include/pcl/keypoints/impl/iss_3d.hpp @@ -338,7 +338,7 @@ pcl::ISSKeypoint3D::detectKeypoints (PointCloudOut } #ifdef _OPENMP - Eigen::Vector3d *omp_mem = new Eigen::Vector3d[threads_]; + auto *omp_mem = new Eigen::Vector3d[threads_]; for (std::size_t i = 0; i < threads_; i++) omp_mem[i].setZero (3); diff --git a/keypoints/include/pcl/keypoints/keypoint.h b/keypoints/include/pcl/keypoints/keypoint.h index 655006a0897..ef224f20791 100644 --- a/keypoints/include/pcl/keypoints/keypoint.h +++ b/keypoints/include/pcl/keypoints/keypoint.h @@ -179,10 +179,10 @@ namespace pcl KdTreePtr tree_; /** \brief The actual search parameter (casted from either \a search_radius_ or \a k_). */ - double search_parameter_{0}; + double search_parameter_{0.0}; /** \brief The nearest neighbors search radius for each point. */ - double search_radius_{0}; + double search_radius_{0.0}; /** \brief The number of K nearest neighbors to use for each point. */ int k_{0}; diff --git a/ml/include/pcl/ml/svm_wrapper.h b/ml/include/pcl/ml/svm_wrapper.h index 90523bec06b..b125b700798 100644 --- a/ml/include/pcl/ml/svm_wrapper.h +++ b/ml/include/pcl/ml/svm_wrapper.h @@ -100,7 +100,7 @@ struct SVMDataPoint { /// It's the feature index. It has to be an integer number greater or equal to zero int idx{-1}; /// The value assigned to the correspondent feature. - float value{0}; + float value{0.0f}; SVMDataPoint() = default; }; diff --git a/octree/include/pcl/octree/octree_pointcloud.h b/octree/include/pcl/octree/octree_pointcloud.h index a1959dd51b4..aa9c58d5b63 100644 --- a/octree/include/pcl/octree/octree_pointcloud.h +++ b/octree/include/pcl/octree/octree_pointcloud.h @@ -583,19 +583,19 @@ class OctreePointCloud : public OctreeT { IndicesConstPtr indices_; /** \brief Epsilon precision (error bound) for nearest neighbors searches. */ - double epsilon_{0}; + double epsilon_{0.0}; /** \brief Octree resolution. */ double resolution_; // Octree bounding box coordinates - double min_x_{0.0f}; + double min_x_{0.0}; double max_x_; - double min_y_{0.0f}; + double min_y_{0.0}; double max_y_; - double min_z_{0.0f}; + double min_z_{0.0}; double max_z_; /** \brief Flag indicating if octree has defined bounding box. */ diff --git a/recognition/include/pcl/recognition/3rdparty/metslib/abstract-search.hh b/recognition/include/pcl/recognition/3rdparty/metslib/abstract-search.hh index 43008e00e3d..0cbef3f7907 100644 --- a/recognition/include/pcl/recognition/3rdparty/metslib/abstract-search.hh +++ b/recognition/include/pcl/recognition/3rdparty/metslib/abstract-search.hh @@ -34,7 +34,7 @@ #ifndef METS_ABSTRACT_SEARCH_HH_ #define METS_ABSTRACT_SEARCH_HH_ - +//NOLINTBEGIN namespace mets { /// @defgroup common Common components @@ -346,5 +346,5 @@ mets::best_ever_solution::accept(const mets::feasible_solution& sol) } return false; } - +//NOLINTEND #endif diff --git a/recognition/include/pcl/recognition/3rdparty/metslib/simulated-annealing.hh b/recognition/include/pcl/recognition/3rdparty/metslib/simulated-annealing.hh index 98ee923de6d..9887e0c6532 100644 --- a/recognition/include/pcl/recognition/3rdparty/metslib/simulated-annealing.hh +++ b/recognition/include/pcl/recognition/3rdparty/metslib/simulated-annealing.hh @@ -33,7 +33,7 @@ #ifndef METS_SIMULATED_ANNEALING_HH_ #define METS_SIMULATED_ANNEALING_HH_ - +//NOLINTBEGIN namespace mets { /// @defgroup simulated_annealing Simulated Annealing @@ -271,4 +271,5 @@ mets::simulated_annealing::search() cooling_schedule_m(current_temp_m, base_t::working_solution_m); } } +//NOLINTEND #endif diff --git a/registration/include/pcl/registration/correspondence_rejection_median_distance.h b/registration/include/pcl/registration/correspondence_rejection_median_distance.h index 16edbbbca95..bf5715dbc87 100644 --- a/registration/include/pcl/registration/correspondence_rejection_median_distance.h +++ b/registration/include/pcl/registration/correspondence_rejection_median_distance.h @@ -193,7 +193,7 @@ class PCL_EXPORTS CorrespondenceRejectorMedianDistance : public CorrespondenceRe /** \brief The median distance threshold between two correspondent points in source * <-> target. */ - double median_distance_{0}; + double median_distance_{0.0}; /** \brief The factor for correspondence rejection. Points with distance greater than * median times factor will be rejected diff --git a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h index 7d7607fa9cb..37485c9f6a1 100644 --- a/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h +++ b/registration/include/pcl/registration/correspondence_rejection_var_trimmed.h @@ -223,7 +223,7 @@ class PCL_EXPORTS CorrespondenceRejectorVarTrimmed : public CorrespondenceReject /** \brief The inlier distance threshold (based on the computed trim factor) between * two correspondent points in source <-> target. */ - double trimmed_distance_{0}; + double trimmed_distance_{0.0}; /** \brief The factor for correspondence rejection. Only factor times the total points * sorted based on the correspondence distances will be considered as inliers. diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index c2fa789a279..d73e56c3c3d 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -153,7 +153,7 @@ pcl::registration::FPCSInitialAlignment(std::time(NULL)) ^ omp_get_thread_num(); + static_cast(std::time(nullptr)) ^ 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) diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index 48356ba5122..39aab83b0fd 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -175,7 +175,7 @@ class LabeledEuclideanClusterExtraction : public PCLBase { KdTreePtr tree_{nullptr}; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_{0}; + double cluster_tolerance_{0.0}; /** \brief The minimum number of points that a cluster needs to contain in order to be * considered valid (default = 1). */ diff --git a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h index e322599ca93..0739726c53e 100644 --- a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h +++ b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h @@ -199,7 +199,7 @@ namespace pcl double height_limit_max_{std::numeric_limits::max()}; /** \brief Values describing the data acquisition viewpoint. Default: 0,0,0. */ - float vpx_{0}, vpy_{0}, vpz_{0}; + float vpx_{0.0f}, vpy_{0.0f}, vpz_{0.0f}; /** \brief Class getName method. */ virtual std::string diff --git a/segmentation/include/pcl/segmentation/grabcut_segmentation.h b/segmentation/include/pcl/segmentation/grabcut_segmentation.h index 13d20d77a82..0788cd69050 100644 --- a/segmentation/include/pcl/segmentation/grabcut_segmentation.h +++ b/segmentation/include/pcl/segmentation/grabcut_segmentation.h @@ -438,39 +438,39 @@ namespace pcl inline bool isSource (vertex_descriptor v) { return (graph_.inSourceTree (v)); } /// image width - std::uint32_t width_; + std::uint32_t width_{0}; /// image height - std::uint32_t height_; + std::uint32_t height_{0}; // Variables used in formulas from the paper. /// Number of GMM components std::uint32_t K_; /// lambda = 50. This value was suggested the GrabCut paper. float lambda_; /// beta = 1/2 * average of the squared color distances between all pairs of 8-neighboring pixels. - float beta_; + float beta_{0.0f}; /// L = a large value to force a pixel to be foreground or background - float L_; + float L_{0.0f}; /// Pointer to the spatial search object. - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /// Number of neighbours int nb_neighbours_{9}; /// is segmentation initialized bool initialized_{false}; /// Precomputed N-link weights - std::vector n_links_; + std::vector n_links_{}; /// Converted input segmentation::grabcut::Image::Ptr image_; - std::vector trimap_; - std::vector GMM_component_; - std::vector hard_segmentation_; + std::vector trimap_{}; + std::vector GMM_component_{}; + std::vector hard_segmentation_{}; // Not yet implemented (this would be interpreted as alpha) - std::vector soft_segmentation_; + std::vector soft_segmentation_{}; segmentation::grabcut::GMM background_GMM_, foreground_GMM_; // Graph part /// Graph for Graphcut pcl::segmentation::grabcut::BoykovKolmogorov graph_; /// Graph nodes - std::vector graph_nodes_; + std::vector graph_nodes_{}; }; } diff --git a/segmentation/include/pcl/segmentation/lccp_segmentation.h b/segmentation/include/pcl/segmentation/lccp_segmentation.h index 8e9a82c8802..c3c3508ad8b 100644 --- a/segmentation/include/pcl/segmentation/lccp_segmentation.h +++ b/segmentation/include/pcl/segmentation/lccp_segmentation.h @@ -312,10 +312,10 @@ namespace pcl bool use_sanity_check_{false}; /** \brief Seed resolution of the supervoxels (used only for smoothness check) */ - float seed_resolution_{0}; + float seed_resolution_{0.0f}; /** \brief Voxel resolution used to build the supervoxels (used only for smoothness check)*/ - float voxel_resolution_{0}; + float voxel_resolution_{0.0f}; /** \brief Factor used for k-convexity */ std::uint32_t k_factor_{0}; diff --git a/segmentation/include/pcl/segmentation/sac_segmentation.h b/segmentation/include/pcl/segmentation/sac_segmentation.h index 3f8047905b5..a43832cdd83 100644 --- a/segmentation/include/pcl/segmentation/sac_segmentation.h +++ b/segmentation/include/pcl/segmentation/sac_segmentation.h @@ -260,7 +260,7 @@ namespace pcl int method_type_{0}; /** \brief Distance to the model threshold (user given parameter). */ - double threshold_{0}; + double threshold_{0.0}; /** \brief Set to true if a coefficient refinement is required. */ bool optimize_coefficients_{true}; @@ -397,7 +397,7 @@ namespace pcl double distance_weight_{0.1}; /** \brief The distance from the template plane to the origin. */ - double distance_from_origin_{0}; + double distance_from_origin_{0.0}; /** \brief The minimum and maximum allowed opening angle of valid cone model. */ double min_angle_{0.0}; diff --git a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h index a89ee2d3754..e740a7fc483 100644 --- a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h +++ b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h @@ -157,10 +157,10 @@ namespace pcl KdTreePtr tree_{nullptr}; /** \brief The spatial cluster tolerance as a measure in the L2 Euclidean space. */ - double cluster_tolerance_{0}; + double cluster_tolerance_{0.0}; /** \brief The allowed difference on the hue*/ - float delta_hue_{0.0}; + float delta_hue_{0.0f}; /** \brief Class getName method. */ virtual std::string getClassName () const { return ("seededHueSegmentation"); } diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index 78cbf00ba9f..e9e8018bf55 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -159,7 +159,7 @@ namespace pcl Eigen::Vector3f rgb_; Eigen::Vector4f normal_; float curvature_{0.0f}; - float distance_{0}; + float distance_{0.0f}; int idx_{0}; SupervoxelHelper* owner_; diff --git a/surface/include/pcl/surface/bilateral_upsampling.h b/surface/include/pcl/surface/bilateral_upsampling.h index 1c3601b3bfc..1be6fc85777 100644 --- a/surface/include/pcl/surface/bilateral_upsampling.h +++ b/surface/include/pcl/surface/bilateral_upsampling.h @@ -77,10 +77,7 @@ namespace pcl Eigen::Matrix3f KinectVGAProjectionMatrix, KinectSXGAProjectionMatrix; /** \brief Constructor. */ - BilateralUpsampling () - : window_size_ (5) - , sigma_color_ (15.0f) - , sigma_depth_ (0.5f) + BilateralUpsampling () { KinectVGAProjectionMatrix << 525.0f, 0.0f, 320.0f, 0.0f, 525.0f, 240.0f, @@ -148,8 +145,8 @@ namespace pcl computeDistances (Eigen::MatrixXf &val_exp_depth, Eigen::VectorXf &val_exp_rgb); private: - int window_size_; - float sigma_color_, sigma_depth_; + int window_size_{5}; + float sigma_color_{15.0f}, sigma_depth_{0.5f}; Eigen::Matrix3f projection_matrix_, unprojection_matrix_; public: diff --git a/surface/include/pcl/surface/concave_hull.h b/surface/include/pcl/surface/concave_hull.h index dc7ab370251..65aeb585b3e 100644 --- a/surface/include/pcl/surface/concave_hull.h +++ b/surface/include/pcl/surface/concave_hull.h @@ -71,9 +71,7 @@ namespace pcl using PointCloudConstPtr = typename PointCloud::ConstPtr; /** \brief Empty constructor. */ - ConcaveHull () : alpha_ (0), keep_information_ (false), voronoi_centers_ (), dim_(0) - { - }; + ConcaveHull () = default; /** \brief Empty destructor */ ~ConcaveHull () override = default; @@ -189,18 +187,18 @@ namespace pcl /** \brief The method accepts facets only if the distance from any vertex to the facet->center * (center of the voronoi cell) is smaller than alpha */ - double alpha_; + double alpha_{0.0}; /** \brief If set to true, the reconstructed point cloud describing the hull is obtained from * the original input cloud by performing a nearest neighbor search from Qhull output. */ - bool keep_information_; + bool keep_information_{false}; /** \brief the centers of the voronoi cells */ - PointCloudPtr voronoi_centers_; + PointCloudPtr voronoi_centers_{nullptr}; /** \brief the dimensionality of the concave hull */ - int dim_; + int dim_{0}; /** \brief vector containing the point cloud indices of the convex hull points. */ pcl::PointIndices hull_indices_; diff --git a/surface/include/pcl/surface/convex_hull.h b/surface/include/pcl/surface/convex_hull.h index d763eaeedd9..330a4b80e51 100644 --- a/surface/include/pcl/surface/convex_hull.h +++ b/surface/include/pcl/surface/convex_hull.h @@ -88,12 +88,8 @@ namespace pcl using PointCloudConstPtr = typename PointCloud::ConstPtr; /** \brief Empty constructor. */ - 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) - { - } - + ConvexHull() = default; + /** \brief Empty destructor */ ~ConvexHull () override = default; @@ -237,31 +233,31 @@ namespace pcl } /* \brief True if we should compute the area and volume of the convex hull. */ - bool compute_area_; + bool compute_area_{false}; /* \brief The area of the convex hull. */ - double total_area_; + double total_area_{0.0}; /* \brief The volume of the convex hull (only for 3D hulls, zero for 2D). */ - double total_volume_; + double total_volume_{0.0}; /** \brief The dimensionality of the concave hull (2D or 3D). */ - int dimension_; + int dimension_{0}; /** \brief How close can a 2D plane's normal be to an axis to make projection problematic. */ - double projection_angle_thresh_; + double projection_angle_thresh_{std::cos (0.174532925)}; /** \brief Option flag string to be used calling qhull. */ - std::string qhull_flags; + std::string qhull_flags{"qhull "}; /* \brief x-axis - for checking valid projections. */ - const Eigen::Vector3d x_axis_; + const Eigen::Vector3d x_axis_{1.0, 0.0, 0.0}; /* \brief y-axis - for checking valid projections. */ - const Eigen::Vector3d y_axis_; + const Eigen::Vector3d y_axis_{0.0, 1.0, 0.0}; /* \brief z-axis - for checking valid projections. */ - const Eigen::Vector3d z_axis_; + const Eigen::Vector3d z_axis_{0.0, 0.0, 1.0}; /* \brief vector containing the point cloud indices of the convex hull points. */ pcl::PointIndices hull_indices_; diff --git a/surface/include/pcl/surface/gp3.h b/surface/include/pcl/surface/gp3.h index e588845e6f8..9a3cdbbd3f2 100644 --- a/surface/include/pcl/surface/gp3.h +++ b/surface/include/pcl/surface/gp3.h @@ -155,28 +155,7 @@ namespace pcl }; /** \brief Empty constructor. */ - GreedyProjectionTriangulation () : - mu_ (0), - search_radius_ (0), // must be set by user - nnn_ (100), - minimum_angle_ (M_PI/18), // 10 degrees - maximum_angle_ (2*M_PI/3), // 120 degrees - eps_angle_(M_PI/4), //45 degrees, - consistent_(false), - consistent_ordering_ (false), - angles_ (), - R_ (), - is_current_free_ (false), - current_index_ (), - prev_is_ffn_ (false), - prev_is_sfn_ (false), - next_is_ffn_ (false), - next_is_sfn_ (false), - changed_1st_fn_ (false), - changed_2nd_fn_ (false), - new2boundary_ (), - already_connected_ (false) - {}; + GreedyProjectionTriangulation () = default; /** \brief Set the multiplier of the nearest neighbor distance to obtain the final search radius for each point * (this will make the algorithm adapt to different point densities in the cloud). @@ -288,28 +267,28 @@ namespace pcl protected: /** \brief The nearest neighbor distance multiplier to obtain the final search radius. */ - double mu_; + double mu_{0.0}; /** \brief The nearest neighbors search radius for each point and the maximum edge length. */ - double search_radius_; + double search_radius_{0.0}; /** \brief The maximum number of nearest neighbors accepted by searching. */ - int nnn_; + int nnn_{100}; /** \brief The preferred minimum angle for the triangles. */ - double minimum_angle_; + double minimum_angle_{M_PI/18}; /** \brief The maximum angle for the triangles. */ - double maximum_angle_; + double maximum_angle_{2*M_PI/3}; /** \brief Maximum surface angle. */ - double eps_angle_; + double eps_angle_{M_PI/4}; /** \brief Set this to true if the normals of the input are consistently oriented. */ - bool consistent_; + bool consistent_{false}; /** \brief Set this to true if the output triangle vertices should be consistently oriented. */ - bool consistent_ordering_; + bool consistent_ordering_{false}; private: /** \brief Struct for storing the angles to nearest neighbors **/ @@ -324,8 +303,8 @@ namespace pcl /** \brief Struct for storing the edges starting from a fringe point **/ struct doubleEdge { - doubleEdge () : index (0) {} - int index; + doubleEdge () = default; + int index{0}; Eigen::Vector2f first; Eigen::Vector2f second; }; @@ -333,50 +312,50 @@ namespace pcl // Variables made global to decrease the number of parameters to helper functions /** \brief Temporary variable to store a triangle (as a set of point indices) **/ - pcl::Vertices triangle_; + pcl::Vertices triangle_{}; /** \brief Temporary variable to store point coordinates **/ - std::vector > coords_; + std::vector > coords_{}; /** \brief A list of angles to neighbors **/ - std::vector angles_; + std::vector angles_{}; /** \brief Index of the current query point **/ - pcl::index_t R_; + pcl::index_t R_{}; /** \brief List of point states **/ - std::vector state_; + std::vector state_{}; /** \brief List of sources **/ - pcl::Indices source_; + pcl::Indices source_{}; /** \brief List of fringe neighbors in one direction **/ - pcl::Indices ffn_; + pcl::Indices ffn_{}; /** \brief List of fringe neighbors in other direction **/ - pcl::Indices sfn_; + pcl::Indices sfn_{}; /** \brief Connected component labels for each point **/ - std::vector part_; + std::vector part_{}; /** \brief Points on the outer edge from which the mesh has to be grown **/ - std::vector fringe_queue_; + std::vector fringe_queue_{}; /** \brief Flag to set if the current point is free **/ - bool is_current_free_; + bool is_current_free_{false}; /** \brief Current point's index **/ - pcl::index_t current_index_; + pcl::index_t current_index_{}; /** \brief Flag to set if the previous point is the first fringe neighbor **/ - bool prev_is_ffn_; + bool prev_is_ffn_{false}; /** \brief Flag to set if the next point is the second fringe neighbor **/ - bool prev_is_sfn_; + bool prev_is_sfn_{false}; /** \brief Flag to set if the next point is the first fringe neighbor **/ - bool next_is_ffn_; + bool next_is_ffn_{false}; /** \brief Flag to set if the next point is the second fringe neighbor **/ - bool next_is_sfn_; + bool next_is_sfn_{false}; /** \brief Flag to set if the first fringe neighbor was changed **/ - bool changed_1st_fn_; + bool changed_1st_fn_{false}; /** \brief Flag to set if the second fringe neighbor was changed **/ - bool changed_2nd_fn_; + bool changed_2nd_fn_{false}; /** \brief New boundary point **/ - pcl::index_t new2boundary_; + pcl::index_t new2boundary_{}; /** \brief Flag to set if the next neighbor was already connected in the previous step. * To avoid inconsistency it should not be connected again. */ - bool already_connected_; + bool already_connected_{false}; /** \brief Point coordinates projected onto the plane defined by the point normal **/ Eigen::Vector3f proj_qp_; diff --git a/surface/include/pcl/surface/impl/mls.hpp b/surface/include/pcl/surface/impl/mls.hpp index 8f5a3fb82e6..79ec961e0b0 100644 --- a/surface/include/pcl/surface/impl/mls.hpp +++ b/surface/include/pcl/surface/impl/mls.hpp @@ -809,7 +809,7 @@ pcl::MovingLeastSquares::MLSVoxelGrid::MLSVoxelGrid (PointC IndicesPtr &indices, float voxel_size, int dilation_iteration_num) : - voxel_grid_ (), data_size_ (), voxel_size_ (voxel_size) + voxel_grid_ (), voxel_size_ (voxel_size) { pcl::getMinMax3D (*cloud, *indices, bounding_min_, bounding_max_); bounding_min_ -= Eigen::Vector4f::Constant(voxel_size_ * (dilation_iteration_num + 1)); diff --git a/surface/include/pcl/surface/impl/poisson.hpp b/surface/include/pcl/surface/impl/poisson.hpp index c020020e636..9e0cd210a90 100644 --- a/surface/include/pcl/surface/impl/poisson.hpp +++ b/surface/include/pcl/surface/impl/poisson.hpp @@ -60,29 +60,7 @@ using namespace pcl; ////////////////////////////////////////////////////////////////////////////////////////////// template -pcl::Poisson::Poisson () - : depth_ (8) - , min_depth_ (5) - , point_weight_ (4) - , scale_ (1.1f) - , solver_divide_ (8) - , iso_divide_ (8) - , samples_per_node_ (1.0) - , confidence_ (false) - , output_polygons_ (false) - , no_reset_samples_ (false) - , no_clip_tree_ (false) - , manifold_ (true) - , refine_ (3) - , kernel_depth_ (8) - , degree_ (2) - , non_adaptive_weights_ (false) - , show_residual_ (false) - , min_iterations_ (8) - , solver_accuracy_ (1e-3f) - , threads_(1) -{ -} +pcl::Poisson::Poisson () = default; ////////////////////////////////////////////////////////////////////////////////////////////// template diff --git a/surface/include/pcl/surface/mls.h b/surface/include/pcl/surface/mls.h index 94df042d9d5..8c3a45e1dff 100644 --- a/surface/include/pcl/surface/mls.h +++ b/surface/include/pcl/surface/mls.h @@ -79,10 +79,10 @@ namespace pcl /** \brief Data structure used to store the MLS projection results */ struct MLSProjectionResults { - MLSProjectionResults () : u (0), v (0) {} + MLSProjectionResults () = default; - double u; /**< \brief The u-coordinate of the projected point in local MLS frame. */ - double v; /**< \brief The v-coordinate of the projected point in local MLS frame. */ + double u{0.0}; /**< \brief The u-coordinate of the projected point in local MLS frame. */ + double v{0.0}; /**< \brief The v-coordinate of the projected point in local MLS frame. */ Eigen::Vector3d point; /**< \brief The projected point. */ Eigen::Vector3d normal; /**< \brief The projected point's normal. */ PCL_MAKE_ALIGNED_OPERATOR_NEW @@ -307,20 +307,9 @@ namespace pcl MovingLeastSquares () : CloudSurfaceProcessing (), distinct_cloud_ (), tree_ (), - order_ (2), - search_radius_ (0.0), - sqr_gauss_param_ (0.0), - compute_normals_ (false), + upsample_method_ (NONE), - upsampling_radius_ (0.0), - upsampling_step_ (0.0), - desired_num_points_in_radius_ (0), - cache_mls_results_ (true), - projection_method_ (MLSResult::SIMPLE), - threads_ (1), - voxel_size_ (1.0), - dilation_iteration_num_ (0), - nr_coeff_ (), + rng_uniform_distribution_ () {}; @@ -523,28 +512,28 @@ namespace pcl protected: /** \brief The point cloud that will hold the estimated normals, if set. */ - NormalCloudPtr normals_; + NormalCloudPtr normals_{nullptr}; /** \brief The distinct point cloud that will be projected to the MLS surface. */ - PointCloudInConstPtr distinct_cloud_; + PointCloudInConstPtr distinct_cloud_{nullptr}; /** \brief The search method template for indices. */ SearchMethod search_method_; /** \brief A pointer to the spatial search object. */ - KdTreePtr tree_; + KdTreePtr tree_{nullptr}; /** \brief The order of the polynomial to be fit. */ - int order_; + int order_{2}; /** \brief The nearest neighbors search radius for each point. */ - double search_radius_; + double search_radius_{0.0}; /** \brief Parameter for distance based weighting of neighbors (search_radius_ * search_radius_ works fine) */ - double sqr_gauss_param_; + double sqr_gauss_param_{0.0}; /** \brief Parameter that specifies whether the normals should be computed for the input cloud or not */ - bool compute_normals_; + bool compute_normals_{false}; /** \brief Parameter that specifies the upsampling method to be used */ UpsamplingMethod upsample_method_; @@ -552,33 +541,33 @@ namespace pcl /** \brief Radius of the circle in the local point plane that will be sampled * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling */ - double upsampling_radius_; + double upsampling_radius_{0.0}; /** \brief Step size for the local plane sampling * \note Used only in the case of SAMPLE_LOCAL_PLANE upsampling */ - double upsampling_step_; + double upsampling_step_{0.0}; /** \brief Parameter that specifies the desired number of points within the search radius * \note Used only in the case of RANDOM_UNIFORM_DENSITY upsampling */ - int desired_num_points_in_radius_; + int desired_num_points_in_radius_{0}; /** \brief True if the mls results for the input cloud should be stored * \note This is forced to be true when using upsampling methods VOXEL_GRID_DILATION or DISTINCT_CLOUD. */ - bool cache_mls_results_; + bool cache_mls_results_{true}; /** \brief Stores the MLS result for each point in the input cloud * \note Used only in the case of VOXEL_GRID_DILATION or DISTINCT_CLOUD upsampling */ - std::vector mls_results_; + std::vector mls_results_{}; /** \brief Parameter that specifies the projection method to be used. */ - MLSResult::ProjectionMethod projection_method_; + MLSResult::ProjectionMethod projection_method_{MLSResult::SIMPLE}; /** \brief The maximum number of threads the scheduler should use. */ - unsigned int threads_; + unsigned int threads_{1}; /** \brief A minimalistic implementation of a voxel grid, necessary for the point cloud upsampling @@ -587,7 +576,7 @@ namespace pcl class MLSVoxelGrid { public: - struct Leaf { Leaf () : valid (true) {} bool valid; }; + struct Leaf { Leaf () = default; bool valid{true}; }; MLSVoxelGrid (PointCloudInConstPtr& cloud, IndicesPtr &indices, @@ -633,23 +622,23 @@ namespace pcl using HashMap = std::map; HashMap voxel_grid_; Eigen::Vector4f bounding_min_, bounding_max_; - std::uint64_t data_size_; + std::uint64_t data_size_{0}; float voxel_size_; PCL_MAKE_ALIGNED_OPERATOR_NEW }; /** \brief Voxel size for the VOXEL_GRID_DILATION upsampling method */ - float voxel_size_; + float voxel_size_{1.0f}; /** \brief Number of dilation steps for the VOXEL_GRID_DILATION upsampling method */ - int dilation_iteration_num_; + int dilation_iteration_num_{0}; /** \brief Number of coefficients, to be computed from the requested order.*/ - int nr_coeff_; + int nr_coeff_{0}; /** \brief Collects for each point in output the corresponding point in the input. */ - PointIndicesPtr corresponding_input_indices_; + PointIndicesPtr corresponding_input_indices_{nullptr}; /** \brief Search for the nearest neighbors of a given point using a radius search * \param[in] index the index of the query point diff --git a/surface/include/pcl/surface/organized_fast_mesh.h b/surface/include/pcl/surface/organized_fast_mesh.h index b05f19b8496..3e0810c8e82 100644 --- a/surface/include/pcl/surface/organized_fast_mesh.h +++ b/surface/include/pcl/surface/organized_fast_mesh.h @@ -86,20 +86,6 @@ namespace pcl /** \brief Constructor. Triangulation type defaults to \a QUAD_MESH. */ OrganizedFastMesh () - : max_edge_length_a_ (0.0f) - , max_edge_length_b_ (0.0f) - , max_edge_length_c_ (0.0f) - , max_edge_length_set_ (false) - , max_edge_length_dist_dependent_ (false) - , triangle_pixel_size_rows_ (1) - , triangle_pixel_size_columns_ (1) - , triangulation_type_ (QUAD_MESH) - , viewpoint_ (Eigen::Vector3f::Zero ()) - , store_shadowed_faces_ (false) - , cos_angle_tolerance_ (std::abs (std::cos (pcl::deg2rad (12.5f)))) - , distance_tolerance_ (-1.0f) - , distance_dependent_ (false) - , use_depth_as_distance_(false) { check_tree_ = false; }; @@ -228,44 +214,44 @@ namespace pcl protected: /** \brief max length of edge, scalar component */ - float max_edge_length_a_; + float max_edge_length_a_{0.0f}; /** \brief max length of edge, scalar component */ - float max_edge_length_b_; + float max_edge_length_b_{0.0f}; /** \brief max length of edge, scalar component */ - float max_edge_length_c_; + float max_edge_length_c_{0.0f}; /** \brief flag whether or not edges are limited in length */ - bool max_edge_length_set_; + bool max_edge_length_set_{false}; /** \brief flag whether or not max edge length is distance dependent. */ - bool max_edge_length_dist_dependent_; + bool max_edge_length_dist_dependent_{false}; /** \brief size of triangle edges (in pixels) for iterating over rows. */ - int triangle_pixel_size_rows_; + int triangle_pixel_size_rows_{1}; /** \brief size of triangle edges (in pixels) for iterating over columns*/ - int triangle_pixel_size_columns_; + int triangle_pixel_size_columns_{1}; /** \brief Type of meshing scheme (quads vs. triangles, left cut vs. right cut ... */ - TriangulationType triangulation_type_; + TriangulationType triangulation_type_{QUAD_MESH}; /** \brief Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data). */ - Eigen::Vector3f viewpoint_; + Eigen::Vector3f viewpoint_{Eigen::Vector3f::Zero ()}; /** \brief Whether or not shadowed faces are stored, e.g., for exploration */ - bool store_shadowed_faces_; + bool store_shadowed_faces_{false}; /** \brief (Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed. */ - float cos_angle_tolerance_; + float cos_angle_tolerance_{std::abs (std::cos (pcl::deg2rad (12.5f)))}; /** \brief distance tolerance for filtering out shadowed/occluded edges */ - float distance_tolerance_; + float distance_tolerance_{-1.0f}; /** \brief flag whether or not \a distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not. */ - bool distance_dependent_; + bool distance_dependent_{false}; /** \brief flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint). This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up. */ - bool use_depth_as_distance_; + bool use_depth_as_distance_{false}; /** \brief Perform the actual polygonal reconstruction. diff --git a/surface/include/pcl/surface/poisson.h b/surface/include/pcl/surface/poisson.h index 9f1e36e9de4..9fca5b4b343 100644 --- a/surface/include/pcl/surface/poisson.h +++ b/surface/include/pcl/surface/poisson.h @@ -236,28 +236,28 @@ namespace pcl getClassName () const override { return ("Poisson"); } private: - int depth_; - int min_depth_; - float point_weight_; - float scale_; - int solver_divide_; - int iso_divide_; - float samples_per_node_; - bool confidence_; - bool output_polygons_; - - bool no_reset_samples_; - bool no_clip_tree_; - bool manifold_; - - int refine_; - int kernel_depth_; - int degree_; - bool non_adaptive_weights_; - bool show_residual_; - int min_iterations_; - float solver_accuracy_; - int threads_; + int depth_{8}; + int min_depth_{5}; + float point_weight_{4}; + float scale_{1.1f}; + int solver_divide_{8}; + int iso_divide_{8}; + float samples_per_node_{1.0}; + bool confidence_{false}; + bool output_polygons_{false}; + + bool no_reset_samples_{false}; + bool no_clip_tree_{false}; + bool manifold_{true}; + + int refine_{3}; + int kernel_depth_{8}; + int degree_{2}; + bool non_adaptive_weights_{false}; + bool show_residual_{false}; + int min_iterations_{8}; + float solver_accuracy_{1e-3f}; + int threads_{1}; template void execute (poisson::CoredVectorMeshData &mesh, diff --git a/surface/include/pcl/surface/reconstruction.h b/surface/include/pcl/surface/reconstruction.h index 34ffe7c1072..75ae4308eff 100644 --- a/surface/include/pcl/surface/reconstruction.h +++ b/surface/include/pcl/surface/reconstruction.h @@ -128,7 +128,7 @@ namespace pcl using PCLSurfaceBase::getClassName; /** \brief Constructor. */ - SurfaceReconstruction () : check_tree_ (true) {} + SurfaceReconstruction () = default; /** \brief Destructor. */ ~SurfaceReconstruction () override = default; @@ -153,7 +153,7 @@ namespace pcl protected: /** \brief A flag specifying whether or not the derived reconstruction * algorithm needs the search object \a tree.*/ - bool check_tree_; + bool check_tree_{true}; /** \brief Abstract surface reconstruction method. * \param[out] output the output polygonal mesh @@ -197,7 +197,7 @@ namespace pcl using PCLSurfaceBase::getClassName; /** \brief Constructor. */ - MeshConstruction () : check_tree_ (true) {} + MeshConstruction () = default; /** \brief Destructor. */ ~MeshConstruction () override = default; @@ -225,7 +225,7 @@ namespace pcl protected: /** \brief A flag specifying whether or not the derived reconstruction * algorithm needs the search object \a tree.*/ - bool check_tree_; + bool check_tree_{true}; /** \brief Abstract surface reconstruction method. * \param[out] output the output polygonal mesh diff --git a/surface/include/pcl/surface/texture_mapping.h b/surface/include/pcl/surface/texture_mapping.h index caff3c2e836..2aa8ef9df9f 100644 --- a/surface/include/pcl/surface/texture_mapping.h +++ b/surface/include/pcl/surface/texture_mapping.h @@ -64,16 +64,15 @@ namespace pcl */ struct Camera { - Camera () : focal_length (), focal_length_w (-1), focal_length_h (-1), - center_w (-1), center_h (-1), height (), width () {} + Camera () = default; Eigen::Affine3f pose; - double focal_length; - double focal_length_w; // optional - double focal_length_h; // optinoal - double center_w; // optional - double center_h; // optional - double height; - double width; + double focal_length{0.0}; + double focal_length_w{-1.0}; // optional + double focal_length_h{-1.0}; // optinoal + double center_w{-1.0}; // optional + double center_h{-1.0}; // optional + double height{0.0}; + double width{0.0}; std::string texture_file; PCL_MAKE_ALIGNED_OPERATOR_NEW @@ -83,9 +82,9 @@ namespace pcl */ struct UvIndex { - UvIndex () : idx_cloud (), idx_face () {} - int idx_cloud; // Index of the PointXYZ in the camera's cloud - int idx_face; // Face corresponding to that projection + UvIndex () = default; + int idx_cloud{0}; // Index of the PointXYZ in the camera's cloud + int idx_face{0}; // Face corresponding to that projection }; using CameraVector = std::vector >; @@ -116,10 +115,7 @@ namespace pcl using UvIndex = pcl::texture_mapping::UvIndex; /** \brief Constructor. */ - TextureMapping () : - f_ () - { - } + TextureMapping () = default; /** \brief Destructor. */ ~TextureMapping () = default; @@ -335,7 +331,7 @@ namespace pcl protected: /** \brief mesh scale control. */ - float f_; + float f_{0.0f}; /** \brief vector field */ Eigen::Vector3f vector_field_; diff --git a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h index 3f9884b2725..d4232144465 100644 --- a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h +++ b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h @@ -75,7 +75,7 @@ namespace pcl performProcessing (pcl::PolygonMesh &output) override; private: - float target_reduction_factor_; + float target_reduction_factor_{0.5f}; vtkSmartPointer vtk_polygons_; }; diff --git a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h index e2edb7710d7..8a68c40f658 100644 --- a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h +++ b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_laplacian.h @@ -52,15 +52,7 @@ namespace pcl { public: /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */ - MeshSmoothingLaplacianVTK () - : num_iter_ (20) - , convergence_ (0.0f) - , relaxation_factor_ (0.01f) - , feature_edge_smoothing_ (false) - , feature_angle_ (45.f) - , edge_angle_ (15.f) - , boundary_smoothing_ (true) - {}; + MeshSmoothingLaplacianVTK () = default; /** \brief Set the number of iterations for the smoothing filter. * \param[in] num_iter the number of iterations @@ -185,12 +177,12 @@ namespace pcl vtkSmartPointer vtk_polygons_; /// Parameters - int num_iter_; - float convergence_; - float relaxation_factor_; - bool feature_edge_smoothing_; - float feature_angle_; - float edge_angle_; - bool boundary_smoothing_; + int num_iter_{20}; + float convergence_{0.0f}; + float relaxation_factor_{0.01f}; + bool feature_edge_smoothing_{false}; + float feature_angle_{45.f}; + float edge_angle_{15.f}; + bool boundary_smoothing_{true}; }; } diff --git a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h index 220e17baa00..f52119d8481 100644 --- a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h +++ b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_smoothing_windowed_sinc.h @@ -52,15 +52,7 @@ namespace pcl { public: /** \brief Empty constructor that sets the values of the algorithm parameters to the VTK defaults */ - MeshSmoothingWindowedSincVTK () - : num_iter_ (20), - pass_band_ (0.1f), - feature_edge_smoothing_ (false), - feature_angle_ (45.f), - edge_angle_ (15.f), - boundary_smoothing_ (true), - normalize_coordinates_ (false) - {}; + MeshSmoothingWindowedSincVTK () = default; /** \brief Set the number of iterations for the smoothing filter. * \param[in] num_iter the number of iterations @@ -185,12 +177,12 @@ namespace pcl private: vtkSmartPointer vtk_polygons_; - int num_iter_; - float pass_band_; - bool feature_edge_smoothing_; - float feature_angle_; - float edge_angle_; - bool boundary_smoothing_; - bool normalize_coordinates_; + int num_iter_{20}; + float pass_band_{0.1f}; + bool feature_edge_smoothing_{false}; + float feature_angle_{45.f}; + float edge_angle_{15.f}; + bool boundary_smoothing_{true}; + bool normalize_coordinates_{false}; }; } diff --git a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h index 52fe077d27d..fee48b56461 100644 --- a/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h +++ b/surface/include/pcl/surface/vtk_smoothing/vtk_mesh_subdivision.h @@ -79,7 +79,7 @@ namespace pcl performProcessing (pcl::PolygonMesh &output) override; private: - MeshSubdivisionVTKFilterType filter_type_; + MeshSubdivisionVTKFilterType filter_type_{LINEAR}; vtkSmartPointer vtk_polygons_; }; diff --git a/surface/src/vtk_smoothing/vtk_mesh_quadric_decimation.cpp b/surface/src/vtk_smoothing/vtk_mesh_quadric_decimation.cpp index 2277ba1a6a3..c271b5eaa63 100644 --- a/surface/src/vtk_smoothing/vtk_mesh_quadric_decimation.cpp +++ b/surface/src/vtk_smoothing/vtk_mesh_quadric_decimation.cpp @@ -42,10 +42,7 @@ #include ////////////////////////////////////////////////////////////////////////////////////////////// -pcl::MeshQuadricDecimationVTK::MeshQuadricDecimationVTK () - : target_reduction_factor_ (0.5f) -{ -} +pcl::MeshQuadricDecimationVTK::MeshQuadricDecimationVTK () = default; ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/surface/src/vtk_smoothing/vtk_mesh_subdivision.cpp b/surface/src/vtk_smoothing/vtk_mesh_subdivision.cpp index 5ff489a9803..6b78214c08c 100644 --- a/surface/src/vtk_smoothing/vtk_mesh_subdivision.cpp +++ b/surface/src/vtk_smoothing/vtk_mesh_subdivision.cpp @@ -45,10 +45,7 @@ ////////////////////////////////////////////////////////////////////////////////////////////// -pcl::MeshSubdivisionVTK::MeshSubdivisionVTK () - : filter_type_ (LINEAR) -{ -} +pcl::MeshSubdivisionVTK::MeshSubdivisionVTK () = default; ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/tools/openni2_viewer.cpp b/tools/openni2_viewer.cpp index 24fd15cd79c..9df14649ec2 100644 --- a/tools/openni2_viewer.cpp +++ b/tools/openni2_viewer.cpp @@ -114,7 +114,6 @@ class OpenNI2Viewer OpenNI2Viewer (pcl::io::OpenNI2Grabber& grabber) : cloud_viewer_ (new pcl::visualization::PCLVisualizer ("PCL OpenNI2 cloud")) , grabber_ (grabber) - , rgb_data_ (nullptr), rgb_data_size_ (0) { } @@ -266,13 +265,13 @@ class OpenNI2Viewer pcl::visualization::ImageViewer::Ptr image_viewer_; pcl::io::OpenNI2Grabber& grabber_; - std::mutex cloud_mutex_; - std::mutex image_mutex_; + std::mutex cloud_mutex_{}; + std::mutex image_mutex_{}; - CloudConstPtr cloud_; - pcl::io::openni2::Image::Ptr image_; - unsigned char* rgb_data_; - unsigned rgb_data_size_; + CloudConstPtr cloud_{nullptr}; + pcl::io::openni2::Image::Ptr image_{nullptr}; + unsigned char* rgb_data_{nullptr}; + unsigned rgb_data_size_{0}; }; /* ---[ */ diff --git a/tools/ply2obj.cpp b/tools/ply2obj.cpp index 5db70395c57..df1e4094651 100644 --- a/tools/ply2obj.cpp +++ b/tools/ply2obj.cpp @@ -124,7 +124,7 @@ class ply_to_obj_converter flags_type flags_{0}; std::ostream* ostream_{}; - double vertex_x_{0}, vertex_y_{0}, vertex_z_{0}; + double vertex_x_{0.0}, vertex_y_{0.0}, vertex_z_{0.0}; std::size_t face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0}; }; diff --git a/tools/ply2raw.cpp b/tools/ply2raw.cpp index 86ab736ea45..1fd1f833ab9 100644 --- a/tools/ply2raw.cpp +++ b/tools/ply2raw.cpp @@ -136,7 +136,7 @@ class ply_to_raw_converter face_end (); std::ostream* ostream_{}; - pcl::io::ply::float32 vertex_x_{0}, vertex_y_{0}, vertex_z_{0}; + pcl::io::ply::float32 vertex_x_{0.0f}, vertex_y_{0.0f}, vertex_z_{0.0f}; pcl::io::ply::int32 face_vertex_indices_element_index_{0}, face_vertex_indices_first_element_{0}, face_vertex_indices_previous_element_{0}; std::vector > vertices_{}; }; diff --git a/tracking/include/pcl/tracking/distance_coherence.h b/tracking/include/pcl/tracking/distance_coherence.h index e2f15f4f692..e56e72bfba0 100644 --- a/tracking/include/pcl/tracking/distance_coherence.h +++ b/tracking/include/pcl/tracking/distance_coherence.h @@ -17,7 +17,7 @@ class DistanceCoherence : public PointCoherence { using ConstPtr = shared_ptr>; /** \brief initialize the weight to 1.0. */ - DistanceCoherence() : PointCoherence(), weight_(1.0) {} + DistanceCoherence() : PointCoherence() {} /** \brief set the weight of coherence. * \param weight the value of the wehgit. @@ -44,7 +44,7 @@ class DistanceCoherence : public PointCoherence { computeCoherence(PointInT& source, PointInT& target) override; /** \brief the weight of coherence.*/ - double weight_; + double weight_{1.0}; }; } // namespace tracking } // namespace pcl diff --git a/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h b/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h index a28fbf806c8..b1291f2ab62 100644 --- a/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h +++ b/tracking/include/pcl/tracking/kld_adaptive_particle_filter.h @@ -63,11 +63,7 @@ class KLDAdaptiveParticleFilterTracker /** \brief Empty constructor. */ KLDAdaptiveParticleFilterTracker() - : ParticleFilterTracker() - , maximum_particle_number_() - , epsilon_(0) - , delta_(0.99) - , bin_size_() + : ParticleFilterTracker(), bin_size_() { tracker_name_ = "KLDAdaptiveParticleFilterTracker"; } @@ -243,14 +239,14 @@ class KLDAdaptiveParticleFilterTracker resample() override; /** \brief the maximum number of the particles. */ - unsigned int maximum_particle_number_; + unsigned int maximum_particle_number_{0}; /** \brief error between K-L distance and MLE*/ - double epsilon_; + double epsilon_{0.0}; /** \brief probability of distance between K-L distance and MLE is less than * epsilon_*/ - double delta_; + double delta_{0.99}; /** \brief the size of a bin.*/ StateT bin_size_; diff --git a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h index 8e54f38e8f8..f7d6eda2a2b 100644 --- a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h +++ b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h @@ -29,7 +29,6 @@ class NearestPairPointCloudCoherence : public PointCloudCoherence { /** \brief empty constructor */ NearestPairPointCloudCoherence() - : new_target_(false), search_(), maximum_distance_(std::numeric_limits::max()) { coherence_name_ = "NearestPairPointCloudCoherence"; } @@ -82,13 +81,13 @@ class NearestPairPointCloudCoherence : public PointCloudCoherence { initCompute() override; /** \brief A flag which is true if target_input_ is updated */ - bool new_target_; + bool new_target_{false}; /** \brief A pointer to the spatial search object. */ - SearchPtr search_; + SearchPtr search_{nullptr}; /** \brief max of distance for points to be taken into account*/ - double maximum_distance_; + double maximum_distance_{std::numeric_limits::max()}; /** \brief compute the nearest pairs and compute coherence using * point_coherences_ */ diff --git a/tracking/include/pcl/tracking/normal_coherence.h b/tracking/include/pcl/tracking/normal_coherence.h index 604e28d61f1..d251ca0a3e5 100644 --- a/tracking/include/pcl/tracking/normal_coherence.h +++ b/tracking/include/pcl/tracking/normal_coherence.h @@ -13,7 +13,7 @@ template class NormalCoherence : public PointCoherence { public: /** \brief initialize the weight to 1.0. */ - NormalCoherence() : PointCoherence(), weight_(1.0) {} + NormalCoherence() : PointCoherence() {} /** \brief set the weight of coherence * \param weight the weight of coherence @@ -40,7 +40,7 @@ class NormalCoherence : public PointCoherence { computeCoherence(PointInT& source, PointInT& target) override; /** \brief the weight of coherence */ - double weight_; + double weight_{1.0}; }; } // namespace tracking } // namespace pcl diff --git a/tracking/include/pcl/tracking/particle_filter.h b/tracking/include/pcl/tracking/particle_filter.h index 1f0fe6a4513..122d4b5417c 100644 --- a/tracking/include/pcl/tracking/particle_filter.h +++ b/tracking/include/pcl/tracking/particle_filter.h @@ -50,30 +50,7 @@ class ParticleFilterTracker : public Tracker { /** \brief Empty constructor. */ ParticleFilterTracker() - : iteration_num_(1) - , particle_num_() - , min_indices_(1) - , ref_() - , particles_() - , coherence_() - , resample_likelihood_thr_(0.0) - , occlusion_angle_thr_(M_PI / 2.0) - , alpha_(15.0) - , representative_state_() - , use_normal_(false) - , motion_() - , motion_ratio_(0.25) - , pass_x_() - , pass_y_() - , pass_z_() - , transed_reference_vector_() - , change_detector_() - , changed_(false) - , change_counter_(0) - , change_detector_filter_(10) - , change_detector_interval_(10) - , change_detector_resolution_(0.01) - , use_change_detector_(false) + : representative_state_(), motion_(), pass_x_(), pass_y_(), pass_z_() { tracker_name_ = "ParticleFilterTracker"; pass_x_.setFilterFieldName("x"); @@ -558,48 +535,48 @@ class ParticleFilterTracker : public Tracker { testChangeDetection(const PointCloudInConstPtr& input); /** \brief The number of iteration of particlefilter. */ - int iteration_num_; + int iteration_num_{1}; /** \brief The number of the particles. */ - int particle_num_; + int particle_num_{0}; /** \brief The minimum number of points which the hypothesis should have. */ - int min_indices_; + int min_indices_{1}; /** \brief Adjustment of the particle filter. */ - double fit_ratio_; + double fit_ratio_{0.0}; /** \brief A pointer to reference point cloud. */ - PointCloudInConstPtr ref_; + PointCloudInConstPtr ref_{nullptr}; /** \brief A pointer to the particles */ - PointCloudStatePtr particles_; + PointCloudStatePtr particles_{nullptr}; /** \brief A pointer to PointCloudCoherence. */ - CloudCoherencePtr coherence_; + CloudCoherencePtr coherence_{nullptr}; /** \brief The diagonal elements of covariance matrix of the step noise. the * covariance matrix is used at every resample method. */ - std::vector step_noise_covariance_; + std::vector step_noise_covariance_{}; /** \brief The diagonal elements of covariance matrix of the initial noise. * the covariance matrix is used when initialize the particles. */ - std::vector initial_noise_covariance_; + std::vector initial_noise_covariance_{}; /** \brief The mean values of initial noise. */ - std::vector initial_noise_mean_; + std::vector initial_noise_mean_{}; /** \brief The threshold for the particles to be re-initialized. */ - double resample_likelihood_thr_; + double resample_likelihood_thr_{0.0}; /** \brief The threshold for the points to be considered as occluded. */ - double occlusion_angle_thr_; + double occlusion_angle_thr_{M_PI / 2.0}; /** \brief The weight to be used in normalization of the weights of the * particles. */ - double alpha_; + double alpha_{15.0}; /** \brief The result of tracking. */ StateT representative_state_; @@ -609,13 +586,13 @@ class ParticleFilterTracker : public Tracker { Eigen::Affine3f trans_; /** \brief A flag to use normal or not. defaults to false. */ - bool use_normal_; + bool use_normal_{false}; /** \brief Difference between the result in t and t-1. */ StateT motion_; /** \brief Ratio of hypothesis to use motion model. */ - double motion_ratio_; + double motion_ratio_{0.25}; /** \brief Pass through filter to crop the pointclouds within the hypothesis * bounding box. */ @@ -628,30 +605,31 @@ class ParticleFilterTracker : public Tracker { pcl::PassThrough pass_z_; /** \brief A list of the pointers to pointclouds. */ - std::vector transed_reference_vector_; + std::vector transed_reference_vector_{}; /** \brief Change detector used as a trigger to track. */ - typename pcl::octree::OctreePointCloudChangeDetector::Ptr change_detector_; + typename pcl::octree::OctreePointCloudChangeDetector::Ptr change_detector_{ + nullptr}; /** \brief A flag to be true when change of pointclouds is detected. */ - bool changed_; + bool changed_{false}; /** \brief A counter to skip change detection. */ - unsigned int change_counter_; + unsigned int change_counter_{0}; /** \brief Minimum points in a leaf when calling change detector. defaults * to 10. */ - unsigned int change_detector_filter_; + unsigned int change_detector_filter_{10}; /** \brief The number of interval frame to run change detection. defaults * to 10. */ - unsigned int change_detector_interval_; + unsigned int change_detector_interval_{10}; /** \brief Resolution of change detector. defaults to 0.01. */ - double change_detector_resolution_; + double change_detector_resolution_{0.01}; /** \brief The flag which will be true if using change detection. */ - bool use_change_detector_; + bool use_change_detector_{false}; }; } // namespace tracking } // namespace pcl diff --git a/visualization/include/pcl/visualization/common/actor_map.h b/visualization/include/pcl/visualization/common/actor_map.h index 57525d21029..8e23c6b40d3 100644 --- a/visualization/include/pcl/visualization/common/actor_map.h +++ b/visualization/include/pcl/visualization/common/actor_map.h @@ -67,7 +67,7 @@ namespace pcl using ColorHandlerConstPtr = ColorHandler::ConstPtr; public: - CloudActor () : color_handler_index_ (0), geometry_handler_index_ (0) {} + CloudActor () = default; virtual ~CloudActor () = default; @@ -81,10 +81,10 @@ namespace pcl std::vector color_handlers; /** \brief The active color handler. */ - int color_handler_index_; + int color_handler_index_{0}; /** \brief The active geometry handler. */ - int geometry_handler_index_; + int geometry_handler_index_{0}; /** \brief The viewpoint transformation matrix. */ vtkSmartPointer viewpoint_transformation_; diff --git a/visualization/include/pcl/visualization/histogram_visualizer.h b/visualization/include/pcl/visualization/histogram_visualizer.h index 6da04f7f103..901846341a8 100644 --- a/visualization/include/pcl/visualization/histogram_visualizer.h +++ b/visualization/include/pcl/visualization/histogram_visualizer.h @@ -229,7 +229,7 @@ namespace pcl struct ExitCallback : public vtkCommand { - ExitCallback () : his () {} + ExitCallback () = default; static ExitCallback* New () { @@ -239,14 +239,14 @@ namespace pcl void Execute (vtkObject*, unsigned long event_id, void*) override; - PCLHistogramVisualizer *his; + PCLHistogramVisualizer *his{nullptr}; }; /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ vtkSmartPointer exit_main_loop_timer_callback_; vtkSmartPointer exit_callback_; /** \brief Set to true when the histogram visualizer is ready to be terminated. */ - bool stopped_; + bool stopped_{false}; }; } } diff --git a/visualization/include/pcl/visualization/image_viewer.h b/visualization/include/pcl/visualization/image_viewer.h index dd65d37f9c8..de682f6d91c 100644 --- a/visualization/include/pcl/visualization/image_viewer.h +++ b/visualization/include/pcl/visualization/image_viewer.h @@ -920,7 +920,7 @@ namespace pcl protected: // types struct ExitMainLoopTimerCallback : public vtkCommand { - ExitMainLoopTimerCallback () : right_timer_id (), window () {} + ExitMainLoopTimerCallback () = default; static ExitMainLoopTimerCallback* New () { @@ -936,12 +936,12 @@ namespace pcl return; window->interactor_->TerminateApp (); } - int right_timer_id; - ImageViewer* window; + int right_timer_id{0}; + ImageViewer* window{nullptr}; }; struct ExitCallback : public vtkCommand { - ExitCallback () : window () {} + ExitCallback () = default; static ExitCallback* New () { @@ -955,7 +955,7 @@ namespace pcl window->stopped_ = true; window->interactor_->TerminateApp (); } - ImageViewer* window; + ImageViewer* window{nullptr}; }; private: @@ -1009,13 +1009,13 @@ namespace pcl boost::shared_array data_; /** \brief The data array (representing the image) size. Used internally. */ - std::size_t data_size_; + std::size_t data_size_{0}; /** \brief Set to false if the interaction loop is running. */ - bool stopped_; + bool stopped_{false}; /** \brief Global timer ID. Used in destructor only. */ - int timer_id_; + int timer_id_{0}; // /** \brief Internal blender used to overlay 2D geometry over the image. */ // vtkSmartPointer blend_; @@ -1029,7 +1029,7 @@ namespace pcl /** \brief Internal data array. Used everytime add***Image is called. * Cleared, everytime the render loop is executed. */ - std::vector image_data_; + std::vector image_data_{}; struct LayerComparator { diff --git a/visualization/include/pcl/visualization/interactor_style.h b/visualization/include/pcl/visualization/interactor_style.h index 5f9ae34bae9..4202b1952b7 100644 --- a/visualization/include/pcl/visualization/interactor_style.h +++ b/visualization/include/pcl/visualization/interactor_style.h @@ -112,12 +112,7 @@ namespace pcl static PCLVisualizerInteractorStyle *New (); /** \brief Empty constructor. */ - PCLVisualizerInteractorStyle () : - init_ (), win_height_ (), win_width_ (), win_pos_x_ (), win_pos_y_ (), - max_win_height_ (), max_win_width_ (), use_vbos_ (false), grid_enabled_ (), lut_enabled_ (), - stereo_anaglyph_mask_default_ (), - modifier_ (), camera_saved_ () - {} + PCLVisualizerInteractorStyle () = default; /** \brief Empty destructor */ ~PCLVisualizerInteractorStyle () override = default; @@ -260,36 +255,36 @@ namespace pcl protected: /** \brief Set to true after initialization is complete. */ - bool init_; + bool init_{false}; /** \brief Collection of vtkRenderers stored internally. */ vtkSmartPointer rens_; /** \brief Cloud actor map stored internally. */ - CloudActorMapPtr cloud_actors_; + CloudActorMapPtr cloud_actors_{nullptr}; /** \brief Shape map stored internally. */ - ShapeActorMapPtr shape_actors_; + ShapeActorMapPtr shape_actors_{nullptr}; /** \brief The current window width/height. */ - int win_height_, win_width_; + int win_height_{0}, win_width_{0}; /** \brief The current window position x/y. */ - int win_pos_x_, win_pos_y_; + int win_pos_x_{0}, win_pos_y_{0}; /** \brief The maximum resizeable window width/height. */ - int max_win_height_, max_win_width_; + int max_win_height_{0}, max_win_width_{0}; /** \brief Boolean that holds whether or not to use the vtkVertexBufferObjectMapper*/ - bool use_vbos_; + bool use_vbos_{false}; /** \brief Set to true if the grid actor is enabled. */ - bool grid_enabled_; + bool grid_enabled_{false}; /** \brief Actor for 2D grid on screen. */ vtkSmartPointer grid_actor_; /** \brief Set to true if the LUT actor is enabled. */ - bool lut_enabled_; + bool lut_enabled_{false}; /** \brief Actor for 2D lookup table on screen. */ vtkSmartPointer lut_actor_; @@ -364,20 +359,20 @@ namespace pcl } /** \brief True if we're using red-blue colors for anaglyphic stereo, false if magenta-green. */ - bool stereo_anaglyph_mask_default_; + bool stereo_anaglyph_mask_default_{false}; /** \brief A VTK Mouse Callback object, used for point picking. */ vtkSmartPointer mouse_callback_; /** \brief The keyboard modifier to use. Default: Alt. */ - InteractorKeyboardModifier modifier_; + InteractorKeyboardModifier modifier_{}; /** \brief Camera file for camera parameter saving/restoring. */ std::string camera_file_; /** \brief A \ref pcl::visualization::Camera for camera parameter saving/restoring. */ Camera camera_; /** \brief A \ref pcl::visualization::Camera is saved or not. */ - bool camera_saved_; + bool camera_saved_{false}; /** \brief The render window. * Only used when interactor maybe not available */ @@ -408,7 +403,7 @@ namespace pcl static PCLHistogramVisualizerInteractorStyle *New (); /** \brief Empty constructor. */ - PCLHistogramVisualizerInteractorStyle () : init_ (false) {} + PCLHistogramVisualizerInteractorStyle () = default; /** \brief Initialization routine. Must be called before anything else. */ void @@ -425,7 +420,7 @@ namespace pcl RenWinInteractMap wins_; /** \brief Set to true after initialization is complete. */ - bool init_; + bool init_{false}; /** \brief Interactor style internal method. Gets called whenever a key is pressed. */ void OnKeyDown () override; diff --git a/visualization/include/pcl/visualization/keyboard_event.h b/visualization/include/pcl/visualization/keyboard_event.h index 226ea40ea27..2fb9baa3f42 100644 --- a/visualization/include/pcl/visualization/keyboard_event.h +++ b/visualization/include/pcl/visualization/keyboard_event.h @@ -111,7 +111,7 @@ namespace pcl protected: bool action_; - unsigned int modifiers_; + unsigned int modifiers_{0}; unsigned char key_code_; std::string key_sym_; }; @@ -119,8 +119,8 @@ namespace pcl KeyboardEvent::KeyboardEvent (bool action, const std::string& key_sym, unsigned char key, bool alt, bool ctrl, bool shift) : action_ (action) - , modifiers_ (0) - , key_code_(key) + , + key_code_(key) , key_sym_ (key_sym) { if (alt) diff --git a/visualization/include/pcl/visualization/mouse_event.h b/visualization/include/pcl/visualization/mouse_event.h index 96413d3cc77..6bc4ee71b16 100644 --- a/visualization/include/pcl/visualization/mouse_event.h +++ b/visualization/include/pcl/visualization/mouse_event.h @@ -132,7 +132,7 @@ namespace pcl MouseButton button_; unsigned int pointer_x_; unsigned int pointer_y_; - unsigned int key_state_; + unsigned int key_state_{0}; bool selection_mode_; }; @@ -144,8 +144,8 @@ namespace pcl , button_ (button) , pointer_x_ (x) , pointer_y_ (y) - , key_state_ (0) - , selection_mode_ (selection_mode) + , + selection_mode_ (selection_mode) { if (alt) key_state_ = KeyboardEvent::Alt; diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 62e80ba99e3..8e5d42fa565 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -2070,27 +2070,27 @@ namespace pcl { static FPSCallback *New () { return (new FPSCallback); } - FPSCallback () : actor (), pcl_visualizer (), decimated (), last_fps(0.0f) {} + FPSCallback () = default; FPSCallback (const FPSCallback& src) = default; FPSCallback& operator = (const FPSCallback& src) { actor = src.actor; pcl_visualizer = src.pcl_visualizer; decimated = src.decimated; last_fps = src.last_fps; return (*this); } void Execute (vtkObject*, unsigned long event_id, void*) override; - vtkTextActor *actor; - PCLVisualizer* pcl_visualizer; - bool decimated; - float last_fps; + vtkTextActor *actor{nullptr}; + PCLVisualizer* pcl_visualizer{nullptr}; + bool decimated{false}; + float last_fps{0.0f}; }; /** \brief The FPSCallback object for the current visualizer. */ vtkSmartPointer update_fps_; /** \brief Set to false if the interaction loop is running. */ - bool stopped_; + bool stopped_{false}; /** \brief Global timer ID. Used in destructor only. */ - int timer_id_; + int timer_id_{0}; /** \brief Callback object enabling us to leave the main loop, when a timer fires. */ vtkSmartPointer exit_main_loop_timer_callback_; diff --git a/visualization/include/pcl/visualization/registration_visualizer.h b/visualization/include/pcl/visualization/registration_visualizer.h index 74996fc3d75..4a9b1d7a4e3 100644 --- a/visualization/include/pcl/visualization/registration_visualizer.h +++ b/visualization/include/pcl/visualization/registration_visualizer.h @@ -61,11 +61,9 @@ namespace pcl /** \brief Empty constructor. */ RegistrationVisualizer () : update_visualizer_ (), - first_update_flag_ (false), cloud_source_ (), cloud_target_ (), - cloud_intermediate_ (), - maximum_displayed_correspondences_ (0) + cloud_intermediate_ () {} ~RegistrationVisualizer () @@ -180,7 +178,7 @@ namespace pcl PointTarget> &cloud_tgt, const pcl::Indices &indices_tgt)> update_visualizer_; /** \brief Updates source and target point clouds only for the first update call. */ - bool first_update_flag_; + bool first_update_flag_{false}; /** \brief The local buffer for source point cloud. */ pcl::PointCloud cloud_source_; @@ -201,7 +199,7 @@ namespace pcl pcl::Indices cloud_target_indices_; /** \brief The maximum number of displayed correspondences. */ - std::size_t maximum_displayed_correspondences_; + std::size_t maximum_displayed_correspondences_{0}; }; } diff --git a/visualization/include/pcl/visualization/window.h b/visualization/include/pcl/visualization/window.h index d34448f362c..7db1e4331ed 100644 --- a/visualization/include/pcl/visualization/window.h +++ b/visualization/include/pcl/visualization/window.h @@ -184,8 +184,8 @@ namespace pcl void Execute (vtkObject*, unsigned long event_id, void* call_data) override; - int right_timer_id; - Window* window; + int right_timer_id{-1}; + Window* window{nullptr}; }; struct ExitCallback : public vtkCommand @@ -200,11 +200,11 @@ namespace pcl void Execute (vtkObject*, unsigned long event_id, void*) override; - Window* window; + Window* window{nullptr}; }; - bool stopped_; - int timer_id_; + bool stopped_{false}; + int timer_id_{0}; protected: // member fields boost::signals2::signal mouse_signal_; diff --git a/visualization/src/cloud_viewer.cpp b/visualization/src/cloud_viewer.cpp index afe884ac235..fae72d1ad4b 100644 --- a/visualization/src/cloud_viewer.cpp +++ b/visualization/src/cloud_viewer.cpp @@ -61,7 +61,7 @@ namespace pcl cloud_show (const std::string &cloud_name, typename CloudT::ConstPtr cloud, pcl::visualization::PCLVisualizer::Ptr viewer) : - cloud_name (cloud_name), cloud (cloud), viewer (viewer),popped_ (false) + cloud_name (cloud_name), cloud (cloud), viewer (viewer) {} template void @@ -96,7 +96,7 @@ namespace pcl std::string cloud_name; typename CloudT::ConstPtr cloud; pcl::visualization::PCLVisualizer::Ptr viewer; - bool popped_; + bool popped_{false}; }; using cca = pcl::PointCloud; @@ -137,7 +137,7 @@ struct pcl::visualization::CloudViewer::CloudViewer_impl { //////////////////////////////////////////////////////////////////////////////////////////// CloudViewer_impl (const std::string& window_name) : - window_name_ (window_name), has_cloud_ (false), quit_ (false) + window_name_ (window_name) { viewer_thread_ = std::thread (&CloudViewer_impl::operator(), this); while (!viewer_) @@ -251,8 +251,8 @@ struct pcl::visualization::CloudViewer::CloudViewer_impl pcl::visualization::PCLVisualizer::Ptr viewer_; std::mutex mtx_, spin_mtx_, c_mtx, once_mtx; std::thread viewer_thread_; - bool has_cloud_; - bool quit_; + bool has_cloud_{false}; + bool quit_{false}; std::list cloud_shows_; using CallableMap = std::map; CallableMap callables; diff --git a/visualization/src/histogram_visualizer.cpp b/visualization/src/histogram_visualizer.cpp index 9eae0418feb..7fbeab14dd3 100644 --- a/visualization/src/histogram_visualizer.cpp +++ b/visualization/src/histogram_visualizer.cpp @@ -56,8 +56,7 @@ using namespace std::chrono_literals; ////////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::PCLHistogramVisualizer::PCLHistogramVisualizer () : exit_main_loop_timer_callback_ (vtkSmartPointer::New ()), - exit_callback_ (vtkSmartPointer::New ()), - stopped_ () + exit_callback_ (vtkSmartPointer::New ()) { } diff --git a/visualization/src/image_viewer.cpp b/visualization/src/image_viewer.cpp index d27d4c8bd99..ca1f4579aec 100644 --- a/visualization/src/image_viewer.cpp +++ b/visualization/src/image_viewer.cpp @@ -61,10 +61,8 @@ pcl::visualization::ImageViewer::ImageViewer (const std::string& window_title) , ren_ (vtkSmartPointer::New ()) , slice_ (vtkSmartPointer::New ()) , interactor_style_ (vtkSmartPointer::New ()) - , data_size_ (0) - , stopped_ () - , timer_id_ () - , algo_ (vtkSmartPointer::New ()) + , + algo_ (vtkSmartPointer::New ()) { // Prepare for image flip algo_->SetInterpolationModeToCubic (); diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 06d8fbfbf11..85c4061fb45 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -182,8 +182,6 @@ pcl::visualization::details::fillCells(std::vector& lookup, const std::vect ///////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::PCLVisualizer::PCLVisualizer (const std::string &name, const bool create_interactor) : update_fps_ (vtkSmartPointer::New ()) - , stopped_ () - , timer_id_ () , rens_ (vtkSmartPointer::New ()) , win_ (vtkSmartPointer::New ()) , style_ (vtkSmartPointer::New ()) @@ -207,8 +205,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (const std::string &name, const ///////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, const std::string &name, PCLVisualizerInteractorStyle* style, const bool create_interactor) : update_fps_ (vtkSmartPointer::New ()) - , stopped_ () - , timer_id_ () , rens_ (vtkSmartPointer::New ()) , win_ (vtkSmartPointer::New ()) , style_ (style) @@ -239,8 +235,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, const pcl::visualization::PCLVisualizer::PCLVisualizer (vtkSmartPointer ren, vtkSmartPointer wind, const std::string &name, const bool create_interactor) : update_fps_ (vtkSmartPointer::New ()) - , stopped_ () - , timer_id_ () , rens_ (vtkSmartPointer::New ()) , win_ (wind) , style_ (vtkSmartPointer::New ()) @@ -264,8 +258,6 @@ pcl::visualization::PCLVisualizer::PCLVisualizer (vtkSmartPointer r pcl::visualization::PCLVisualizer::PCLVisualizer (int &argc, char **argv, vtkSmartPointer ren, vtkSmartPointer wind, const std::string &name, PCLVisualizerInteractorStyle* style, const bool create_interactor) : update_fps_ (vtkSmartPointer::New ()) - , stopped_ () - , timer_id_ () , rens_ (vtkSmartPointer::New ()) , win_ (wind) , style_ (style) diff --git a/visualization/src/window.cpp b/visualization/src/window.cpp index 0e1e0a40c9b..652d6efabe9 100644 --- a/visualization/src/window.cpp +++ b/visualization/src/window.cpp @@ -50,9 +50,8 @@ ///////////////////////////////////////////////////////////////////////////////////////////// pcl::visualization::Window::Window (const std::string& window_name) - : stopped_ () - , timer_id_ () - , mouse_command_ (vtkCallbackCommand::New ()) + : + mouse_command_ (vtkCallbackCommand::New ()) , keyboard_command_ (vtkCallbackCommand::New ()) , style_ (vtkSmartPointer::New ()) , rens_ (vtkSmartPointer::New ()) @@ -322,10 +321,7 @@ pcl::visualization::Window::KeyboardCallback (vtkObject*, unsigned long eid, voi } ///////////////////////////////////////////////////////////////////////////////////////////// -pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback () - : right_timer_id (-1), window (nullptr) -{ -} +pcl::visualization::Window::ExitMainLoopTimerCallback::ExitMainLoopTimerCallback () = default; ///////////////////////////////////////////////////////////////////////////////////////////// void @@ -342,10 +338,7 @@ pcl::visualization::Window::ExitMainLoopTimerCallback::Execute ( } ///////////////////////////////////////////////////////////////////////////////////////////// -pcl::visualization::Window::ExitCallback::ExitCallback () - : window (nullptr) -{ -} +pcl::visualization::Window::ExitCallback::ExitCallback () = default; ///////////////////////////////////////////////////////////////////////////////////////////// void From 3216fcddb185982f4c1a4f8619634984937995ac Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 22 Dec 2023 14:30:21 +0100 Subject: [PATCH 173/288] Add changelog for 1.14.0 --- CHANGES.md | 123 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 123 insertions(+) diff --git a/CHANGES.md b/CHANGES.md index 06a63c1c420..1faa1b86236 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -1,5 +1,128 @@ # ChangeList +## = 1.14.0 (03 January 2024) = + +### Notable changes + +**New features** *added to PCL* + +* **[registration]** GICP: add Newton optimizer [[#5825](https://github.com/PointCloudLibrary/pcl/pull/5825)] + +**Deprecation** *of public APIs, scheduled to be removed after two minor releases* + +* **[segmentation]** Deprecate CrfNormalSegmentation [[#5795](https://github.com/PointCloudLibrary/pcl/pull/5795)] +* **[sample_consensus]** Deprecate SampleConsensusModelStick [[#5796](https://github.com/PointCloudLibrary/pcl/pull/5796)] + +**Removal** *of the public APIs deprecated in previous releases* + +* remove deprecated code for 1.14 release [[#5872](https://github.com/PointCloudLibrary/pcl/pull/5872)] + +**Behavior changes** *in classes, apps, or tools* + +* **[common]** Fix register macros to match struct definitions [[#5604](https://github.com/PointCloudLibrary/pcl/pull/5604)] +* **[registration]** ICP: remove possibly inappropriate default setting of rotation convergence threshold when user does not set it. [[#5755](https://github.com/PointCloudLibrary/pcl/pull/5755)] +* **[surface]** MovingLeastSquares: reduce the number of instantiations to reduce com… [[#5764](https://github.com/PointCloudLibrary/pcl/pull/5764)] +* **[filters]** Fix behaviour of BoxClipper3D [[#5769](https://github.com/PointCloudLibrary/pcl/pull/5769)] +* **[surface][cmake]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)] + +### Changes grouped by module + +#### CMake: + +* Move /bigobj flag (Windows/MSVC) [[#5718](https://github.com/PointCloudLibrary/pcl/pull/5718)] +* Make OpenMP available in downstream projects [[#5744](https://github.com/PointCloudLibrary/pcl/pull/5744)] +* Eigen: switch to imported modules and NO_MODULE [[#5613](https://github.com/PointCloudLibrary/pcl/pull/5613)] +* Make Flann optional [[#5772](https://github.com/PointCloudLibrary/pcl/pull/5772)] +* **[behavior change]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)] +* fix build with GNU13 and Eigen3.4 [[#5783](https://github.com/PointCloudLibrary/pcl/pull/5783)] +* Fix Eigen alignment problem when user project is compiled as C++17 or newer [[#5793](https://github.com/PointCloudLibrary/pcl/pull/5793)] +* Allow compilation with Boost 1.83 [[#5810](https://github.com/PointCloudLibrary/pcl/pull/5810)] +* Use real ALIAS target for flann to preserve properties on original target. [[#5861](https://github.com/PointCloudLibrary/pcl/pull/5861)] + +#### libpcl_common: + +* **[behavior change]** Fix register macros to match struct definitions [[#5604](https://github.com/PointCloudLibrary/pcl/pull/5604)] +* Add computeCentroidAndOBB function [[#5690](https://github.com/PointCloudLibrary/pcl/pull/5690)] +* Remove unnecessary pseudo-instantiations of checkCoordinateSystem [[#5765](https://github.com/PointCloudLibrary/pcl/pull/5765)] + +#### libpcl_features: + +* NormalEstimationOMP: use dynamic scheduling for faster computation [[#5775](https://github.com/PointCloudLibrary/pcl/pull/5775)] + +#### libpcl_filters: + +* **[behavior change]** Fix behaviour of BoxClipper3D [[#5769](https://github.com/PointCloudLibrary/pcl/pull/5769)] +* Let setInputCloud of search methods indicate success or failure [[#5840](https://github.com/PointCloudLibrary/pcl/pull/5840)] +* VoxelGridOcclusionEstimation: fix behaviour if sensor origin is inside the voxel grid [[#5867](https://github.com/PointCloudLibrary/pcl/pull/5867)] + +#### libpcl_gpu: + +* Some improvements to gpu/segmentation [[#5813](https://github.com/PointCloudLibrary/pcl/pull/5813)] + +#### libpcl_io: + +* Enable writing very large PCD files on Windows [[#5675](https://github.com/PointCloudLibrary/pcl/pull/5675)] +* Make io more locale invariant [[#5699](https://github.com/PointCloudLibrary/pcl/pull/5699)] +* Fix reading of origin and orientation from PLY files [[#5766](https://github.com/PointCloudLibrary/pcl/pull/5766)] +* Add missing cassert include [[#5812](https://github.com/PointCloudLibrary/pcl/pull/5812)] +* Fix PCD load crashes on empty files [[#5855](https://github.com/PointCloudLibrary/pcl/pull/5855)] +* Fix freeze in hdl_grabber.cpp [[#5826](https://github.com/PointCloudLibrary/pcl/pull/5826)] + +#### libpcl_octree: + +* Octree: grow in positive direction instead of negative [[#5653](https://github.com/PointCloudLibrary/pcl/pull/5653)] + +#### libpcl_registration: + +* **[behavior change]** ICP: remove possibly inappropriate default setting of rotation convergence threshold when user does not set it. [[#5755](https://github.com/PointCloudLibrary/pcl/pull/5755)] +* Improve PPFRegistration [[#5767](https://github.com/PointCloudLibrary/pcl/pull/5767)] +* **[new feature]** GICP: add Newton optimizer [[#5825](https://github.com/PointCloudLibrary/pcl/pull/5825)] +* Add instantiations for ICP and TransformationEstimationSVD [[#5894](https://github.com/PointCloudLibrary/pcl/pull/5894)] + +#### libpcl_sample_consensus: + +* Improve optimizeModelCoefficients for cone, cylinder, sphere models [[#5790](https://github.com/PointCloudLibrary/pcl/pull/5790)] +* **[deprecation]** Deprecate SampleConsensusModelStick [[#5796](https://github.com/PointCloudLibrary/pcl/pull/5796)] +* sac_model_cylinder: fix bug in projectPointToCylinder function [[#5821](https://github.com/PointCloudLibrary/pcl/pull/5821)] +* Replace std::time with std::random_device as seed for random number generator [[#5824](https://github.com/PointCloudLibrary/pcl/pull/5824)] +* MSAC and RMSAC: fix check array distances empty [[#5849](https://github.com/PointCloudLibrary/pcl/pull/5849)] + +#### libpcl_search: + +* OrganizedNeighbor: add additional check to make sure the cloud is sui… [[#5729](https://github.com/PointCloudLibrary/pcl/pull/5729)] +* Modify FlannSearch to return Indices of Point Cloud (issue #5774) [[#5780](https://github.com/PointCloudLibrary/pcl/pull/5780)] +* Let setInputCloud of search methods indicate success or failure [[#5840](https://github.com/PointCloudLibrary/pcl/pull/5840)] + +#### libpcl_segmentation: + +* ApproximateProgressiveMorphologicalFilter: check for finite-ness [[#5756](https://github.com/PointCloudLibrary/pcl/pull/5756)] +* **[deprecation]** Deprecate CrfNormalSegmentation [[#5795](https://github.com/PointCloudLibrary/pcl/pull/5795)] + +#### libpcl_surface: + +* ConvexHull verbose info on stdout enabled only by pcl::console::L_DEBUG [[#5689](https://github.com/PointCloudLibrary/pcl/pull/5689)] +* **[behavior change]** MovingLeastSquares: reduce the number of instantiations to reduce com… [[#5764](https://github.com/PointCloudLibrary/pcl/pull/5764)] +* **[behavior change]** Prefer system zlib over vendored copy in opennurbs [[#5684](https://github.com/PointCloudLibrary/pcl/pull/5684)] +* Fix memory leak bug of poisson reconstruction [[#5832](https://github.com/PointCloudLibrary/pcl/pull/5832)] +* Speed up nurbs surface fitting [[#5873](https://github.com/PointCloudLibrary/pcl/pull/5873)] + +#### libpcl_visualization: + +* Improve spinOnce documentation [[#5716](https://github.com/PointCloudLibrary/pcl/pull/5716)] + +#### PCL Apps: + +* Add missing includes in cloud composer app [[#5777](https://github.com/PointCloudLibrary/pcl/pull/5777)] + +#### PCL Docs: + +* Add readthedocs config files [[#5878](https://github.com/PointCloudLibrary/pcl/pull/5878)] + +#### CI: + +* **[new feature][removal]** Remove 18.04 as its EOL. [[#5799](https://github.com/PointCloudLibrary/pcl/pull/5799)] +* Use new windows images for CI [[#5892](https://github.com/PointCloudLibrary/pcl/pull/5892)] + ## = 1.13.1 (10 May 2023) = ### Notable changes From a8db4ea6f24451f13d165267d073559926287a6e Mon Sep 17 00:00:00 2001 From: luzpaz Date: Sun, 24 Dec 2023 11:14:54 +0000 Subject: [PATCH 174/288] Fix various typos Found via `codespell -q 3 -S ./CHANGES.md,./surface/src/3rdparty,./surface/include/pcl/surface/3rdparty,./recognition/include/pcl/recognition/3rdparty -L afile,ang,bu,childs,coo,currect,dosen,frome,gool,hsi,indeces,ihs,indext,isnt,ith,lod,meshe,metre,metres,nd,opps,ot,shs,te,vertexes` --- .../pcl/apps/in_hand_scanner/in_hand_scanner.h | 2 +- .../include/pcl/apps/in_hand_scanner/opengl_viewer.h | 2 +- .../pcl/apps/point_cloud_editor/select2DTool.h | 2 +- .../include/pcl/apps/point_cloud_editor/selection.h | 2 +- .../apps/point_cloud_editor/selectionTransformTool.h | 2 +- apps/src/face_detection/openni_face_detection.cpp | 2 +- apps/src/openni_grab_images.cpp | 2 +- apps/src/render_views_tesselated_sphere.cpp | 4 ++-- cmake/Modules/NSIS.template.in | 2 +- common/include/pcl/common/impl/centroid.hpp | 4 ++-- common/include/pcl/common/intersections.h | 2 +- common/include/pcl/pcl_macros.h | 2 +- doc/advanced/content/index.rst | 2 +- doc/tutorials/content/compiling_pcl_windows.rst | 2 +- .../ensenso_cameras/ensenso_cloud_images_viewer.cpp | 2 +- doc/tutorials/content/walkthrough.rst | 2 +- examples/segmentation/example_cpc_segmentation.cpp | 2 +- examples/segmentation/example_lccp_segmentation.cpp | 2 +- filters/include/pcl/filters/crop_hull.h | 2 +- filters/include/pcl/filters/impl/pyramid.hpp | 6 +++--- gpu/features/src/fpfh.cu | 2 +- gpu/kinfu/tools/kinfu_app.cpp | 2 +- gpu/kinfu/tools/kinfu_app_sim.cpp | 2 +- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 2 +- gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp | 2 +- gpu/octree/include/pcl/gpu/octree/octree.hpp | 2 +- gpu/people/include/pcl/gpu/people/label_common.h | 2 +- .../include/pcl/gpu/utils/device/vector_math.hpp | 2 +- io/include/pcl/io/openni_camera/openni_device.h | 2 +- io/src/vtk_lib_io.cpp | 2 +- kdtree/include/pcl/kdtree/kdtree_flann.h | 4 ++-- octree/octree.doxy | 2 +- outofcore/include/pcl/outofcore/octree_base.h | 6 +++--- .../include/pcl/recognition/impl/hv/hv_go.hpp | 4 ++-- .../pcl/recognition/impl/implicit_shape_model.hpp | 2 +- .../include/pcl/recognition/implicit_shape_model.h | 4 ++-- registration/include/pcl/registration/ia_fpcs.h | 2 +- .../include/pcl/registration/impl/ia_fpcs.hpp | 2 +- .../include/pcl/registration/impl/ia_kfpcs.hpp | 2 +- .../impl/sample_consensus_prerejective.hpp | 2 +- search/include/pcl/search/organized.h | 2 +- .../organized_multi_plane_segmentation.h | 2 +- simulation/tools/sim_viewer.cpp | 12 ++++++------ surface/include/pcl/surface/grid_projection.h | 2 +- test/features/test_curvatures_estimation.cpp | 2 +- test/octree/test_octree.cpp | 6 +++--- test/registration/test_correspondence_estimation.cpp | 2 +- test/registration/test_fpcs_ia.cpp | 2 +- test/registration/test_registration.cpp | 2 +- test/registration/test_registration_api.cpp | 2 +- test/segmentation/test_segmentation.cpp | 2 +- tools/cluster_extraction.cpp | 2 +- tools/image_viewer.cpp | 2 +- tools/openni_image.cpp | 2 +- tracking/include/pcl/tracking/particle_filter.h | 2 +- tracking/include/pcl/tracking/pyramidal_klt.h | 2 +- .../include/pcl/visualization/pcl_visualizer.h | 2 +- visualization/src/pcl_visualizer.cpp | 6 +++--- 58 files changed, 76 insertions(+), 76 deletions(-) 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 389bc815349..b3d2abcf9e3 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 @@ -253,7 +253,7 @@ public Q_SLOTS: void drawText(); - /** \brief Actual implementeation of startGrabber (needed so it can be run in a + /** \brief Actual implementation of startGrabber (needed so it can be run in a * different thread and doesn't block the application when starting up). */ void startGrabberImpl(); 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 c1c86448c06..4ce4e7ca95a 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 @@ -118,7 +118,7 @@ class PCL_EXPORTS OpenGLViewer : public QOpenGLWidget { /** \brief How to draw the mesh. */ enum MeshRepresentation { MR_POINTS, /**< Draw the points. */ - MR_EDGES, /**< Wireframe represen of the mesh. */ + MR_EDGES, /**< Wireframe representation of the mesh. */ MR_FACES /**< Draw the faces of the mesh without edges. */ }; diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h index 2052f10e8e7..6243fcc65a6 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/select2DTool.h @@ -135,7 +135,7 @@ class Select2DTool : public ToolInterface /// @brief highlight all the points in the rubber band. /// @detail draw the cloud using a stencil buffer. During this time, the - /// points that are highlighted will not be recorded by the selecion object. + /// points that are highlighted will not be recorded by the selection object. /// @param viewport the viewport obtained from GL void highlightPoints (GLint* viewport) const; 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 7855e1711cf..d0e471517fe 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 @@ -35,7 +35,7 @@ /// @file selection.h /// @details A Selection object maintains the set of indices of points from a -/// point cloud that have been identifed by the selection tools. +/// point cloud that have been identified by the selection tools. /// @author Yue Li and Matthew Hielsberg #pragma once diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selectionTransformTool.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selectionTransformTool.h index d871a44a602..d555f007e54 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selectionTransformTool.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/selectionTransformTool.h @@ -87,7 +87,7 @@ class SelectionTransformTool : public ToolInterface /// mouse screen coordinates. Then depending on the passed modifiers, the /// transformation matrix is computed correspondingly. If CONTROL is pressed /// the selection will be translated (panned) parallel to the view plane. If - /// ALT is pressed the selection witll be translated along the z-axis + /// ALT is pressed the selection will be translated along the z-axis /// perpendicular to the view plane. If no key modifiers is pressed the /// selection will be rotated. /// @param x the x value of the mouse screen coordinates. diff --git a/apps/src/face_detection/openni_face_detection.cpp b/apps/src/face_detection/openni_face_detection.cpp index 5a12081eb6a..6574d1efab8 100644 --- a/apps/src/face_detection/openni_face_detection.cpp +++ b/apps/src/face_detection/openni_face_detection.cpp @@ -19,7 +19,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf, bool heat_map = false, bool show_votes = f OpenNIFrameSource::OpenNIFrameSource camera; OpenNIFrameSource::PointCloudPtr scene_vis; - pcl::visualization::PCLVisualizer vis("Face dection"); + pcl::visualization::PCLVisualizer vis("Face detection"); vis.addCoordinateSystem(0.1, "global"); // keyboard callback to stop getting frames and finalize application diff --git a/apps/src/openni_grab_images.cpp b/apps/src/openni_grab_images.cpp index 7a864567129..edb5d549694 100644 --- a/apps/src/openni_grab_images.cpp +++ b/apps/src/openni_grab_images.cpp @@ -254,7 +254,7 @@ class OpenNIGrabFrame { depth_image->getWidth(), depth_image->getHeight(), std::numeric_limits::min(), - // Scale so that the colors look brigher on screen + // Scale so that the colors look brighter on screen std::numeric_limits::max() / 10, true); diff --git a/apps/src/render_views_tesselated_sphere.cpp b/apps/src/render_views_tesselated_sphere.cpp index 896b101544e..9f6ba71ef8c 100644 --- a/apps/src/render_views_tesselated_sphere.cpp +++ b/apps/src/render_views_tesselated_sphere.cpp @@ -409,7 +409,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() trans_view(x, y) = float(view_transform->GetElement(x, y)); // NOTE: vtk view coordinate system is different than the standard camera - // coordinates (z forward, y down, x right) thus, the fliping in y and z + // coordinates (z forward, y down, x right) thus, the flipping in y and z for (auto& point : cloud->points) { point.getVector4fMap() = trans_view * point.getVector4fMap(); point.y *= -1.0f; @@ -430,7 +430,7 @@ pcl::apps::RenderViewsTesselatedSphere::generateViews() transOCtoCC->Concatenate(cam_tmp->GetViewTransformMatrix()); // NOTE: vtk view coordinate system is different than the standard camera - // coordinates (z forward, y down, x right) thus, the fliping in y and z + // coordinates (z forward, y down, x right) thus, the flipping in y and z vtkSmartPointer cameraSTD = vtkSmartPointer::New(); cameraSTD->Identity(); cameraSTD->SetElement(0, 0, 1); diff --git a/cmake/Modules/NSIS.template.in b/cmake/Modules/NSIS.template.in index e344c8d84de..a1a1034ecae 100644 --- a/cmake/Modules/NSIS.template.in +++ b/cmake/Modules/NSIS.template.in @@ -386,7 +386,7 @@ Function un.RemoveFromPath FunctionEnd ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; -; Uninstall sutff +; Uninstall stuff ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; ########################################### diff --git a/common/include/pcl/common/impl/centroid.hpp b/common/include/pcl/common/impl/centroid.hpp index 36d4317a14e..30697e79e3a 100644 --- a/common/include/pcl/common/impl/centroid.hpp +++ b/common/include/pcl/common/impl/centroid.hpp @@ -690,7 +690,7 @@ computeCentroidAndOBB (const pcl::PointCloud &cloud, //obb_rotational_matrix.col(1)==middle_axis //obb_rotational_matrix.col(2)==minor_axis - //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference + //Transforming the point cloud in the (Centroid, ma-mi-mi_axis) reference //with homogeneous matrix //[R^t , -R^t*Centroid ] //[0 , 1 ] @@ -824,7 +824,7 @@ computeCentroidAndOBB (const pcl::PointCloud &cloud, //obb_rotational_matrix.col(1)==middle_axis //obb_rotational_matrix.col(2)==minor_axis - //Trasforming the point cloud in the (Centroid, ma-mi-mi_axis) reference + //Transforming the point cloud in the (Centroid, ma-mi-mi_axis) reference //with homogeneous matrix //[R^t , -R^t*Centroid ] //[0 , 1 ] diff --git a/common/include/pcl/common/intersections.h b/common/include/pcl/common/intersections.h index 28a3f80e828..ff227ab4382 100644 --- a/common/include/pcl/common/intersections.h +++ b/common/include/pcl/common/intersections.h @@ -81,7 +81,7 @@ namespace pcl * \note Described in: "Intersection of Two Planes, John Krumm, Microsoft Research, Redmond, WA, USA" * \param[in] plane_a coefficients of plane A and plane B in the form ax + by + cz + d = 0 * \param[in] plane_b coefficients of line where line.tail<3>() = direction vector and - * line.head<3>() the point on the line clossest to (0, 0, 0) + * line.head<3>() the point on the line closest to (0, 0, 0) * \param[out] line the intersected line to be filled * \param[in] angular_tolerance tolerance in radians * \return true if succeeded/planes aren't parallel diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index da487b5e1bc..608b3ecdfc4 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -82,7 +82,7 @@ // MSVC < 2019 have issues: // * can't short-circuiting logic in macros // * don't define standard macros -// => this leads to annyoing C4067 warnings (see https://developercommunity.visualstudio.com/content/problem/327796/-has-cpp-attribute-emits-warning-is-wrong-highligh.html) +// => this leads to annoying C4067 warnings (see https://developercommunity.visualstudio.com/content/problem/327796/-has-cpp-attribute-emits-warning-is-wrong-highligh.html) #if defined(_MSC_VER) // nvcc on msvc can't work with [[deprecated]] #if !defined(__CUDACC__) diff --git a/doc/advanced/content/index.rst b/doc/advanced/content/index.rst index 93d4a1a1f18..d89455457c8 100644 --- a/doc/advanced/content/index.rst +++ b/doc/advanced/content/index.rst @@ -98,7 +98,7 @@ development that everyone should follow: Committing changes to the git master ------------------------------------ -In order to oversee the commit messages more easier and that the changelist looks homogenous please keep the following format: +In order to oversee the commit messages more easier and that the changelist looks homogeneous please keep the following format: "* X in @@ (#)" diff --git a/doc/tutorials/content/compiling_pcl_windows.rst b/doc/tutorials/content/compiling_pcl_windows.rst index 7a7624b23fb..0f3577cb921 100644 --- a/doc/tutorials/content/compiling_pcl_windows.rst +++ b/doc/tutorials/content/compiling_pcl_windows.rst @@ -132,7 +132,7 @@ CMake window. Let's check also the `Advanced` checkbox to show some advanced CMa variable value, we can either browse the CMake variables to look for it, or we can use the `Search:` field to type the variable name. .. image:: images/windows/cmake_grouped_advanced.png - :alt: CMake groupped and advanced variables + :alt: CMake grouped and advanced variables :align: center Let's check whether CMake did actually find the needed third party dependencies or not : diff --git a/doc/tutorials/content/sources/ensenso_cameras/ensenso_cloud_images_viewer.cpp b/doc/tutorials/content/sources/ensenso_cameras/ensenso_cloud_images_viewer.cpp index 6d4d10a6984..1904f620226 100644 --- a/doc/tutorials/content/sources/ensenso_cameras/ensenso_cloud_images_viewer.cpp +++ b/doc/tutorials/content/sources/ensenso_cameras/ensenso_cloud_images_viewer.cpp @@ -27,7 +27,7 @@ typedef pcl::PointXYZ PointT; /** @brief Convenience typedef */ typedef pcl::PointCloud PointCloudT; -/** @brief Convenience typdef for the Ensenso grabber callback */ +/** @brief Convenience typedef for the Ensenso grabber callback */ typedef std::pair PairOfImages; typedef pcl::shared_ptr PairOfImagesPtr; diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index 971d9a8f78e..e8fecd9e642 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -291,7 +291,7 @@ Octree The *octree* library provides efficient methods for creating a hierarchical tree data structure from point cloud data. This enables spatial partitioning, downsampling and search operations on the point data set. Each octree node has either eight children or no children. The root node describes a cubic bounding box which encapsulates all points. At every tree level, this space becomes subdivided by a factor of 2 which results in an increased voxel resolution. - The *octree* implementation provides efficient nearest neighbor search routines, such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and “Neighbors within Radius Search”. It automatically adjusts its dimension to the point data set. A set of leaf node classes provide additional functionality, such as spacial "occupancy" and "point density per voxel" checks. Functions for serialization and deserialization enable to efficiently encode the octree structure into a binary format. Furthermore, a memory pool implementation reduces expensive memory allocation and deallocation operations in scenarios where octrees needs to be created at high rate. + The *octree* implementation provides efficient nearest neighbor search routines, such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and “Neighbors within Radius Search”. It automatically adjusts its dimension to the point data set. A set of leaf node classes provide additional functionality, such as spatial "occupancy" and "point density per voxel" checks. Functions for serialization and deserialization enable to efficiently encode the octree structure into a binary format. Furthermore, a memory pool implementation reduces expensive memory allocation and deallocation operations in scenarios where octrees needs to be created at high rate. The following figure illustrates the voxel bounding boxes of an octree nodes at lowest tree level. The octree voxels are surrounding every 3D point from the Stanford bunny's surface. The red dots represent the point data. This image is created with the `octree_viewer`_. diff --git a/examples/segmentation/example_cpc_segmentation.cpp b/examples/segmentation/example_cpc_segmentation.cpp index bbb357f673a..c65e2c3a9c5 100644 --- a/examples/segmentation/example_cpc_segmentation.cpp +++ b/examples/segmentation/example_cpc_segmentation.cpp @@ -369,7 +369,7 @@ CPCSegmentation Parameters: \n\ std::multimapsupervoxel_adjacency; super.getSupervoxelAdjacency (supervoxel_adjacency); - /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visulization) + /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visualization) pcl::PointCloud::Ptr sv_centroid_normal_cloud = pcl::SupervoxelClustering::makeSupervoxelNormalCloud (supervoxel_clusters); /// Set parameters for LCCP preprocessing and CPC (CPC inherits from LCCP, thus it includes LCCP's functionality) diff --git a/examples/segmentation/example_lccp_segmentation.cpp b/examples/segmentation/example_lccp_segmentation.cpp index 09a811e567e..e7e7df35695 100644 --- a/examples/segmentation/example_lccp_segmentation.cpp +++ b/examples/segmentation/example_lccp_segmentation.cpp @@ -296,7 +296,7 @@ LCCPSegmentation Parameters: \n\ std::multimap supervoxel_adjacency; super.getSupervoxelAdjacency (supervoxel_adjacency); - /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visulization) + /// Get the cloud of supervoxel centroid with normals and the colored cloud with supervoxel coloring (this is used for visualization) pcl::PointCloud::Ptr sv_centroid_normal_cloud = pcl::SupervoxelClustering::makeSupervoxelNormalCloud (supervoxel_clusters); /// The Main Step: Perform LCCPSegmentation diff --git a/filters/include/pcl/filters/crop_hull.h b/filters/include/pcl/filters/crop_hull.h index 081c2f5d38e..9ec44921a30 100644 --- a/filters/include/pcl/filters/crop_hull.h +++ b/filters/include/pcl/filters/crop_hull.h @@ -109,7 +109,7 @@ namespace pcl * This should be set to correspond to the dimensionality of the * convex/concave hull produced by the pcl::ConvexHull and * pcl::ConcaveHull classes. - * \param[in] dim Dimensionailty of the hull used to filter points. + * \param[in] dim Dimensionality of the hull used to filter points. */ inline void setDim (int dim) diff --git a/filters/include/pcl/filters/impl/pyramid.hpp b/filters/include/pcl/filters/impl/pyramid.hpp index f4fe5a46438..dc47d935320 100644 --- a/filters/include/pcl/filters/impl/pyramid.hpp +++ b/filters/include/pcl/filters/impl/pyramid.hpp @@ -55,13 +55,13 @@ Pyramid::initCompute () { if (!input_->isOrganized ()) { - PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ()); + PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ()); return (false); } if (levels_ < 2) { - PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ()); + PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should be at least 2!\n", getClassName ().c_str ()); return (false); } @@ -71,7 +71,7 @@ Pyramid::initCompute () if (levels_ > 4) { - PCL_ERROR ("[pcl::fileters::%s::initCompute] Number of levels should not exceed 4!\n", getClassName ().c_str ()); + PCL_ERROR ("[pcl::filters::%s::initCompute] Number of levels should not exceed 4!\n", getClassName ().c_str ()); return (false); } diff --git a/gpu/features/src/fpfh.cu b/gpu/features/src/fpfh.cu index d2ae7fda43d..211da113cc4 100644 --- a/gpu/features/src/fpfh.cu +++ b/gpu/features/src/fpfh.cu @@ -297,7 +297,7 @@ namespace pcl template __device__ __forceinline__ void normalizeFeature(volatile float *feature, volatile float *buffer, int lane) const { - //nomalize buns + //normalize buns float value = (lane < bins) ? feature[lane] : 0.f; float sum = Warp::reduce(buffer, value, plus()); diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index ffdb154ffaa..3ed2e31e8f9 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -1246,7 +1246,7 @@ main (int argc, char* argv[]) pcl::gpu::printShortCudaDeviceInfo (device); // if (checkIfPreFermiGPU(device)) -// return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler arhitectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1; +// return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler architectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1; std::unique_ptr capture; diff --git a/gpu/kinfu/tools/kinfu_app_sim.cpp b/gpu/kinfu/tools/kinfu_app_sim.cpp index 383ecb83758..4d4bdd8bffd 100644 --- a/gpu/kinfu/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu/tools/kinfu_app_sim.cpp @@ -1357,7 +1357,7 @@ print_cli_help () std::cout << ""; std::cout << " For RGBD benchmark (Requires OpenCV):" << std::endl; std::cout << " -eval [-match_file ]" << std::endl; - std::cout << " For Simuation (Requires pcl::simulation):" << std::endl; + std::cout << " For Simulation (Requires pcl::simulation):" << std::endl; std::cout << " -plyfile : path to ply file for simulation testing " << std::endl; return 0; diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index 28278195e42..bc455e17ca6 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -1330,7 +1330,7 @@ main (int argc, char* argv[]) pcl::gpu::printShortCudaDeviceInfo (device); // if (checkIfPreFermiGPU(device)) - // return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler arhitectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1; + // return std::cout << std::endl << "Kinfu is supported only for Fermi and Kepler architectures. It is not even compiled for pre-Fermi by default. Exiting..." << std::endl, 1; pcl::shared_ptr capture; bool triggered_capture = false; diff --git a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp index b1ff4f56b99..6ad7c1d60c3 100644 --- a/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp +++ b/gpu/kinfu_large_scale/tools/kinfu_app_sim.cpp @@ -1382,7 +1382,7 @@ print_cli_help () std::cout << ""; std::cout << " For RGBD benchmark (Requires OpenCV):" << std::endl; std::cout << " -eval [-match_file ]" << std::endl; - std::cout << " For Simuation (Requires pcl::simulation):" << std::endl; + std::cout << " For Simulation (Requires pcl::simulation):" << std::endl; std::cout << " -plyfile : path to ply file for simulation testing " << std::endl; return 0; diff --git a/gpu/octree/include/pcl/gpu/octree/octree.hpp b/gpu/octree/include/pcl/gpu/octree/octree.hpp index 5e222a5c38c..9f827e0f3a3 100644 --- a/gpu/octree/include/pcl/gpu/octree/octree.hpp +++ b/gpu/octree/include/pcl/gpu/octree/octree.hpp @@ -164,7 +164,7 @@ namespace pcl */ void nearestKSearchBatch(const Queries& queries, int k, NeighborIndices& results, ResultSqrDists& sqr_distances) const; - /** \brief Desroys octree and release all resources */ + /** \brief Destroys octree and release all resources */ void clear(); private: void *impl; diff --git a/gpu/people/include/pcl/gpu/people/label_common.h b/gpu/people/include/pcl/gpu/people/label_common.h index 417fd3c625e..3391871107a 100644 --- a/gpu/people/include/pcl/gpu/people/label_common.h +++ b/gpu/people/include/pcl/gpu/people/label_common.h @@ -69,7 +69,7 @@ namespace pcl enum { XML_VERSION = 1}; /** \brief This indicates the current used xml file version (for people lib only) **/ enum { NUM_ATTRIBS = 2000 }; - enum { NUM_LABELS = 32 }; /** \brief Our code is forseen to use maximal use 32 labels **/ + enum { NUM_LABELS = 32 }; /** \brief Our code is foreseen to use maximal use 32 labels **/ /** @todo implement label 25 to 29 **/ enum part_t diff --git a/gpu/utils/include/pcl/gpu/utils/device/vector_math.hpp b/gpu/utils/include/pcl/gpu/utils/device/vector_math.hpp index aee46375cae..36647dcf733 100644 --- a/gpu/utils/include/pcl/gpu/utils/device/vector_math.hpp +++ b/gpu/utils/include/pcl/gpu/utils/device/vector_math.hpp @@ -103,7 +103,7 @@ namespace pcl //////////////////////////////// - // tempalted operations vectors + // templated operations vectors template __device__ __host__ __forceinline__ float norm(const T& val) { diff --git a/io/include/pcl/io/openni_camera/openni_device.h b/io/include/pcl/io/openni_camera/openni_device.h index ddda24b0cdc..739d24bd101 100644 --- a/io/include/pcl/io/openni_camera/openni_device.h +++ b/io/include/pcl/io/openni_camera/openni_device.h @@ -178,7 +178,7 @@ namespace openni_wrapper void setDepthRegistration (bool on_off); - /** \return whether the depth stream is registered to the RGB camera fram or not. */ + /** \return whether the depth stream is registered to the RGB camera frame or not. */ bool isDepthRegistered () const noexcept; diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index bb5a5cfe041..623110f0f8b 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -252,7 +252,7 @@ pcl::io::vtk2mesh (const vtkSmartPointer& poly_data, pcl::PolygonMe if (poly_data->GetPoints () == nullptr) { - PCL_ERROR ("[pcl::io::vtk2mesh] Given vtkPolyData is misformed (contains nullpointer instead of points).\n"); + PCL_ERROR ("[pcl::io::vtk2mesh] Given vtkPolyData is malformed (contains nullpointer instead of points).\n"); return (0); } vtkSmartPointer mesh_points = poly_data->GetPoints (); diff --git a/kdtree/include/pcl/kdtree/kdtree_flann.h b/kdtree/include/pcl/kdtree/kdtree_flann.h index 4396cb8b717..73a84d4dc3e 100644 --- a/kdtree/include/pcl/kdtree/kdtree_flann.h +++ b/kdtree/include/pcl/kdtree/kdtree_flann.h @@ -70,7 +70,7 @@ using NotCompatWithFlann = std::enable_if_t::value, b } // namespace detail /** - * @brief Comaptibility template function to allow use of various types of indices with + * @brief Compatibility template function to allow use of various types of indices with * FLANN * @details Template is used for all params to not constrain any FLANN side capability * @param[in,out] index A index searcher, of type ::flann::Index or similar, where @@ -96,7 +96,7 @@ radius_search(const FlannIndex& index, const SearchParams& params); /** - * @brief Comaptibility template function to allow use of various types of indices with + * @brief Compatibility template function to allow use of various types of indices with * FLANN * @details Template is used for all params to not constrain any FLANN side capability * @param[in,out] index A index searcher, of type ::flann::Index or similar, where diff --git a/octree/octree.doxy b/octree/octree.doxy index a68de5461c7..9083ed4319a 100644 --- a/octree/octree.doxy +++ b/octree/octree.doxy @@ -14,7 +14,7 @@ The pcl_octree implementation provides efficient nearest neighbor search such as "Neighbors within Voxel Search”, “K Nearest Neighbor Search” and “Neighbors within Radius Search”. It automatically adjusts its dimension to the point data set. A set of leaf node classes provide additional functionality, such as -spacial "occupancy" and "point density per voxel" checks. Functions for serialization +spatial "occupancy" and "point density per voxel" checks. Functions for serialization and deserialization enable to efficiently encode the octree structure into a binary format. Furthermore, a memory pool implementation reduces expensive memory allocation and deallocation operations in scenarios where octrees needs to be created at high rate. diff --git a/outofcore/include/pcl/outofcore/octree_base.h b/outofcore/include/pcl/outofcore/octree_base.h index e3c5368068f..45959b95236 100644 --- a/outofcore/include/pcl/outofcore/octree_base.h +++ b/outofcore/include/pcl/outofcore/octree_base.h @@ -93,7 +93,7 @@ namespace pcl * recursively in this state. This class provides an the interface * for: * -# Point/Region insertion methods - * -# Frustrum/box/region queries + * -# Frustum/box/region queries * -# Parameterization of resolution, container type, etc... * * For lower-level node access, there is a Depth-First iterator @@ -294,7 +294,7 @@ namespace pcl std::uint64_t addDataToLeaf_and_genLOD (AlignedPointTVector &p); - // Frustrum/Box/Region REQUESTS/QUERIES: DB Accessors + // Frustum/Box/Region REQUESTS/QUERIES: DB Accessors // ----------------------------------------------------------------------- void queryFrustum (const double *planes, std::list& file_names) const; @@ -347,7 +347,7 @@ namespace pcl /** \brief Returns a random subsample of points within the given bounding box at \c query_depth. * - * \param[in] min The minimum corner of the boudning box to query. + * \param[in] min The minimum corner of the bounding box to query. * \param[out] max The maximum corner of the bounding box to query. * \param[in] query_depth The depth in the tree at which to look for the points. Only returns points within the given bounding box at the specified \c query_depth. * \param percent diff --git a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp index 4783f7018d5..e4d6ceee372 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp @@ -635,7 +635,7 @@ bool pcl::GlobalHypothesesVerification::addModel(typename pcl::P Eigen::Vector3f scene_p_normal = (*scene_normals_)[it->first].getNormalVector3fMap (); Eigen::Vector3f model_p_normal = (*recog_model->normals_)[it->second->at(closest).first].getNormalVector3fMap(); - float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel trough perpendicular to parallel + float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel through perpendicular to parallel if (dotp < 0.f) dotp = 0.f; @@ -725,7 +725,7 @@ void pcl::GlobalHypothesesVerification::computeClutterCue(Recogn //using normals to weight clutter points Eigen::Vector3f scene_p_normal = (*scene_normals_)[neighborhood_index.first].getNormalVector3fMap (); Eigen::Vector3f model_p_normal = (*scene_normals_)[recog_model->explained_[neighborhood_index.second]].getNormalVector3fMap (); - float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel trough perpendicular to parallel + float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel through perpendicular to parallel if (dotp < 0) dotp = 0.f; diff --git a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp index 3830bdbe9b1..fdd87b780e9 100644 --- a/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp +++ b/recognition/include/pcl/recognition/impl/implicit_shape_model.hpp @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. * * - * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" + * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classification" * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool * * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov diff --git a/recognition/include/pcl/recognition/implicit_shape_model.h b/recognition/include/pcl/recognition/implicit_shape_model.h index 0347eff922a..ea02007e1f5 100644 --- a/recognition/include/pcl/recognition/implicit_shape_model.h +++ b/recognition/include/pcl/recognition/implicit_shape_model.h @@ -226,12 +226,12 @@ namespace pcl namespace ism { /** \brief This class implements Implicit Shape Model algorithm described in - * "Hough Transforms and 3D SURF for robust three dimensional classication" + * "Hough Transforms and 3D SURF for robust three dimensional classification" * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool. * It has two main member functions. One for training, using the data for which we know * which class it belongs to. And second for investigating a cloud for the presence * of the class of interest. - * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" + * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classification" * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool * * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov diff --git a/registration/include/pcl/registration/ia_fpcs.h b/registration/include/pcl/registration/ia_fpcs.h index abff434f527..cb371b3e12b 100644 --- a/registration/include/pcl/registration/ia_fpcs.h +++ b/registration/include/pcl/registration/ia_fpcs.h @@ -427,7 +427,7 @@ class FPCSInitialAlignment : public Registration::handleMatches( std::numeric_limits::max(); // reset to std::numeric_limits::max() // to accept all candidates and not only best - // determine corresondences between base and match according to their distance to + // determine correspondences between base and match according to their distance to // centroid linkMatchWithBase(base_indices, match, correspondences_temp); diff --git a/registration/include/pcl/registration/impl/sample_consensus_prerejective.hpp b/registration/include/pcl/registration/impl/sample_consensus_prerejective.hpp index 6f853a06be7..5a84f870489 100644 --- a/registration/include/pcl/registration/impl/sample_consensus_prerejective.hpp +++ b/registration/include/pcl/registration/impl/sample_consensus_prerejective.hpp @@ -94,7 +94,7 @@ SampleConsensusPrerejective::selectSamples( // Select a random number sample_indices[i] = getRandomIndex(static_cast(cloud.size()) - i); - // Run trough list of numbers, starting at the lowest, to avoid duplicates + // Run through list of numbers, starting at the lowest, to avoid duplicates for (int j = 0; j < i; j++) { // Move value up if it is higher than previous selections to ensure true // randomness diff --git a/search/include/pcl/search/organized.h b/search/include/pcl/search/organized.h index fe07756ef44..ea6fea672c8 100644 --- a/search/include/pcl/search/organized.h +++ b/search/include/pcl/search/organized.h @@ -80,7 +80,7 @@ namespace pcl /** \brief Constructor * \param[in] sorted_results whether the results should be return sorted in ascending order on the distances or not. - * This applies only for radius search, since knn always returns sorted resutls + * This applies only for radius search, since knn always returns sorted results * \param[in] eps the threshold for the mean-squared-error of the estimation of the projection matrix. * if the MSE is above this value, the point cloud is considered as not from a projective device, * thus organized neighbor search can not be applied on that cloud. diff --git a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h index 79a872a25f3..d87e4a041d4 100644 --- a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h @@ -206,7 +206,7 @@ namespace pcl * \param[out] model_coefficients a vector of model_coefficients for each plane found in the input cloud * \param[out] inlier_indices a vector of inliers for each detected plane * \param[out] centroids a vector of centroids for each plane - * \param[out] covariances a vector of covariance matricies for the inliers of each plane + * \param[out] covariances a vector of covariance matrices for the inliers of each plane * \param[out] labels a point cloud for the connected component labels of each pixel * \param[out] label_indices a vector of PointIndices for each labeled component */ diff --git a/simulation/tools/sim_viewer.cpp b/simulation/tools/sim_viewer.cpp index 02bf5745b13..7978fc7a39a 100644 --- a/simulation/tools/sim_viewer.cpp +++ b/simulation/tools/sim_viewer.cpp @@ -268,13 +268,13 @@ capture(Eigen::Isometry3d pose_in) // 27840 triangle faces // 13670 vertices - // 45.00Hz: simuation only - // 1.28Hz: simuation, addNoise? , getPointCloud, writeASCII - // 33.33Hz: simuation, getPointCloud - // 23.81Hz: simuation, getPointCloud, writeBinary - // 14.28Hz: simuation, addNoise, getPointCloud, writeBinary + // 45.00Hz: simulation only + // 1.28Hz: simulation, addNoise? , getPointCloud, writeASCII + // 33.33Hz: simulation, getPointCloud + // 23.81Hz: simulation, getPointCloud, writeBinary + // 14.28Hz: simulation, addNoise, getPointCloud, writeBinary // MODULE TIME FRACTION - // simuation 0.02222 31% + // simulation 0.02222 31% // addNoise 0.03 41% // getPointCloud 0.008 11% // writeBinary 0.012 16% diff --git a/surface/include/pcl/surface/grid_projection.h b/surface/include/pcl/surface/grid_projection.h index 77142c50006..f49f8b82cca 100644 --- a/surface/include/pcl/surface/grid_projection.h +++ b/surface/include/pcl/surface/grid_projection.h @@ -234,7 +234,7 @@ namespace pcl /** \brief When the input data points don't fill into the 1*1*1 box, * scale them so that they can be filled in the unit box. Otherwise, - * it will be some drawing problem when doing visulization + * it will be some drawing problem when doing visualization * \param scale_factor scale all the input data point by scale_factor */ void diff --git a/test/features/test_curvatures_estimation.cpp b/test/features/test_curvatures_estimation.cpp index 11e858f3ff8..07d3e249e98 100644 --- a/test/features/test_curvatures_estimation.cpp +++ b/test/features/test_curvatures_estimation.cpp @@ -116,7 +116,7 @@ TEST (PCL, PrincipalCurvaturesEstimation) pc.compute (*pcs); EXPECT_EQ (pcs->size (), indices.size ()); - // Adjust for small numerical inconsitencies (due to nn_indices not being sorted) + // Adjust for small numerical inconsistencies (due to nn_indices not being sorted) EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[0]), 0.98509, 1e-4); EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[1]), 0.10713, 1e-4); EXPECT_NEAR (std::abs ((*pcs)[0].principal_curvature[2]), 0.13462, 1e-4); diff --git a/test/octree/test_octree.cpp b/test/octree/test_octree.cpp index 7fbd7bb0925..4ca4def3815 100644 --- a/test/octree/test_octree.cpp +++ b/test/octree/test_octree.cpp @@ -265,7 +265,7 @@ TEST (PCL, Octree_Dynamic_Depth_Test) for (int point = 0; point < 15; point++) { - // gereate a random point + // generate a random point PointXYZ newPoint (1.0, 2.0, 3.0); // OctreePointCloudPointVector can store all points.. @@ -290,7 +290,7 @@ TEST (PCL, Octree_Dynamic_Depth_Test) for (int point = 0; point < pointcount; point++) { - // gereate a random point + // generate a random point PointXYZ newPoint (static_cast (1024.0 * rand () / RAND_MAX), static_cast (1024.0 * rand () / RAND_MAX), static_cast (1024.0 * rand () / RAND_MAX)); @@ -713,7 +713,7 @@ TEST (PCL, Octree_Pointcloud_Test) for (int point = 0; point < pointcount; point++) { - // gereate a random point + // generate a random point PointXYZ newPoint (static_cast (1024.0 * rand () / RAND_MAX), static_cast (1024.0 * rand () / RAND_MAX), static_cast (1024.0 * rand () / RAND_MAX)); diff --git a/test/registration/test_correspondence_estimation.cpp b/test/registration/test_correspondence_estimation.cpp index b251dd974c4..40494659b8f 100644 --- a/test/registration/test_correspondence_estimation.cpp +++ b/test/registration/test_correspondence_estimation.cpp @@ -101,7 +101,7 @@ TYPED_TEST(CorrespondenceEstimationTestSuite, CorrespondenceEstimationNormalShoo auto cloud1 (pcl::make_shared> ()); auto cloud2 (pcl::make_shared> ()); - // Defining two parallel planes differing only by the y co-ordinate + // Defining two parallel planes differing only by the y coordinate for (std::size_t i = 0; i < 50; ++i) { for (std::size_t j = 0; j < 25; ++j) diff --git a/test/registration/test_fpcs_ia.cpp b/test/registration/test_fpcs_ia.cpp index 75a780a17a1..774f06d4829 100644 --- a/test/registration/test_fpcs_ia.cpp +++ b/test/registration/test_fpcs_ia.cpp @@ -79,7 +79,7 @@ TEST (PCL, FPCSInitialAlignment) fpcs_ia.align (source_aligned); EXPECT_EQ (source_aligned.size (), cloud_source.size ()); - // check for correct coarse transformation marix + // check for correct coarse transformation matrix //Eigen::Matrix4f transform_res_from_fpcs = fpcs_ia.getFinalTransformation (); //for (int i = 0; i < 4; ++i) // for (int j = 0; j < 4; ++j) diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index 0b2d33712aa..bb9b132cb72 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -900,7 +900,7 @@ main (int argc, char** argv) testing::InitGoogleTest (&argc, argv); return (RUN_ALL_TESTS ()); - // Tranpose the cloud_model + // Transpose the cloud_model /*for (std::size_t i = 0; i < cloud_model.size (); ++i) { // cloud_model[i].z += 1; diff --git a/test/registration/test_registration_api.cpp b/test/registration/test_registration_api.cpp index 1aeebb78918..29c5c7e6d8b 100644 --- a/test/registration/test_registration_api.cpp +++ b/test/registration/test_registration_api.cpp @@ -733,7 +733,7 @@ main (int argc, char** argv) testing::InitGoogleTest (&argc, argv); return (RUN_ALL_TESTS ()); - // Tranpose the cloud_model + // Transpose the cloud_model /*for (std::size_t i = 0; i < cloud_model.size (); ++i) { // cloud_model[i].z += 1; diff --git a/test/segmentation/test_segmentation.cpp b/test/segmentation/test_segmentation.cpp index f565dd27af7..d02a5103808 100644 --- a/test/segmentation/test_segmentation.cpp +++ b/test/segmentation/test_segmentation.cpp @@ -417,7 +417,7 @@ main (int argc, char** argv) return (-1); } - // Tranpose the cloud + // Transpose the cloud cloud_t_.reset(new PointCloud); *cloud_t_ = *cloud_; for (auto& point: *cloud_t_) diff --git a/tools/cluster_extraction.cpp b/tools/cluster_extraction.cpp index f4d61d8b2cf..600af41e2f1 100644 --- a/tools/cluster_extraction.cpp +++ b/tools/cluster_extraction.cpp @@ -67,7 +67,7 @@ printHelp (int, char **argv) print_value ("%d", default_min); print_info (")\n"); print_info (" -max X = use a maximum of X points peer cluster (default: "); print_value ("%d", default_max); print_info (")\n"); - print_info (" -tolerance X = the spacial distance between clusters (default: "); + print_info (" -tolerance X = the spatial distance between clusters (default: "); print_value ("%lf", default_tolerance); print_info (")\n"); } diff --git a/tools/image_viewer.cpp b/tools/image_viewer.cpp index 9a51397d181..02c047b101b 100644 --- a/tools/image_viewer.cpp +++ b/tools/image_viewer.cpp @@ -58,7 +58,7 @@ main (int, char ** argv) depth_image_viewer_.showFloatImage (img, xyz.width, xyz.height, std::numeric_limits::min (), - // Scale so that the colors look brigher on screen + // Scale so that the colors look brighter on screen std::numeric_limits::max () / 10, true); depth_image_viewer_.spin (); diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 5560ef682e2..2cdb269c235 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -524,7 +524,7 @@ class Viewer reinterpret_cast (&frame->depth_image->getDepthMetaData ().Data ()[0]), frame->depth_image->getWidth (), frame->depth_image->getHeight (), std::numeric_limits::min (), - // Scale so that the colors look brigher on screen + // Scale so that the colors look brighter on screen std::numeric_limits::max () / 10, true); diff --git a/tracking/include/pcl/tracking/particle_filter.h b/tracking/include/pcl/tracking/particle_filter.h index 122d4b5417c..216c27841d9 100644 --- a/tracking/include/pcl/tracking/particle_filter.h +++ b/tracking/include/pcl/tracking/particle_filter.h @@ -472,7 +472,7 @@ class ParticleFilterTracker : public Tracker { /** \brief Resampling phase of particle filter method. Sampling the particles * according to the weights calculated in weight method. In particular, - * "sample with replacement" is archieved by walker's alias method. + * "sample with replacement" is achieved by walker's alias method. */ virtual void resample(); diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index fa410114273..b6416dbe059 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -49,7 +49,7 @@ namespace tracking { /** Pyramidal Kanade Lucas Tomasi tracker. * This is an implementation of the Pyramidal Kanade Lucas Tomasi tracker that * operates on organized 3D keypoints with color/intensity information (this is - * the default behaviour but you can alterate it by providing another operator + * the default behaviour but you can alternate it by providing another operator * as second template argument). It is an affine tracker that iteratively * computes the optical flow to find the best guess for a point p at t given its * location at t-1. User is advised to respect the Tomasi condition: the diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 8e5d42fa565..69478657759 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -111,7 +111,7 @@ namespace pcl PCLVisualizer (const std::string &name = "", const bool create_interactor = true); /** \brief PCL Visualizer constructor. It looks through the passed argv arguments to find the "-cam *.cam" argument. - * If the search failed, the name for cam file is calculated with boost uuid. If there is no such file, camera is not initilalized. + * If the search failed, the name for cam file is calculated with boost uuid. If there is no such file, camera is not initialized. * \param[in] argc * \param[in] argv * \param[in] name the window name (empty by default) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 85c4061fb45..c8a189ccd67 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -3906,7 +3906,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( trans_view (x, y) = static_cast (view_transform->GetElement (x, y)); //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right) - //thus, the fliping in y and z + //thus, the flipping in y and z for (auto &point : cloud->points) { point.getVector4fMap () = trans_view * point.getVector4fMap (); @@ -3928,7 +3928,7 @@ pcl::visualization::PCLVisualizer::renderViewTesselatedSphere ( transOCtoCC->Concatenate (cam_tmp->GetViewTransformMatrix ()); //NOTE: vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right) - //thus, the fliping in y and z + //thus, the flipping in y and z vtkSmartPointer cameraSTD = vtkSmartPointer::New (); cameraSTD->Identity (); cameraSTD->SetElement (0, 0, 1); @@ -4010,7 +4010,7 @@ pcl::visualization::PCLVisualizer::renderView (int xres, int yres, pcl::PointClo float w3 = 1.0f / world_coords[3]; world_coords[0] *= w3; - // vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right), thus, the fliping in y and z + // vtk view coordinate system is different than the standard camera coordinates (z forward, y down, x right), thus, the flipping in y and z world_coords[1] *= -w3; world_coords[2] *= -w3; From 9280e6f7e6dee105d988e761a576fa49737eca96 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Mon, 1 Jan 2024 14:37:45 +0100 Subject: [PATCH 175/288] Enhance toPCLPointCloud2 to remove padding on request The default is to keep the padding (same as before). The amount of padding depends on the point type (e.g. 25% for PointXYZ, 50% for PointXYZI). Speed: I tested with recent GCC and clang compilers and different point types, and removing the padding (padding=false) was almost always faster, except for PointXYZ on GCC, where keeping the padding was slightly faster. --- common/include/pcl/conversions.h | 96 +++++++++++++++++++++++++++----- test/common/test_io.cpp | 46 +++++++++++++++ 2 files changed, 129 insertions(+), 13 deletions(-) diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 631b7443c68..20072819dfa 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -53,6 +53,7 @@ #include #include +#include // for accumulate namespace pcl { @@ -256,12 +257,52 @@ namespace pcl fromPCLPointCloud2 (msg, cloud, field_map); } + namespace detail { + /** \brief Used together with `pcl::for_each_type`, copies all point fields from `cloud_data` (respecting each field offset) to `msg_data` (tightly packed). + */ + template + struct FieldCopier { + FieldCopier(std::uint8_t*& msg_data, const std::uint8_t*& cloud_data) : msg_data_ (msg_data), cloud_data_ (cloud_data) {}; + + template void operator() () { + memcpy(msg_data_, cloud_data_ + pcl::traits::offset::value, sizeof(typename pcl::traits::datatype::type)); + msg_data_ += sizeof(typename pcl::traits::datatype::type); + } + + std::uint8_t*& msg_data_; + const std::uint8_t*& cloud_data_; + }; + + /** \brief Used together with `pcl::for_each_type`, creates list of all fields, and list of size of each field. + */ + template + struct FieldAdderAdvanced + { + FieldAdderAdvanced (std::vector& fields, std::vector& field_sizes) : fields_ (fields), field_sizes_ (field_sizes) {}; + + template void operator() () + { + pcl::PCLPointField f; + f.name = pcl::traits::name::value; + f.offset = pcl::traits::offset::value; + f.datatype = pcl::traits::datatype::value; + f.count = pcl::traits::datatype::size; + fields_.push_back (f); + field_sizes_.push_back (sizeof(typename pcl::traits::datatype::type)); // If field is an array, then this is the size of all array elements + } + + std::vector& fields_; + std::vector& field_sizes_; + }; + } // namespace detail + /** \brief Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob. * \param[in] cloud the input pcl::PointCloud * \param[out] msg the resultant PCLPointCloud2 binary blob + * \param[in] padding Many point types have padding to ensure alignment and SIMD compatibility. Setting this to true will copy the padding to the `PCLPointCloud2` (the default in older PCL versions). Setting this to false will make the data blob in `PCLPointCloud2` smaller, while still keeping all information (useful e.g. when sending msg over network or storing it). The amount of padding depends on the point type, and can in some cases be up to 50 percent. */ template void - toPCLPointCloud2 (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg) + toPCLPointCloud2 (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg, bool padding) { // Ease the user's burden on specifying width/height for unorganized datasets if (cloud.width == 0 && cloud.height == 0) @@ -275,26 +316,55 @@ namespace pcl msg.height = cloud.height; msg.width = cloud.width; } - - // Fill point cloud binary data (padding and all) - std::size_t data_size = sizeof (PointT) * cloud.size (); - msg.data.resize (data_size); - if (data_size) - { - memcpy(msg.data.data(), cloud.data(), data_size); - } - // Fill fields metadata msg.fields.clear (); - for_each_type::type> (detail::FieldAdder(msg.fields)); + std::vector field_sizes; + for_each_type::type>(pcl::detail::FieldAdderAdvanced(msg.fields, field_sizes)); + // Check if padding should be kept, or if the point type does not contain padding (then the single memcpy is faster) + if (padding || std::accumulate(field_sizes.begin(), field_sizes.end(), static_cast(0)) == sizeof (PointT)) { + // Fill point cloud binary data (padding and all) + std::size_t data_size = sizeof (PointT) * cloud.size (); + msg.data.resize (data_size); + if (data_size) + { + memcpy(msg.data.data(), cloud.data(), data_size); + } + + msg.point_step = sizeof (PointT); + msg.row_step = (sizeof (PointT) * msg.width); + } else { + std::size_t point_size = 0; + for(std::size_t i=0; i(&cloud[0]); + const std::uint8_t* end = cloud_data + sizeof (PointT) * cloud.size (); + pcl::detail::FieldCopier copier(msg_data, cloud_data); // copier takes msg_data and cloud_data as references, so the two are shared + for (; cloud_data::type > (copier); + } + msg.point_step = point_size; + msg.row_step = point_size * msg.width; + } msg.header = cloud.header; - msg.point_step = sizeof (PointT); - msg.row_step = (sizeof (PointT) * msg.width); msg.is_dense = cloud.is_dense; /// @todo msg.is_bigendian = ?; } + /** \brief Convert a pcl::PointCloud object to a PCLPointCloud2 binary data blob. + * \param[in] cloud the input pcl::PointCloud + * \param[out] msg the resultant PCLPointCloud2 binary blob + */ + template void + toPCLPointCloud2 (const pcl::PointCloud& cloud, pcl::PCLPointCloud2& msg) + { + toPCLPointCloud2 (cloud, msg, true); // true is the default in older PCL version + } + /** \brief Copy the RGB fields of a PointCloud into pcl::PCLImage format * \param[in] cloud the point cloud message * \param[out] msg the resultant pcl::PCLImage diff --git a/test/common/test_io.cpp b/test/common/test_io.cpp index e5d742ad749..43c2ac1709a 100644 --- a/test/common/test_io.cpp +++ b/test/common/test_io.cpp @@ -250,6 +250,52 @@ TEST (PCL, CopyPointCloudWithSameTypes) ASSERT_EQ (0, cloud_out.size ()); } +TEST (toPCLPointCloud2NoPadding, PointXYZI) +{ + pcl::PointCloud cloud; + cloud.resize(static_cast(2), static_cast(2)); + cloud[0].x = 1.0; cloud[0].y = 2.0; cloud[0].z = 3.0; cloud[0].intensity = 123.0; + cloud[1].x = -1.0; cloud[1].y = -2.0; cloud[1].z = -3.0; cloud[1].intensity = -123.0; + cloud[2].x = 0.1; cloud[2].y = 0.2; cloud[2].z = 0.3; cloud[2].intensity = 12.3; + cloud[3].x = 0.0; cloud[3].y = -1.7; cloud[3].z = 100.0; cloud[3].intensity = 3.14; + pcl::PCLPointCloud2 msg; + pcl::toPCLPointCloud2(cloud, msg, false); + EXPECT_EQ (msg.height, cloud.height); + EXPECT_EQ (msg.width, cloud.width); + EXPECT_EQ (msg.fields.size(), 4); + EXPECT_EQ (msg.fields[0].name, "x"); + EXPECT_EQ (msg.fields[0].offset, 0); + EXPECT_EQ (msg.fields[0].datatype, pcl::PCLPointField::FLOAT32); + EXPECT_EQ (msg.fields[0].count, 1); + EXPECT_EQ (msg.fields[1].name, "y"); + EXPECT_EQ (msg.fields[1].offset, 4); + EXPECT_EQ (msg.fields[1].datatype, pcl::PCLPointField::FLOAT32); + EXPECT_EQ (msg.fields[1].count, 1); + EXPECT_EQ (msg.fields[2].name, "z"); + EXPECT_EQ (msg.fields[2].offset, 8); + EXPECT_EQ (msg.fields[2].datatype, pcl::PCLPointField::FLOAT32); + EXPECT_EQ (msg.fields[2].count, 1); + EXPECT_EQ (msg.fields[3].name, "intensity"); + EXPECT_EQ (msg.fields[3].offset, 12); + EXPECT_EQ (msg.fields[3].datatype, pcl::PCLPointField::FLOAT32); + EXPECT_EQ (msg.fields[3].count, 1); + EXPECT_EQ (msg.point_step, 16); + EXPECT_EQ (msg.row_step, 16*cloud.width); + EXPECT_EQ (msg.data.size(), 16*cloud.width*cloud.height); + EXPECT_EQ (msg.at(0, 0), 1.0f); + EXPECT_EQ (msg.at(3, 4), -1.7f); + EXPECT_EQ (msg.at(1, 8), -3.0f); + EXPECT_EQ (msg.at(2, 12), 12.3f); + pcl::PointCloud cloud2; + pcl::fromPCLPointCloud2(msg, cloud2); + for(std::size_t i=0; i Date: Wed, 3 Jan 2024 17:24:07 +0100 Subject: [PATCH 176/288] Bump version to 1.14.0 --- CMakeLists.txt | 2 +- README.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 92ffe0a4270..1709af51df3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.13.1.99) +project(PCL VERSION 1.14.0) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) diff --git a/README.md b/README.md index 75482dc411a..08318ebf317 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ [![Release][release-image]][releases] [![License][license-image]][license] -[release-image]: https://img.shields.io/badge/release-1.13.1-green.svg?style=flat +[release-image]: https://img.shields.io/badge/release-1.14.0-green.svg?style=flat [releases]: https://github.com/PointCloudLibrary/pcl/releases [license-image]: https://img.shields.io/badge/license-BSD-green.svg?style=flat From 728aedc38866dfec016bbcb47bfe2e6ce71dc894 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 3 Jan 2024 20:29:56 +0100 Subject: [PATCH 177/288] Bump version to 1.14.0.99 post release --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1709af51df3..8b015bff26f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.14.0) +project(PCL VERSION 1.14.0.99) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) From 671109849d76468c8421ebbbf605b614411a5ccf Mon Sep 17 00:00:00 2001 From: tomatih Date: Thu, 4 Jan 2024 12:55:39 +0000 Subject: [PATCH 178/288] Real Sense 2 grabber stream fix (#5912) * Add stream request safety * Small clarity reformat --- io/src/real_sense_2_grabber.cpp | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/io/src/real_sense_2_grabber.cpp b/io/src/real_sense_2_grabber.cpp index b034501bab4..798b6cd904a 100644 --- a/io/src/real_sense_2_grabber.cpp +++ b/io/src/real_sense_2_grabber.cpp @@ -86,6 +86,10 @@ namespace pcl signal_PointXYZRGBA->num_slots () == 0) return; + // cache stream options + const bool color_requested = signal_PointXYZRGB->num_slots () > 0 || signal_PointXYZRGBA->num_slots () > 0; + const bool ir_requested = signal_PointXYZI->num_slots () > 0; + running_ = true; quit_ = false; @@ -96,30 +100,30 @@ namespace pcl { cfg.enable_device_from_file ( file_name_or_serial_number_, repeat_playback_ ); } + // capture from camera else { + // find by serial number if provided if (!file_name_or_serial_number_.empty ()) cfg.enable_device ( file_name_or_serial_number_ ); - if (signal_PointXYZRGB->num_slots () > 0 || signal_PointXYZRGBA->num_slots () > 0) - { + // enable camera streams as requested + if (color_requested) cfg.enable_stream ( RS2_STREAM_COLOR, device_width_, device_height_, RS2_FORMAT_RGB8, target_fps_ ); - } cfg.enable_stream ( RS2_STREAM_DEPTH, device_width_, device_height_, RS2_FORMAT_Z16, target_fps_ ); - if (signal_PointXYZI->num_slots () > 0) - { + if (ir_requested) cfg.enable_stream ( RS2_STREAM_INFRARED, device_width_, device_height_, RS2_FORMAT_Y8, target_fps_ ); - } } rs2::pipeline_profile prof = pipe_.start ( cfg ); - if ( prof.get_stream ( RS2_STREAM_COLOR ).format ( ) != RS2_FORMAT_RGB8 || + // check all requested streams started properly + if ( (color_requested && prof.get_stream ( RS2_STREAM_COLOR ).format ( ) != RS2_FORMAT_RGB8) || prof.get_stream ( RS2_STREAM_DEPTH ).format ( ) != RS2_FORMAT_Z16 || - prof.get_stream ( RS2_STREAM_INFRARED ).format ( ) != RS2_FORMAT_Y8 ) + (ir_requested && prof.get_stream (RS2_STREAM_INFRARED ).format ( ) != RS2_FORMAT_Y8) ) THROW_IO_EXCEPTION ( "This stream type or format not supported." ); thread_ = std::thread ( &RealSense2Grabber::threadFunction, this ); From 6e51b16ee4a281d7c691a8442cbe6056e669cb89 Mon Sep 17 00:00:00 2001 From: Kino Date: Fri, 5 Jan 2024 21:51:28 +0800 Subject: [PATCH 179/288] replace boost filesystem exists (#5907) * replace boost filesystem exists * fix clang-tidy errors * revert some changes * fix some typos * address review changes * address more review changes * Review changes --- io/src/ifs_io.cpp | 12 +++++++++--- io/src/obj_io.cpp | 36 +++++++++++++++++++++++++++++------- io/src/pcd_io.cpp | 19 ++++++++++++++++--- 3 files changed, 54 insertions(+), 13 deletions(-) diff --git a/io/src/ifs_io.cpp b/io/src/ifs_io.cpp index d3bc8c7a1e4..8f9884fd292 100644 --- a/io/src/ifs_io.cpp +++ b/io/src/ifs_io.cpp @@ -42,7 +42,6 @@ #include #include -#include // for exists #include // for mapped_file_source /////////////////////////////////////////////////////////////////////////////////////////// @@ -60,15 +59,22 @@ pcl::IFSReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c //cloud.is_dense = true; std::uint32_t nr_points = 0; + + if (file_name.empty ()) + { + PCL_ERROR ("[pcl::IFSReader::readHeader] No file name given!\n"); + return (-1); + } + std::ifstream fs; + fs.open (file_name.c_str (), std::ios::binary); - if (file_name.empty() || !boost::filesystem::exists (file_name)) + if (!fs.good ()) { PCL_ERROR ("[pcl::IFSReader::readHeader] Could not find file '%s'.\n", file_name.c_str ()); return (-1); } - fs.open (file_name.c_str (), std::ios::binary); if (!fs.is_open () || fs.fail ()) { PCL_ERROR ("[pcl::IFSReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno)); diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 9cc1fdc68f7..4f20368d29c 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -146,14 +146,20 @@ int pcl::MTLReader::read (const std::string& obj_file_name, const std::string& mtl_file_name) { - if (obj_file_name.empty() || !boost::filesystem::exists (obj_file_name)) + if (obj_file_name.empty ()) + { + PCL_ERROR ("[pcl::MTLReader::read] No OBJ file name given!\n"); + return (-1); + } + + if (!boost::filesystem::exists (obj_file_name)) { PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'!\n", obj_file_name.c_str ()); return (-1); } - if (mtl_file_name.empty()) + if (mtl_file_name.empty ()) { PCL_ERROR ("[pcl::MTLReader::read] MTL file name is empty!\n"); return (-1); @@ -168,14 +174,23 @@ pcl::MTLReader::read (const std::string& obj_file_name, int pcl::MTLReader::read (const std::string& mtl_file_path) { - if (mtl_file_path.empty() || !boost::filesystem::exists (mtl_file_path)) + if (mtl_file_path.empty ()) { - PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'.\n", mtl_file_path.c_str ()); + PCL_ERROR ("[pcl::MTLReader::read] No file name given!\n"); return (-1); } + // Open file in binary mode to avoid problem of + // std::getline() corrupting the result of ifstream::tellg() std::ifstream mtl_file; mtl_file.open (mtl_file_path.c_str (), std::ios::binary); + + if (!mtl_file.good ()) + { + PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'.\n", mtl_file_path.c_str ()); + return (-1); + } + if (!mtl_file.is_open () || mtl_file.fail ()) { PCL_ERROR ("[pcl::MTLReader::read] Could not open file '%s'! Error : %s\n", @@ -340,18 +355,25 @@ pcl::OBJReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c data_type = 0; data_idx = offset; - std::ifstream fs; std::string line; - if (file_name.empty() || !boost::filesystem::exists (file_name)) + if (file_name.empty ()) { - PCL_ERROR ("[pcl::OBJReader::readHeader] Could not find file '%s'.\n", file_name.c_str ()); + PCL_ERROR ("[pcl::OBJReader::readHeader] No file name given!\n"); return (-1); } // Open file in binary mode to avoid problem of // std::getline() corrupting the result of ifstream::tellg() + std::ifstream fs; fs.open (file_name.c_str (), std::ios::binary); + + if (!fs.good ()) + { + PCL_ERROR ("[pcl::OBJReader::readHeader] Could not find file '%s'.\n", file_name.c_str ()); + return (-1); + } + if (!fs.is_open () || fs.fail ()) { PCL_ERROR ("[pcl::OBJReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror(errno)); diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 2a90664c841..0407cc9587c 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -385,9 +385,9 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, int &data_type, unsigned int &data_idx, const int offset) { - if (file_name.empty() || !boost::filesystem::exists (file_name)) + if (file_name.empty ()) { - PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ()); + PCL_ERROR ("[pcl::PCDReader::readHeader] No file name given!\n"); return (-1); } @@ -395,6 +395,13 @@ pcl::PCDReader::readHeader (const std::string &file_name, pcl::PCLPointCloud2 &c // std::getline() corrupting the result of ifstream::tellg() std::ifstream fs; fs.open (file_name.c_str (), std::ios::binary); + + if (!fs.good ()) + { + PCL_ERROR ("[pcl::PCDReader::readHeader] Could not find file '%s'.\n", file_name.c_str ()); + return (-1); + } + if (!fs.is_open () || fs.fail ()) { PCL_ERROR ("[pcl::PCDReader::readHeader] Could not open file '%s'! Error : %s\n", file_name.c_str (), strerror (errno)); @@ -664,7 +671,13 @@ pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, pcl::console::TicToc tt; tt.tic (); - if (file_name.empty() || !boost::filesystem::exists (file_name)) + if (file_name.empty ()) + { + PCL_ERROR ("[pcl::PCDReader::read] No file name given!\n"); + return (-1); + } + + if (!boost::filesystem::exists (file_name)) { PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ()); return (-1); From e9d71317624175466ccfb8521cda6a5b7ac31263 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 10 Jan 2024 21:05:29 +0100 Subject: [PATCH 180/288] Add missing PCL_EXPORTS --- .../include/pcl/gpu/segmentation/impl/gpu_extract_clusters.hpp | 3 ++- sample_consensus/include/pcl/sample_consensus/sac_model_cone.h | 3 ++- .../include/pcl/sample_consensus/sac_model_cylinder.h | 3 ++- .../include/pcl/sample_consensus/sac_model_sphere.h | 3 ++- .../pcl/visualization/vtk/vtkRenderWindowInteractorFix.h | 3 ++- 5 files changed, 10 insertions(+), 5 deletions(-) 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 2e2be0de375..1f4e28535c8 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 @@ -39,12 +39,13 @@ #pragma once #include #include +#include namespace pcl { namespace detail { //// Downloads only the neccssary cluster indices from the device to the host. -void +PCL_EXPORTS void economical_download(const pcl::gpu::NeighborIndices& source_indices, const pcl::Indices& buffer_indices, std::size_t buffer_size, diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h index 6137c26126c..9bf22810650 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cone.h @@ -41,11 +41,12 @@ #include #include #include +#include namespace pcl { namespace internal { - int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsCone (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief @b SampleConsensusModelCone defines a model for 3D cone segmentation. diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h index 95a6e80873b..12a42ea5a41 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_cylinder.h @@ -43,11 +43,12 @@ #include #include #include +#include namespace pcl { namespace internal { - int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsCylinder (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief @b SampleConsensusModelCylinder defines a model for 3D cylinder segmentation. diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h index 537fcb3d0dd..c3209e3f672 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_sphere.h @@ -49,11 +49,12 @@ #include #include +#include namespace pcl { namespace internal { - int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); + PCL_EXPORTS int optimizeModelCoefficientsSphere (Eigen::VectorXf& coeff, const Eigen::ArrayXf& pts_x, const Eigen::ArrayXf& pts_y, const Eigen::ArrayXf& pts_z); } // namespace internal /** \brief SampleConsensusModelSphere defines a model for 3D sphere segmentation. diff --git a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h index b427e76d9d3..7958f80e616 100644 --- a/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h +++ b/visualization/include/pcl/visualization/vtk/vtkRenderWindowInteractorFix.h @@ -38,5 +38,6 @@ #pragma once #include +#include -vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew (); +PCL_EXPORTS vtkRenderWindowInteractor* vtkRenderWindowInteractorFixNew (); From cc9c979cd6936e245ede548bec8c0ea9866ba3d0 Mon Sep 17 00:00:00 2001 From: Tsukasa Sugiura Date: Sat, 13 Jan 2024 00:49:15 +0900 Subject: [PATCH 181/288] [tutorials] suppress cmake warning for find python/sphinx using cmake 3.27 or later (#5924) * suppress cmake warning for find python/sphinx using cmake 3.27 or later * change module for find python using cmake 3.12 or later * fix variables for new find python package --- cmake/Modules/FindSphinx.cmake | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/cmake/Modules/FindSphinx.cmake b/cmake/Modules/FindSphinx.cmake index 61f5521c832..5bae14ea7bf 100644 --- a/cmake/Modules/FindSphinx.cmake +++ b/cmake/Modules/FindSphinx.cmake @@ -8,10 +8,16 @@ find_package(PkgConfig QUIET) pkg_check_modules(PC_SPHINX sphinx-build) -find_package(PythonInterp) - -if(PYTHONINTERP_FOUND) - get_filename_component(PYTHON_DIR "${PYTHON_EXECUTABLE}" PATH) +if(CMAKE_VERSION VERSION_LESS 3.12.0) + find_package(PythonInterp) + if(PYTHONINTERP_FOUND) + get_filename_component(PYTHON_DIR "${PYTHON_EXECUTABLE}" PATH) + endif() +else() + find_package(Python) + if(Python_Interpreter_FOUND) + get_filename_component(PYTHON_DIR "${Python_EXECUTABLE}" PATH) + endif() endif() find_program(SPHINX_EXECUTABLE NAMES sphinx-build From eb6bdd7bc66d492ede81346c570729b36e181d3a Mon Sep 17 00:00:00 2001 From: Kino Date: Thu, 18 Jan 2024 03:15:48 +0800 Subject: [PATCH 182/288] Switch latest Ubuntu to C++17 (#5931) * Switch latest Ubuntu to C++17 * Address review --- .ci/azure-pipelines/azure-pipelines.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index bc6d7501820..5b580a05ebb 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -54,6 +54,7 @@ stages: CC: gcc CXX: g++ BUILD_GPU: ON + CMAKE_ARGS: '-DCMAKE_CXX_STANDARD=17 -DCMAKE_CUDA_STANDARD=17' container: $[ variables['CONTAINER'] ] timeoutInMinutes: 0 variables: From c295be985117eeae28bd3e9576b095431409cb92 Mon Sep 17 00:00:00 2001 From: Kino Date: Thu, 18 Jan 2024 03:18:57 +0800 Subject: [PATCH 183/288] Enable C++17 filesystem in the future (#5921) * Enable C++17 filesystem * Fix format complaint * Fix ubuntu build error * Fix apps build error * Fix format complaint * Switch Ubuntu 23.04 to C++17 * Revert doc/tutorials and outofcore * Revert examples/outofcore * Revert test/outofcore * Revert recognition * Fix apps/face_detection build error * Address review * Address more review --- .../3d_rec_framework/pc_source/mesh_source.h | 8 ++-- .../pipeline/impl/global_nn_classifier.hpp | 8 ++-- .../impl/global_nn_recognizer_crh.hpp | 8 ++-- .../impl/global_nn_recognizer_cvfh.hpp | 12 ++--- .../pipeline/impl/local_recognizer.hpp | 8 ++-- .../utils/persistence_utils.h | 7 +++ .../tools/local_recognition_mian_dataset.cpp | 24 +++++----- .../src/offline_integration.cpp | 13 ++++-- .../face_detection_apps_utils.h | 16 +++++-- apps/include/pcl/apps/pcd_video_player.h | 8 +++- .../filesystem_face_detection.cpp | 10 ++-- apps/src/openni_grab_frame.cpp | 11 +++-- apps/src/openni_grab_images.cpp | 3 -- apps/src/organized_segmentation_demo.cpp | 3 -- .../src/pcd_video_player/pcd_video_player.cpp | 9 ++-- apps/src/stereo_ground_segmentation.cpp | 12 +++-- common/include/pcl/common/impl/file_io.hpp | 15 ++++-- cuda/apps/src/kinect_planes_cuda.cpp | 8 +++- gpu/kinfu/tools/kinfu_app.cpp | 17 ++++--- .../kinfu_large_scale/screenshot_manager.h | 8 +++- .../src/screenshot_manager.cpp | 4 +- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 17 ++++--- .../tools/standalone_texture_mapping.cpp | 13 ++++-- gpu/people/tools/people_app.cpp | 18 +++++--- io/include/pcl/io/impl/auto_io.hpp | 13 ++++-- io/src/ascii_io.cpp | 12 ++++- io/src/auto_io.cpp | 12 ++--- io/src/image_grabber.cpp | 46 +++++++++++-------- io/src/lzf_image_io.cpp | 10 +++- io/src/obj_io.cpp | 18 ++++++-- io/src/openni2_grabber.cpp | 9 +++- io/src/openni_grabber.cpp | 9 +++- io/src/pcd_io.cpp | 23 ++++++++-- io/src/ply_io.cpp | 13 ++++-- test/io/test_grabbers.cpp | 12 ++++- tools/converter.cpp | 23 ++++++---- tools/fast_bilateral_filter.cpp | 16 +++++-- tools/grid_min.cpp | 16 +++++-- tools/image_grabber_saver.cpp | 11 ++++- tools/image_grabber_viewer.cpp | 9 +++- tools/local_max.cpp | 16 +++++-- tools/morph.cpp | 16 +++++-- tools/normal_estimation.cpp | 16 +++++-- tools/passthrough_filter.cpp | 16 +++++-- tools/pcd_grabber_viewer.cpp | 16 +++++-- tools/progressive_morphological_filter.cpp | 16 +++++-- tools/radius_filter.cpp | 16 +++++-- tools/sac_segmentation_plane.cpp | 16 +++++-- tools/tiff2pcd.cpp | 21 ++++++--- tools/unary_classifier_segment.cpp | 15 ++++-- tools/uniform_sampling.cpp | 10 +++- tools/virtual_scanner.cpp | 15 ++++-- visualization/src/interactor_style.cpp | 9 +++- visualization/src/pcl_visualizer.cpp | 36 +++++++++------ 54 files changed, 523 insertions(+), 223 deletions(-) diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h index 6e1713618e2..4b39619f465 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h @@ -81,7 +81,7 @@ class MeshSource : public Source { loadOrGenerate(std::string& dir, std::string& model_path, ModelT& model) { const std::string pathmodel = dir + '/' + model.class_ + '/' + model.id_; - bf::path trained_dir = pathmodel; + pcl_fs::path trained_dir = pathmodel; model.views_.reset(new std::vector::Ptr>); model.poses_.reset( @@ -90,12 +90,12 @@ class MeshSource : public Source { model.assembled_.reset(new pcl::PointCloud); uniform_sampling(model_path, 100000, *model.assembled_, model_scale_); - if (bf::exists(trained_dir)) { + if (pcl_fs::exists(trained_dir)) { // load views, poses and self-occlusions std::vector view_filenames; - for (const auto& dir_entry : bf::directory_iterator(trained_dir)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(trained_dir)) { // check if its a directory, then get models in it - if (!(bf::is_directory(dir_entry))) { + if (!(pcl_fs::is_directory(dir_entry))) { // check that it is a ply file and then add, otherwise ignore.. std::vector strs; std::vector strs_; diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_classifier.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_classifier.hpp index 0592be86b93..79929997ab2 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_classifier.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_classifier.hpp @@ -17,7 +17,7 @@ pcl::rec_3d_framework::GlobalNNPipeline:: std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - for (const auto& dir_entry : bf::directory_iterator(path)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(path)) { std::string file_name = (dir_entry.path().filename()).string(); std::vector strs; @@ -177,9 +177,9 @@ pcl::rec_3d_framework::GlobalNNPipeline::initializ std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - bf::path desc_dir = path; - if (!bf::exists(desc_dir)) - bf::create_directory(desc_dir); + pcl_fs::path desc_dir = path; + if (!pcl_fs::exists(desc_dir)) + pcl_fs::create_directory(desc_dir); const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd"; pcl::io::savePCDFileBinary(path_view, *processed); diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp index bf6607eeae7..af7ab87d642 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_crh.hpp @@ -91,7 +91,7 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer:: std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - for (const auto& dir_entry : bf::directory_iterator(path)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(path)) { std::string file_name = (dir_entry.path().filename()).string(); std::vector strs; @@ -412,9 +412,9 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer::init std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - bf::path desc_dir = path; - if (!bf::exists(desc_dir)) - bf::create_directory(desc_dir); + pcl_fs::path desc_dir = path; + if (!pcl_fs::exists(desc_dir)) + pcl_fs::create_directory(desc_dir); const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd"; pcl::io::savePCDFileBinary(path_view, *processed); diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp index fdd83be86d7..6a583006cd7 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/global_nn_recognizer_cvfh.hpp @@ -51,8 +51,8 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer:: const std::string dir = path + "/roll_trans_" + std::to_string(view_id) + '_' + std::to_string(d_id) + ".txt"; - const bf::path file_path = dir; - if (bf::exists(file_path)) { + const pcl_fs::path file_path = dir; + if (pcl_fs::exists(file_path)) { PersistenceUtils::readMatrixFromFile(dir, pose_matrix); return true; } @@ -108,7 +108,7 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer:: std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - for (const auto& dir_entry : bf::directory_iterator(path)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(path)) { std::string file_name = (dir_entry.path().filename()).string(); std::vector strs; @@ -608,9 +608,9 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer::ini std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - bf::path desc_dir = path; - if (!bf::exists(desc_dir)) - bf::create_directory(desc_dir); + pcl_fs::path desc_dir = path; + if (!pcl_fs::exists(desc_dir)) + pcl_fs::create_directory(desc_dir); const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd"; pcl::io::savePCDFileBinary(path_view, *processed); diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp index 3561c3036cd..1bf8388f7fe 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pipeline/impl/local_recognizer.hpp @@ -20,7 +20,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline:: std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - for (const auto& dir_entry : bf::directory_iterator(path)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(path)) { std::string file_name = (dir_entry.path().filename()).string(); std::vector strs; @@ -150,9 +150,9 @@ pcl::rec_3d_framework::LocalRecognitionPipeline:: std::string path = source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_); - bf::path desc_dir = path; - if (!bf::exists(desc_dir)) - bf::create_directory(desc_dir); + pcl_fs::path desc_dir = path; + if (!pcl_fs::exists(desc_dir)) + pcl_fs::create_directory(desc_dir); const std::string path_view = path = "/view_" + std::to_string(v) + ".pcd"; pcl::io::savePCDFileBinary(path_view, *processed); diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h index a3c5812487e..9415c366fe8 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h @@ -1,7 +1,14 @@ #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include diff --git a/apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp b/apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp index 53891821d11..220952347f4 100644 --- a/apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp +++ b/apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp @@ -22,17 +22,17 @@ #include void -getScenesInDirectory(bf::path& dir, +getScenesInDirectory(pcl_fs::path& dir, std::string& rel_path_so_far, std::vector& relative_paths) { // list models in MODEL_FILES_DIR_ and return list - for (const auto& dir_entry : bf::directory_iterator(dir)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { // check if its a directory, then get models in it - if (bf::is_directory(dir_entry)) { + if (pcl_fs::is_directory(dir_entry)) { std::string so_far = rel_path_so_far + (dir_entry.path().filename()).string() + "/"; - bf::path curr_path = dir_entry.path(); + pcl_fs::path curr_path = dir_entry.path(); getScenesInDirectory(curr_path, so_far, relative_paths); } else { @@ -86,7 +86,7 @@ recognizeAndVisualize( { // read mians scenes - bf::path ply_files_dir = scenes_dir; + pcl_fs::path ply_files_dir = scenes_dir; std::vector files; std::string start; getScenesInDirectory(ply_files_dir, start, files); @@ -223,18 +223,18 @@ recognizeAndVisualize( } void -getModelsInDirectory(bf::path& dir, +getModelsInDirectory(pcl_fs::path& dir, std::string& rel_path_so_far, std::vector& relative_paths, std::string& ext) { - for (const auto& dir_entry : bf::directory_iterator(dir)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { // check if its a directory, then get models in it - if (bf::is_directory(dir_entry)) { + if (pcl_fs::is_directory(dir_entry)) { std::string so_far = rel_path_so_far + (dir_entry.path().filename()).string() + "/"; - bf::path curr_path = dir_entry.path(); + pcl_fs::path curr_path = dir_entry.path(); getModelsInDirectory(curr_path, so_far, relative_paths, ext); } else { @@ -315,8 +315,8 @@ main(int argc, char** argv) return -1; } - bf::path models_dir_path = path; - if (!bf::exists(models_dir_path)) { + pcl_fs::path models_dir_path = path; + if (!pcl_fs::exists(models_dir_path)) { PCL_ERROR("Models dir path %s does not exist, use -models_dir [dir] option\n", path.c_str()); return -1; @@ -324,7 +324,7 @@ main(int argc, char** argv) std::vector files; std::string start; std::string ext = std::string("ply"); - bf::path dir = models_dir_path; + pcl_fs::path dir = models_dir_path; getModelsInDirectory(dir, start, files, ext); assert(files.size() == 4); diff --git a/apps/in_hand_scanner/src/offline_integration.cpp b/apps/in_hand_scanner/src/offline_integration.cpp index 853232dc7f6..626320a4959 100644 --- a/apps/in_hand_scanner/src/offline_integration.cpp +++ b/apps/in_hand_scanner/src/offline_integration.cpp @@ -45,7 +45,14 @@ #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -186,14 +193,14 @@ pcl::ihs::OfflineIntegration::getFilesFromDirectory( const std::string& extension, std::vector& files) const { - if (path_dir.empty() || !boost::filesystem::exists(path_dir)) { + if (path_dir.empty() || !pcl_fs::exists(path_dir)) { std::cerr << "ERROR in offline_integration.cpp: Invalid path\n '" << path_dir << "'\n"; return (false); } - boost::filesystem::directory_iterator it_end; - for (boost::filesystem::directory_iterator it(path_dir); it != it_end; ++it) { + pcl_fs::directory_iterator it_end; + for (pcl_fs::directory_iterator it(path_dir); it != it_end; ++it) { if (!is_directory(it->status()) && boost::algorithm::to_upper_copy(it->path().extension().string()) == boost::algorithm::to_upper_copy(extension)) { diff --git a/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h b/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h index b986ea9a6c1..bce884062a0 100644 --- a/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h +++ b/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h @@ -7,6 +7,14 @@ #pragma once +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else +#include +namespace pcl_fs = boost::filesystem; +#endif + namespace face_detection_apps_utils { inline bool @@ -65,18 +73,18 @@ sortFiles(const std::string& file1, const std::string& file2) } inline void -getFilesInDirectory(bf::path& dir, +getFilesInDirectory(pcl_fs::path& dir, std::string& rel_path_so_far, std::vector& relative_paths, std::string& ext) { - for (const auto& dir_entry : bf::directory_iterator(dir)) { + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { // check if its a directory, then get models in it - if (bf::is_directory(dir_entry)) { + if (pcl_fs::is_directory(dir_entry)) { std::string so_far = rel_path_so_far + (dir_entry.path().filename()).string() + "/"; - bf::path curr_path = dir_entry.path(); + pcl_fs::path curr_path = dir_entry.path(); getFilesInDirectory(curr_path, so_far, relative_paths, ext); } else { diff --git a/apps/include/pcl/apps/pcd_video_player.h b/apps/include/pcl/apps/pcd_video_player.h index ba177d66f15..657b3626e63 100644 --- a/apps/include/pcl/apps/pcd_video_player.h +++ b/apps/include/pcl/apps/pcd_video_player.h @@ -42,7 +42,13 @@ #include #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -100,7 +106,7 @@ class PCDVideoPlayer : public QMainWindow { QString dir_; std::vector pcd_files_; - std::vector pcd_paths_; + std::vector pcd_paths_; /** \brief The current displayed frame */ unsigned int current_frame_; diff --git a/apps/src/face_detection/filesystem_face_detection.cpp b/apps/src/face_detection/filesystem_face_detection.cpp index fcb5028b66a..58dbb329329 100644 --- a/apps/src/face_detection/filesystem_face_detection.cpp +++ b/apps/src/face_detection/filesystem_face_detection.cpp @@ -13,9 +13,13 @@ #include // clang-format on +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include - -namespace bf = boost::filesystem; +namespace pcl_fs = boost::filesystem; +#endif bool SHOW_GT = false; bool VIDEO = false; @@ -222,7 +226,7 @@ main(int argc, char** argv) // recognize all files in directory... std::string start; std::string ext = std::string("pcd"); - bf::path dir = test_directory; + pcl_fs::path dir = test_directory; std::vector files; face_detection_apps_utils::getFilesInDirectory(dir, start, files, ext); diff --git a/apps/src/openni_grab_frame.cpp b/apps/src/openni_grab_frame.cpp index fbdc4d42ebf..cc7c454c763 100644 --- a/apps/src/openni_grab_frame.cpp +++ b/apps/src/openni_grab_frame.cpp @@ -45,7 +45,13 @@ #include #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include @@ -75,7 +81,6 @@ using namespace std::chrono_literals; #endif using namespace pcl::console; -using namespace boost::filesystem; template class OpenNIGrabFrame { @@ -222,7 +227,7 @@ class OpenNIGrabFrame { bool paused, bool visualizer) { - boost::filesystem::path path(filename); + pcl_fs::path path(filename); if (filename.empty()) { dir_name_ = "."; @@ -231,7 +236,7 @@ class OpenNIGrabFrame { else { dir_name_ = path.parent_path().string(); - if (!dir_name_.empty() && !boost::filesystem::exists(path.parent_path())) { + if (!dir_name_.empty() && !pcl_fs::exists(path.parent_path())) { std::cerr << "directory \"" << path.parent_path() << "\" does not exist!\n"; exit(1); } diff --git a/apps/src/openni_grab_images.cpp b/apps/src/openni_grab_images.cpp index edb5d549694..428b083da42 100644 --- a/apps/src/openni_grab_images.cpp +++ b/apps/src/openni_grab_images.cpp @@ -44,12 +44,9 @@ #include #include -#include - #include using namespace pcl::console; -using namespace boost::filesystem; class OpenNIGrabFrame { public: diff --git a/apps/src/organized_segmentation_demo.cpp b/apps/src/organized_segmentation_demo.cpp index 480817345a4..cbf81a72728 100644 --- a/apps/src/organized_segmentation_demo.cpp +++ b/apps/src/organized_segmentation_demo.cpp @@ -15,9 +15,6 @@ #include #include -// #include // for boost::filesystem::directory_iterator -#include // for boost::signals2::connection - void displayPlanarRegions( std::vector, diff --git a/apps/src/pcd_video_player/pcd_video_player.cpp b/apps/src/pcd_video_player/pcd_video_player.cpp index aa6157e3678..66c3d4fa104 100644 --- a/apps/src/pcd_video_player/pcd_video_player.cpp +++ b/apps/src/pcd_video_player/pcd_video_player.cpp @@ -167,11 +167,10 @@ PCDVideoPlayer::selectFolderButtonPressed() QFileDialog::ShowDirsOnly | QFileDialog::DontResolveSymlinks); - boost::filesystem::directory_iterator end_itr; + pcl_fs::directory_iterator end_itr; - if (boost::filesystem::is_directory(dir_.toStdString())) { - for (boost::filesystem::directory_iterator itr(dir_.toStdString()); itr != end_itr; - ++itr) { + if (pcl_fs::is_directory(dir_.toStdString())) { + for (pcl_fs::directory_iterator itr(dir_.toStdString()); itr != end_itr; ++itr) { std::string ext = itr->path().extension().string(); if (ext == ".pcd") { pcd_files_.push_back(itr->path().string()); @@ -211,7 +210,7 @@ void PCDVideoPlayer::selectFilesButtonPressed() { pcd_files_.clear(); // Clear the std::vector - pcd_paths_.clear(); // Clear the boost filesystem paths + pcd_paths_.clear(); // Clear the filesystem paths QStringList qt_pcd_files = QFileDialog::getOpenFileNames( this, "Select one or more PCD files to open", "/home", "PointClouds (*.pcd)"); diff --git a/apps/src/stereo_ground_segmentation.cpp b/apps/src/stereo_ground_segmentation.cpp index 0ef2ed02713..b2b8743b3d1 100755 --- a/apps/src/stereo_ground_segmentation.cpp +++ b/apps/src/stereo_ground_segmentation.cpp @@ -50,7 +50,13 @@ #include #include +#if (__cplusplus >= 201703L) +#include // for directory_iterator +namespace pcl_fs = std::filesystem; +#else #include // for directory_iterator +namespace pcl_fs = boost::filesystem; +#endif #include @@ -541,13 +547,13 @@ main(int argc, char** argv) // Get list of stereo files std::vector left_images; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr(argv[1]); itr != end_itr; ++itr) { + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr(argv[1]); itr != end_itr; ++itr) { left_images.push_back(itr->path().string()); } sort(left_images.begin(), left_images.end()); std::vector right_images; - for (boost::filesystem::directory_iterator itr(argv[2]); itr != end_itr; ++itr) { + for (pcl_fs::directory_iterator itr(argv[2]); itr != end_itr; ++itr) { right_images.push_back(itr->path().string()); } sort(right_images.begin(), right_images.end()); diff --git a/common/include/pcl/common/impl/file_io.hpp b/common/include/pcl/common/impl/file_io.hpp index 1c1fe9ec876..503c34d2437 100644 --- a/common/include/pcl/common/impl/file_io.hpp +++ b/common/include/pcl/common/impl/file_io.hpp @@ -39,7 +39,14 @@ #ifndef PCL_COMMON_FILE_IO_IMPL_HPP_ #define PCL_COMMON_FILE_IO_IMPL_HPP_ +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include #include @@ -53,12 +60,12 @@ namespace pcl void getAllPcdFilesInDirectory(const std::string& directory, std::vector& file_names) { - boost::filesystem::path p(directory); - if(boost::filesystem::is_directory(p)) + pcl_fs::path p(directory); + if(pcl_fs::is_directory(p)) { - for(const auto& entry : boost::make_iterator_range(boost::filesystem::directory_iterator(p), {})) + for(const auto& entry : boost::make_iterator_range(pcl_fs::directory_iterator(p), {})) { - if (boost::filesystem::is_regular_file(entry)) + if (pcl_fs::is_regular_file(entry)) { if (entry.path().extension() == ".pcd") file_names.emplace_back(entry.path().filename().string()); diff --git a/cuda/apps/src/kinect_planes_cuda.cpp b/cuda/apps/src/kinect_planes_cuda.cpp index c61c03364f2..9282bf68410 100644 --- a/cuda/apps/src/kinect_planes_cuda.cpp +++ b/cuda/apps/src/kinect_planes_cuda.cpp @@ -61,7 +61,13 @@ #include #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -273,7 +279,7 @@ class MultiRansac //bool repeat = false; //std::string path = "./pcl_logo.pcd"; - //if (path.empty() || !boost::filesystem::exists (path)) + //if (path.empty() || !pcl_fs::exists (path)) //{ // std::cerr << "did not find file" << std::endl; //} diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 3ed2e31e8f9..7feb67f4dbe 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -43,7 +43,13 @@ #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -173,19 +179,18 @@ namespace pcl /////////////////////////////////////////////////////////////////////////////////////////////////////////////////// std::vector getPcdFilesInDir(const std::string& directory) { - namespace fs = boost::filesystem; - fs::path dir(directory); + pcl_fs::path dir(directory); std::cout << "path: " << directory << std::endl; - if (directory.empty() || !fs::exists(dir) || !fs::is_directory(dir)) + if (directory.empty() || !pcl_fs::exists(dir) || !pcl_fs::is_directory(dir)) PCL_THROW_EXCEPTION (pcl::IOException, "No valid PCD directory given!\n"); std::vector result; - fs::directory_iterator pos(dir); - fs::directory_iterator end; + pcl_fs::directory_iterator pos(dir); + pcl_fs::directory_iterator end; for(; pos != end ; ++pos) - if (fs::is_regular_file(pos->status()) ) + if (pcl_fs::is_regular_file(pos->status()) ) if (pos->path().extension().string() == ".pcd") { result.push_back (pos->path ().string ()); diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h index 35b0a152925..520877494ae 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h @@ -48,8 +48,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include -//#include +namespace pcl_fs = boost::filesystem; +#endif #include diff --git a/gpu/kinfu_large_scale/src/screenshot_manager.cpp b/gpu/kinfu_large_scale/src/screenshot_manager.cpp index 15e6a9a8dfd..755fc947130 100644 --- a/gpu/kinfu_large_scale/src/screenshot_manager.cpp +++ b/gpu/kinfu_large_scale/src/screenshot_manager.cpp @@ -48,8 +48,8 @@ namespace pcl { ScreenshotManager::ScreenshotManager() { - boost::filesystem::path p ("KinFuSnapshots"); - boost::filesystem::create_directory (p); + pcl_fs::path p ("KinFuSnapshots"); + pcl_fs::create_directory (p); screenshot_counter = 0; setCameraIntrinsics(); } diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index bc455e17ca6..b5f92881919 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -55,7 +55,13 @@ Work in progress: patch by Marco (AUG,19th 2012) #include #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -123,19 +129,18 @@ namespace pcl std::vector getPcdFilesInDir(const std::string& directory) { - namespace fs = boost::filesystem; - fs::path dir(directory); + pcl_fs::path dir(directory); std::cout << "path: " << directory << std::endl; - if (directory.empty() || !fs::exists(dir) || !fs::is_directory(dir)) + if (directory.empty() || !pcl_fs::exists(dir) || !pcl_fs::is_directory(dir)) PCL_THROW_EXCEPTION (pcl::IOException, "No valid PCD directory given!\n"); std::vector result; - fs::directory_iterator pos(dir); - fs::directory_iterator end; + pcl_fs::directory_iterator pos(dir); + pcl_fs::directory_iterator end; for(; pos != end ; ++pos) - if (fs::is_regular_file(pos->status()) ) + if (pcl_fs::is_regular_file(pos->status()) ) if (pos->path().extension().string() == ".pcd") { result.push_back (pos->path ().string ()); diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index 6803bba3e3d..a7c58e413d7 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -36,8 +36,13 @@ * Author: Raphael Favier, Technical University Eindhoven, (r.mysurname tue.nl) */ - +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -432,11 +437,11 @@ main (int argc, char** argv) PCL_INFO ("\nLoading textures and camera poses...\n"); pcl::texture_mapping::CameraVector my_cams; - const boost::filesystem::path base_dir ("."); + const pcl_fs::path base_dir ("."); std::string extension (".txt"); - for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it) + for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it) { - if(boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) + if(pcl_fs::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) { pcl::TextureMapping::Camera cam; readCamPoseFile(it->path ().string (), cam); diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index 91308e4e263..816188ff13a 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -54,7 +54,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -66,18 +73,17 @@ using namespace std::chrono_literals; std::vector getPcdFilesInDir(const std::string& directory) { - namespace fs = boost::filesystem; - fs::path dir(directory); + pcl_fs::path dir(directory); - if (!fs::exists(dir) || !fs::is_directory(dir)) + if (!pcl_fs::exists(dir) || !pcl_fs::is_directory(dir)) PCL_THROW_EXCEPTION(pcl::IOException, "Wrong PCD directory"); std::vector result; - fs::directory_iterator pos(dir); - fs::directory_iterator end; + pcl_fs::directory_iterator pos(dir); + pcl_fs::directory_iterator end; for(; pos != end ; ++pos) - if (fs::is_regular_file(pos->status()) ) + if (pcl_fs::is_regular_file(pos->status()) ) if (pos->path().extension().string() == ".pcd") result.push_back(pos->path().string()); diff --git a/io/include/pcl/io/impl/auto_io.hpp b/io/include/pcl/io/impl/auto_io.hpp index c45f8860c5c..748dd0bc408 100644 --- a/io/include/pcl/io/impl/auto_io.hpp +++ b/io/include/pcl/io/impl/auto_io.hpp @@ -44,7 +44,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path +namespace pcl_fs = std::filesystem; +#else #include // for path +namespace pcl_fs = boost::filesystem; +#endif namespace pcl { @@ -53,7 +60,7 @@ namespace pcl template int load (const std::string& file_name, pcl::PointCloud& cloud) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".pcd") @@ -75,7 +82,7 @@ namespace pcl template int save (const std::string& file_name, const pcl::PointCloud& cloud) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".pcd") @@ -94,4 +101,4 @@ namespace pcl } } -#endif //PCL_IO_AUTO_IO_IMPL_H_ \ No newline at end of file +#endif //PCL_IO_AUTO_IO_IMPL_H_ diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index 486ef5aba18..1b52d89a168 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -40,7 +40,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include // for lexical_cast #include // for split #include @@ -88,9 +96,9 @@ pcl::ASCIIReader::readHeader (const std::string& file_name, { pcl::utils::ignore(offset); //offset is not used for ascii file implementation - boost::filesystem::path fpath = file_name; + pcl_fs::path fpath = file_name; - if (!boost::filesystem::exists (fpath)) + if (!pcl_fs::exists (fpath)) { PCL_ERROR ("[%s] File %s does not exist.\n", name_.c_str (), file_name.c_str ()); return (-1); diff --git a/io/src/auto_io.cpp b/io/src/auto_io.cpp index 86a206bef82..e5c09e05549 100644 --- a/io/src/auto_io.cpp +++ b/io/src/auto_io.cpp @@ -46,7 +46,7 @@ int pcl::io::load (const std::string& file_name, pcl::PCLPointCloud2& blob) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".pcd") @@ -68,7 +68,7 @@ pcl::io::load (const std::string& file_name, pcl::PCLPointCloud2& blob) int pcl::io::load (const std::string& file_name, pcl::PolygonMesh& mesh) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".ply") @@ -88,7 +88,7 @@ pcl::io::load (const std::string& file_name, pcl::PolygonMesh& mesh) int pcl::io::load (const std::string& file_name, pcl::TextureMesh& mesh) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".obj") @@ -104,7 +104,7 @@ pcl::io::load (const std::string& file_name, pcl::TextureMesh& mesh) int pcl::io::save (const std::string& file_name, const pcl::PCLPointCloud2& blob, unsigned precision) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".pcd") @@ -134,7 +134,7 @@ pcl::io::save (const std::string& file_name, const pcl::PCLPointCloud2& blob, un int pcl::io::save (const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".obj") @@ -150,7 +150,7 @@ pcl::io::save (const std::string &file_name, const pcl::TextureMesh &tex_mesh, u int pcl::io::save (const std::string &file_name, const pcl::PolygonMesh &poly_mesh, unsigned precision) { - boost::filesystem::path p (file_name.c_str ()); + pcl_fs::path p (file_name.c_str ()); std::string extension = p.extension ().string (); int result = -1; if (extension == ".ply") diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index de32f1f20de..e436dd6a8c6 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -42,7 +42,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for exists, basename, is_directory, ... +namespace pcl_fs = std::filesystem; +#else #include // for exists, basename, is_directory, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy #ifdef PCL_BUILT_WITH_VTK @@ -255,7 +263,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::trigger () void pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string &dir) { - if (!boost::filesystem::exists (dir) || !boost::filesystem::is_directory (dir)) + if (!pcl_fs::exists (dir) || !pcl_fs::is_directory (dir)) { PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which" " is not a directory: %s\n", dir.c_str ()); @@ -264,13 +272,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string std::string pathname; std::string extension; std::string basename; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (dir); itr != end_itr; ++itr) { extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); - if (!boost::filesystem::is_directory (itr->status ()) + if (!pcl_fs::is_directory (itr->status ()) && isValidExtension (extension)) { if (basename.find ("rgb") < std::string::npos) @@ -291,13 +299,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string void pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string &depth_dir, const std::string &rgb_dir) { - if (!boost::filesystem::exists (depth_dir) || !boost::filesystem::is_directory (depth_dir)) + if (!pcl_fs::exists (depth_dir) || !pcl_fs::is_directory (depth_dir)) { PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which" " is not a directory: %s\n", depth_dir.c_str ()); return; } - if (!boost::filesystem::exists (rgb_dir) || !boost::filesystem::is_directory (rgb_dir)) + if (!pcl_fs::exists (rgb_dir) || !pcl_fs::is_directory (rgb_dir)) { PCL_ERROR ("[pcl::ImageGrabber::loadDepthAndRGBFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which" " is not a directory: %s\n", rgb_dir.c_str ()); @@ -306,14 +314,14 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string std::string pathname; std::string extension; std::string basename; - boost::filesystem::directory_iterator end_itr; + pcl_fs::directory_iterator end_itr; // First iterate over depth images - for (boost::filesystem::directory_iterator itr (depth_dir); itr != end_itr; ++itr) + for (pcl_fs::directory_iterator itr (depth_dir); itr != end_itr; ++itr) { extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); - if (!boost::filesystem::is_directory (itr->status ()) + if (!pcl_fs::is_directory (itr->status ()) && isValidExtension (extension)) { if (basename.find ("depth") < std::string::npos) @@ -323,12 +331,12 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string } } // Then iterate over RGB images - for (boost::filesystem::directory_iterator itr (rgb_dir); itr != end_itr; ++itr) + for (pcl_fs::directory_iterator itr (rgb_dir); itr != end_itr; ++itr) { extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); - if (!boost::filesystem::is_directory (itr->status ()) + if (!pcl_fs::is_directory (itr->status ()) && isValidExtension (extension)) { if (basename.find ("rgb") < std::string::npos) @@ -354,7 +362,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadDepthAndRGBFiles (const std::string void pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir) { - if (!boost::filesystem::exists (dir) || !boost::filesystem::is_directory (dir)) + if (!pcl_fs::exists (dir) || !pcl_fs::is_directory (dir)) { PCL_ERROR ("[pcl::ImageGrabber::loadPCLZFFiles] Error: attempted to instantiate a pcl::ImageGrabber from a path which" " is not a directory: %s\n", dir.c_str ()); @@ -363,13 +371,13 @@ pcl::ImageGrabberBase::ImageGrabberImpl::loadPCLZFFiles (const std::string &dir) std::string pathname; std::string extension; std::string basename; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (dir); itr != end_itr; ++itr) { extension = boost::algorithm::to_upper_copy (itr->path ().extension ().string ()); pathname = itr->path ().string (); basename = itr->path ().stem ().string (); - if (!boost::filesystem::is_directory (itr->status ()) + if (!pcl_fs::is_directory (itr->status ()) && isValidExtension (extension)) { if (basename.find ("rgb") < std::string::npos) @@ -429,7 +437,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getTimestampFromFilepath ( { // For now, we assume the file is of the form frame_[22-char POSIX timestamp]_* char timestamp_str[256]; - int result = std::sscanf (boost::filesystem::path (filepath).stem ().string ().c_str (), + int result = std::sscanf (pcl_fs::path (filepath).stem ().string ().c_str (), "frame_%22s_%*s", timestamp_str); if (result > 0) @@ -971,7 +979,7 @@ pcl::ImageGrabberBase::getCurrentDepthFileName () const pathname = impl_->depth_pclzf_files_[impl_->cur_frame_]; else pathname = impl_->depth_image_files_[impl_->cur_frame_]; - std::string basename = boost::filesystem::path (pathname).stem ().string (); + std::string basename = pcl_fs::path (pathname).stem ().string (); return (basename); } ////////////////////////////////////////////////////////////////////////////////////////// @@ -983,7 +991,7 @@ pcl::ImageGrabberBase::getPrevDepthFileName () const pathname = impl_->depth_pclzf_files_[impl_->cur_frame_-1]; else pathname = impl_->depth_image_files_[impl_->cur_frame_-1]; - std::string basename = boost::filesystem::path (pathname).stem ().string (); + std::string basename = pcl_fs::path (pathname).stem ().string (); return (basename); } @@ -996,7 +1004,7 @@ pcl::ImageGrabberBase::getDepthFileNameAtIndex (std::size_t idx) const pathname = impl_->depth_pclzf_files_[idx]; else pathname = impl_->depth_image_files_[idx]; - std::string basename = boost::filesystem::path (pathname).stem ().string (); + std::string basename = pcl_fs::path (pathname).stem ().string (); return (basename); } diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index ab59a6eeb11..e6104748935 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -40,7 +40,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include #include @@ -357,7 +365,7 @@ pcl::io::LZFImageReader::loadImageBlob (const std::string &filename, std::vector &data, std::uint32_t &uncompressed_size) { - if (filename.empty() || !boost::filesystem::exists (filename)) + if (filename.empty() || !pcl_fs::exists (filename)) { PCL_ERROR ("[pcl::io::LZFImageReader::loadImage] Could not find file '%s'.\n", filename.c_str ()); return (false); diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 4f20368d29c..e77d350fbf6 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -42,7 +42,15 @@ #include #include // for lexical_cast + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif + #include // for trim pcl::MTLReader::MTLReader () @@ -152,7 +160,7 @@ pcl::MTLReader::read (const std::string& obj_file_name, return (-1); } - if (!boost::filesystem::exists (obj_file_name)) + if (!pcl_fs::exists (obj_file_name)) { PCL_ERROR ("[pcl::MTLReader::read] Could not find file '%s'!\n", obj_file_name.c_str ()); @@ -165,8 +173,8 @@ pcl::MTLReader::read (const std::string& obj_file_name, return (-1); } - boost::filesystem::path obj_file_path (obj_file_name.c_str ()); - boost::filesystem::path mtl_file_path = obj_file_path.parent_path (); + pcl_fs::path obj_file_path (obj_file_name.c_str ()); + pcl_fs::path mtl_file_path = obj_file_path.parent_path (); mtl_file_path /= mtl_file_name; return (read (mtl_file_path.string ())); } @@ -201,7 +209,7 @@ pcl::MTLReader::read (const std::string& mtl_file_path) std::string line; std::vector st; - boost::filesystem::path parent_path = mtl_file_path.c_str (); + pcl_fs::path parent_path = mtl_file_path.c_str (); parent_path = parent_path.parent_path (); try @@ -322,7 +330,7 @@ pcl::MTLReader::read (const std::string& mtl_file_path) if (st[0] == "map_Kd") { - boost::filesystem::path full_path = parent_path; + pcl_fs::path full_path = parent_path; full_path/= st.back ().c_str (); materials_.back ().tex_file = full_path.string (); continue; diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 2ce1b603620..68dce0cf1d3 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -50,7 +50,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif using namespace pcl::io::openni2; @@ -292,7 +299,7 @@ pcl::io::OpenNI2Grabber::setupDevice (const std::string& device_id, const Mode& try { - if (boost::filesystem::exists (device_id)) + if (pcl_fs::exists (device_id)) { device_ = deviceManager->getFileDevice (device_id); // Treat as file path } diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 04d43c765d5..4f577c4a523 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -47,7 +47,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif using namespace std::chrono_literals; @@ -303,7 +310,7 @@ pcl::OpenNIGrabber::setupDevice (const std::string& device_id, const Mode& depth try { - if (boost::filesystem::exists (device_id)) + if (pcl_fs::exists (device_id)) { device_ = driver.createVirtualDevice (device_id, true, true); } diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 0407cc9587c..0bcd3a40fdf 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -51,7 +51,14 @@ #include #include + +#if (__cplusplus >= 201703L) +#include // for permissions +namespace pcl_fs = std::filesystem; +#else #include // for permissions +namespace pcl_fs = boost::filesystem; +#endif /////////////////////////////////////////////////////////////////////////////////////////// void @@ -69,10 +76,13 @@ pcl::PCDWriter::setLockingPermissions (const std::string &file_name, else PCL_DEBUG ("[pcl::PCDWriter::setLockingPermissions] File %s could not be locked!\n", file_name.c_str ()); - namespace fs = boost::filesystem; try { - fs::permissions (fs::path (file_name), fs::add_perms | fs::set_gid_on_exe); +#if (__cplusplus >= 201703L) + pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::add); +#else + pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::add_perms | pcl_fs::set_gid_on_exe); +#endif } catch (const std::exception &e) { @@ -90,10 +100,13 @@ pcl::PCDWriter::resetLockingPermissions (const std::string &file_name, pcl::utils::ignore(file_name, lock); #ifndef _WIN32 #ifndef NO_MANDATORY_LOCKING - namespace fs = boost::filesystem; try { - fs::permissions (fs::path (file_name), fs::remove_perms | fs::set_gid_on_exe); +#if (__cplusplus >= 201703L) + pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::remove); +#else + pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::remove_perms | pcl_fs::set_gid_on_exe); +#endif } catch (const std::exception &e) { @@ -677,7 +690,7 @@ pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, return (-1); } - if (!boost::filesystem::exists (file_name)) + if (!pcl_fs::exists (file_name)) { PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ()); return (-1); diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index aaedca8f39d..9197eb2f53f 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -46,12 +46,17 @@ #include #include +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else // 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 pcl_fs = boost::filesystem; +#endif -namespace fs = boost::filesystem; +#include // for split std::tuple, std::function > pcl::PLYReader::elementDefinitionCallback (const std::string& element_name, std::size_t count) @@ -582,7 +587,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, int data_type; unsigned int data_idx; - if (!fs::exists (file_name)) + if (!pcl_fs::exists (file_name)) { PCL_ERROR ("[pcl::PLYReader::read] File (%s) not found!\n",file_name.c_str ()); return (-1); @@ -682,7 +687,7 @@ pcl::PLYReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, unsigned int data_idx; polygons_ = &(mesh.polygons); - if (!fs::exists (file_name)) + if (!pcl_fs::exists (file_name)) { PCL_ERROR ("[pcl::PLYReader::read] File (%s) not found!\n",file_name.c_str ()); return (-1); diff --git a/test/io/test_grabbers.cpp b/test/io/test_grabbers.cpp index 09185f9f8d2..81e3e4fb670 100644 --- a/test/io/test_grabbers.cpp +++ b/test/io/test_grabbers.cpp @@ -7,7 +7,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for directory_iterator, extension +namespace pcl_fs = std::filesystem; +#else #include // for directory_iterator, extension +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace std::chrono_literals; @@ -519,8 +527,8 @@ int pclzf_dir_ = grabber_sequences + "/pclzf"; pcd_dir_ = grabber_sequences + "/pcd"; // Get pcd files - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (pcd_dir_); itr != end_itr; ++itr) { if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { diff --git a/tools/converter.cpp b/tools/converter.cpp index dd155ec41c9..68deafdcd95 100644 --- a/tools/converter.cpp +++ b/tools/converter.cpp @@ -52,7 +52,14 @@ #include #include // for pcl::make_shared +#if (__cplusplus >= 201703L) +#include // for std::filesystem::path +namespace pcl_fs = std::filesystem; +#else #include // for boost::filesystem::path +namespace pcl_fs = boost::filesystem; +#endif + #include // for boost::algorithm::ends_with #define ASCII 0 @@ -103,7 +110,7 @@ savePointCloud (const pcl::PCLPointCloud2::Ptr& input, std::string output_file, int output_type) { - if (boost::filesystem::path (output_file).extension () == ".pcd") + if (pcl_fs::path (output_file).extension () == ".pcd") { //TODO Support precision, origin, orientation pcl::PCDWriter w; @@ -126,7 +133,7 @@ savePointCloud (const pcl::PCLPointCloud2::Ptr& input, return (false); } } - else if (boost::filesystem::path (output_file).extension () == ".stl") + else if (pcl_fs::path (output_file).extension () == ".stl") { PCL_ERROR ("STL file format does not support point clouds! Aborting.\n"); return (false); @@ -156,7 +163,7 @@ saveMesh (pcl::PolygonMesh& input, std::string output_file, int output_type) { - if (boost::filesystem::path (output_file).extension () == ".obj") + if (pcl_fs::path (output_file).extension () == ".obj") { if (output_type == BINARY || output_type == BINARY_COMPRESSED) PCL_WARN ("OBJ file format only supports ASCII.\n"); @@ -167,7 +174,7 @@ saveMesh (pcl::PolygonMesh& input, if (pcl::io::saveOBJFile (output_file, input) != 0) return (false); } - else if (boost::filesystem::path (output_file).extension () == ".pcd") + else if (pcl_fs::path (output_file).extension () == ".pcd") { if (!input.polygons.empty ()) PCL_WARN ("PCD file format does not support meshes! Only points be saved.\n"); @@ -180,7 +187,7 @@ saveMesh (pcl::PolygonMesh& input, if (output_type == BINARY_COMPRESSED) PCL_WARN ("PLY, STL and VTK file formats only supports ASCII and binary output file types.\n"); - if (input.polygons.empty() && boost::filesystem::path (output_file).extension () == ".stl") + if (input.polygons.empty() && pcl_fs::path (output_file).extension () == ".stl") { PCL_ERROR ("STL file format does not support point clouds! Aborting.\n"); return (false); @@ -263,7 +270,7 @@ main (int argc, // Try to load as mesh pcl::PolygonMesh mesh; - if (boost::filesystem::path (argv[file_args[0]]).extension () != ".pcd" && + if (pcl_fs::path (argv[file_args[0]]).extension () != ".pcd" && pcl::io::loadPolygonFile (argv[file_args[0]], mesh) != 0) { PCL_INFO ("Loaded a mesh with %d points (total size is %d) and the following channels:\n%s\n", @@ -275,7 +282,7 @@ main (int argc, if (!saveMesh (mesh, argv[file_args[1]], output_type)) return (-1); } - else if (boost::filesystem::path (argv[file_args[0]]).extension () == ".stl") + else if (pcl_fs::path (argv[file_args[0]]).extension () == ".stl") { PCL_ERROR ("Unable to load %s.\n", argv[file_args[0]]); return (-1); @@ -283,7 +290,7 @@ main (int argc, else { // PCD, OBJ, PLY or VTK - if (boost::filesystem::path (argv[file_args[0]]).extension () != ".pcd") + if (pcl_fs::path (argv[file_args[0]]).extension () != ".pcd") PCL_WARN ("Could not load %s as a mesh, trying as a point cloud instead.\n", argv[file_args[0]]); //Eigen::Vector4f origin; // TODO: Support origin/orientation diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index ff9d49544a3..3c9a6ca0aa1 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -41,7 +41,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -131,7 +139,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, sigma_s, sigma_r); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_files[i]).filename().string(); + std::string filename = pcl_fs::path(pcd_files[i]).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -203,11 +211,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/grid_min.cpp b/tools/grid_min.cpp index 1a5c2fa913a..d3bf263b48b 100644 --- a/tools/grid_min.cpp +++ b/tools/grid_min.cpp @@ -44,7 +44,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -129,7 +137,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, resolution); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -195,11 +203,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/image_grabber_saver.cpp b/tools/image_grabber_saver.cpp index 1dab5d9230d..34af68249b1 100644 --- a/tools/image_grabber_saver.cpp +++ b/tools/image_grabber_saver.cpp @@ -40,7 +40,14 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif using pcl::console::print_error; using pcl::console::print_info; @@ -108,7 +115,7 @@ main (int argc, char** argv) pcl::console::parse_argument (argc, argv, "-out_dir", out_folder); - if (out_folder.empty() || !boost::filesystem::exists (out_folder)) + if (out_folder.empty() || !pcl_fs::exists (out_folder)) { PCL_INFO("No correct directory was given with the -out_dir flag. Setting to current dir\n"); out_folder = "./"; @@ -116,7 +123,7 @@ main (int argc, char** argv) else PCL_INFO("Using %s as output dir", out_folder.c_str()); - if (!rgb_path.empty() && !depth_path.empty() && boost::filesystem::exists (rgb_path) && boost::filesystem::exists (depth_path)) + if (!rgb_path.empty() && !depth_path.empty() && pcl_fs::exists (rgb_path) && pcl_fs::exists (depth_path)) { grabber.reset (new pcl::ImageGrabber (depth_path, rgb_path, frames_per_second, false)); } diff --git a/tools/image_grabber_viewer.cpp b/tools/image_grabber_viewer.cpp index 4cf45843fe1..19b365c3a0e 100644 --- a/tools/image_grabber_viewer.cpp +++ b/tools/image_grabber_viewer.cpp @@ -45,7 +45,14 @@ #include #include + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif using namespace std::chrono_literals; using pcl::console::print_error; @@ -197,7 +204,7 @@ main (int argc, char** argv) std::string path; pcl::console::parse_argument (argc, argv, "-dir", path); std::cout << "path: " << path << std::endl; - if (!path.empty() && boost::filesystem::exists (path)) + if (!path.empty() && pcl_fs::exists (path)) { grabber.reset (new pcl::ImageGrabber (path, frames_per_second, repeat, use_pclzf)); } diff --git a/tools/local_max.cpp b/tools/local_max.cpp index 665aee3759c..18806a8d035 100644 --- a/tools/local_max.cpp +++ b/tools/local_max.cpp @@ -44,7 +44,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -130,7 +138,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, radius); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -196,11 +204,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/morph.cpp b/tools/morph.cpp index 7c33cdbd2fa..0f37f006d59 100644 --- a/tools/morph.cpp +++ b/tools/morph.cpp @@ -44,7 +44,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -151,7 +159,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, resolution, method); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -219,11 +227,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index 149427c3d68..61aae380223 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -45,7 +45,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -150,7 +158,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, k, radius); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_files[i]).filename().string(); + std::string filename = pcl_fs::path(pcd_files[i]).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -222,11 +230,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/passthrough_filter.cpp b/tools/passthrough_filter.cpp index f79a87f0d63..7a23172df57 100644 --- a/tools/passthrough_filter.cpp +++ b/tools/passthrough_filter.cpp @@ -42,7 +42,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -138,7 +146,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, field_name, min, max, inside, keep_organized); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -211,11 +219,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/pcd_grabber_viewer.cpp b/tools/pcd_grabber_viewer.cpp index b8216c3a82a..f68761edb9e 100644 --- a/tools/pcd_grabber_viewer.cpp +++ b/tools/pcd_grabber_viewer.cpp @@ -41,7 +41,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for exists, extension, ... +namespace pcl_fs = std::filesystem; +#else #include // for exists, extension, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy #include #include @@ -179,7 +187,7 @@ main (int argc, char** argv) std::string path; pcl::console::parse_argument (argc, argv, "-file", path); std::cout << "path: " << path << std::endl; - if (!path.empty() && boost::filesystem::exists (path)) + if (!path.empty() && pcl_fs::exists (path)) { grabber.reset (new pcl::PCDGrabber (path, frames_per_second, repeat)); } @@ -188,10 +196,10 @@ main (int argc, char** argv) std::vector pcd_files; pcl::console::parse_argument (argc, argv, "-dir", path); std::cout << "path: " << path << std::endl; - if (!path.empty() && boost::filesystem::exists (path)) + if (!path.empty() && pcl_fs::exists (path)) { - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (path); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (path); itr != end_itr; ++itr) { if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) { diff --git a/tools/progressive_morphological_filter.cpp b/tools/progressive_morphological_filter.cpp index 943d5657c9d..95fc9327eda 100644 --- a/tools/progressive_morphological_filter.cpp +++ b/tools/progressive_morphological_filter.cpp @@ -46,7 +46,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -188,7 +196,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, max_window_size, slope, max_distance, initial_distance, cell_size, base, exponential, approximate); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -297,11 +305,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/radius_filter.cpp b/tools/radius_filter.cpp index be5c50dbd8b..1617ffabefc 100644 --- a/tools/radius_filter.cpp +++ b/tools/radius_filter.cpp @@ -40,7 +40,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy @@ -131,7 +139,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, radius, inside, keep_organized); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -201,11 +209,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/sac_segmentation_plane.cpp b/tools/sac_segmentation_plane.cpp index 45554684055..cc71f5ffaac 100644 --- a/tools/sac_segmentation_plane.cpp +++ b/tools/sac_segmentation_plane.cpp @@ -43,7 +43,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif + #include // for to_upper_copy using namespace pcl; @@ -191,7 +199,7 @@ batchProcess (const std::vector &pcd_files, std::string &output_dir compute (cloud, output, max_it, thresh, negative); // Prepare output file name - std::string filename = boost::filesystem::path(pcd_file).filename().string(); + std::string filename = pcl_fs::path(pcd_file).filename().string(); // Save into the second file const std::string filepath = output_dir + '/' + filename; @@ -276,11 +284,11 @@ main (int argc, char** argv) } else { - if (!input_dir.empty() && boost::filesystem::exists (input_dir)) + if (!input_dir.empty() && pcl_fs::exists (input_dir)) { std::vector pcd_files; - boost::filesystem::directory_iterator end_itr; - for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr) + pcl_fs::directory_iterator end_itr; + for (pcl_fs::directory_iterator itr (input_dir); itr != end_itr; ++itr) { // Only add PCD files if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (itr->path ().extension ().string ()) == ".PCD" ) diff --git a/tools/tiff2pcd.cpp b/tools/tiff2pcd.cpp index d92eddab469..c181068492c 100644 --- a/tools/tiff2pcd.cpp +++ b/tools/tiff2pcd.cpp @@ -40,7 +40,14 @@ **/ #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif #include #include @@ -235,12 +242,12 @@ int main(int argc, char ** argv) PCL_INFO ("Creating RGB Tiff List\n"); std::vector tiff_rgb_files; - std::vector tiff_rgb_paths; - boost::filesystem::directory_iterator end_itr; + std::vector tiff_rgb_paths; + pcl_fs::directory_iterator end_itr; - if(boost::filesystem::is_directory(rgb_path_)) + if(pcl_fs::is_directory(rgb_path_)) { - for (boost::filesystem::directory_iterator itr(rgb_path_); itr != end_itr; ++itr) + for (pcl_fs::directory_iterator itr(rgb_path_); itr != end_itr; ++itr) { std::string ext = itr->path().extension().string(); if(ext == ".tiff") @@ -278,11 +285,11 @@ int main(int argc, char ** argv) PCL_INFO ("Creating Depth Tiff List\n"); std::vector tiff_depth_files; - std::vector tiff_depth_paths; + std::vector tiff_depth_paths; - if(boost::filesystem::is_directory(depth_path_)) + if(pcl_fs::is_directory(depth_path_)) { - for (boost::filesystem::directory_iterator itr(depth_path_); itr != end_itr; ++itr) + for (pcl_fs::directory_iterator itr(depth_path_); itr != end_itr; ++itr) { std::string ext = itr->path().extension().string(); if(ext == ".tiff") diff --git a/tools/unary_classifier_segment.cpp b/tools/unary_classifier_segment.cpp index cdec686d155..785dc233227 100644 --- a/tools/unary_classifier_segment.cpp +++ b/tools/unary_classifier_segment.cpp @@ -45,7 +45,14 @@ #include // for removeNaNFromPointCloud #include + +#if (__cplusplus >= 201703L) +#include // for path, exists, ... +namespace pcl_fs = std::filesystem; +#else #include // for path, exists, ... +namespace pcl_fs = boost::filesystem; +#endif using namespace pcl; using namespace pcl::io; @@ -76,14 +83,14 @@ printHelp (int, char **argv) bool loadTrainedFeatures (std::vector &out, - const boost::filesystem::path &base_dir) + const pcl_fs::path &base_dir) { - if (!boost::filesystem::exists (base_dir) && !boost::filesystem::is_directory (base_dir)) + if (!pcl_fs::exists (base_dir) && !pcl_fs::is_directory (base_dir)) return false; - for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it) + for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it) { - if (!boost::filesystem::is_directory (it->status ()) && + if (!pcl_fs::is_directory (it->status ()) && it->path ().extension ().string () == ".pcd") { const std::string path = it->path ().string (); diff --git a/tools/uniform_sampling.cpp b/tools/uniform_sampling.cpp index 269552b16aa..674971859fa 100644 --- a/tools/uniform_sampling.cpp +++ b/tools/uniform_sampling.cpp @@ -41,7 +41,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include #include @@ -129,7 +137,7 @@ saveCloud (const std::string &filename, const pcl::PCLPointCloud2 &output) PCDWriter w_pcd; PLYWriter w_ply; - std::string output_ext = boost::filesystem::path (filename).extension ().string (); + std::string output_ext = pcl_fs::path (filename).extension ().string (); std::transform (output_ext.begin (), output_ext.end (), output_ext.begin (), ::tolower); if (output_ext == ".pcd") diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index d339a88413d..19a854db861 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -64,7 +64,14 @@ #include #include // for boost::is_any_of, boost::split, boost::token_compress_on, boost::trim + +#if (__cplusplus >= 201703L) +#include // for std::filesystem::create_directories, std::filesystem::exists, std::filesystem::path, std::filesystem::path::extension +namespace pcl_fs = std::filesystem; +#else #include // for boost::filesystem::create_directories, boost::filesystem::exists, boost::filesystem::path, boost::filesystem::path::extension +namespace pcl_fs = boost::filesystem; +#endif using namespace pcl; @@ -87,7 +94,7 @@ struct ScanParameters vtkPolyData* loadDataSet (const char* file_name) { - std::string extension = boost::filesystem::path (file_name).extension ().string (); + std::string extension = pcl_fs::path (file_name).extension ().string (); if (extension == ".ply") { vtkPLYReader* reader = vtkPLYReader::New (); @@ -413,10 +420,10 @@ main (int argc, char** argv) const std::string output_dir = st.at (st.size () - 1) + "_output"; - boost::filesystem::path outpath (output_dir); - if (!boost::filesystem::exists (outpath)) + pcl_fs::path outpath (output_dir); + if (!pcl_fs::exists (outpath)) { - if (!boost::filesystem::create_directories (outpath)) + if (!pcl_fs::create_directories (outpath)) { PCL_ERROR ("Error creating directory %s.\n", output_dir.c_str ()); return (-1); diff --git a/visualization/src/interactor_style.cpp b/visualization/src/interactor_style.cpp index 58633fe59d4..91728eb56f8 100644 --- a/visualization/src/interactor_style.cpp +++ b/visualization/src/interactor_style.cpp @@ -69,7 +69,14 @@ #include // for is_any_of #include // for split + +#if (__cplusplus >= 201703L) +#include // for exists +namespace pcl_fs = std::filesystem; +#else #include // for exists +namespace pcl_fs = boost::filesystem; +#endif #define ORIENT_MODE 0 #define SELECT_MODE 1 @@ -610,7 +617,7 @@ pcl::visualization::PCLVisualizerInteractorStyle::OnKeyDown () } else { - if (boost::filesystem::exists (camera_file_)) + if (pcl_fs::exists (camera_file_)) { if (loadCameraParameters (camera_file_)) { diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index c8a189ccd67..cb3f0151f50 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -102,7 +102,15 @@ #else #include #endif + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include // for split #include // pcl::utils::ignore #include @@ -465,7 +473,7 @@ void pcl::visualization::PCLVisualizer::setupCamera (int argc, char **argv) std::string camera_file = getUniqueCameraFile (argc, argv); if (!camera_file.empty ()) { - if (boost::filesystem::exists (camera_file) && style_->loadCameraParameters (camera_file)) + if (pcl_fs::exists (camera_file) && style_->loadCameraParameters (camera_file)) { camera_file_loaded_ = true; } @@ -4451,39 +4459,39 @@ pcl::visualization::PCLVisualizer::textureFromTexMaterial (const pcl::TexMateria return (-1); } - boost::filesystem::path full_path (tex_mat.tex_file.c_str ()); - if (!boost::filesystem::exists (full_path)) + pcl_fs::path full_path (tex_mat.tex_file.c_str ()); + if (!pcl_fs::exists (full_path)) { - boost::filesystem::path parent_dir = full_path.parent_path (); + pcl_fs::path parent_dir = full_path.parent_path (); std::string upper_filename = tex_mat.tex_file; boost::to_upper (upper_filename); std::string real_name; try { - if (!boost::filesystem::exists (parent_dir)) + if (!pcl_fs::exists (parent_dir)) { PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Parent directory '%s' doesn't exist!\n", parent_dir.string ().c_str ()); return (-1); } - if (!boost::filesystem::is_directory (parent_dir)) + if (!pcl_fs::is_directory (parent_dir)) { PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Parent '%s' is not a directory !\n", parent_dir.string ().c_str ()); return (-1); } - using paths_vector = std::vector; + using paths_vector = std::vector; paths_vector paths; - std::copy (boost::filesystem::directory_iterator (parent_dir), - boost::filesystem::directory_iterator (), + std::copy (pcl_fs::directory_iterator (parent_dir), + pcl_fs::directory_iterator (), back_inserter (paths)); for (const auto& path : paths) { - if (boost::filesystem::is_regular_file (path)) + if (pcl_fs::is_regular_file (path)) { std::string name = path.string (); boost::to_upper (name); @@ -4502,7 +4510,7 @@ pcl::visualization::PCLVisualizer::textureFromTexMaterial (const pcl::TexMateria return (-1); } } - catch (const boost::filesystem::filesystem_error& ex) + catch (const pcl_fs::filesystem_error& ex) { PCL_WARN ("[PCLVisualizer::textureFromTexMaterial] Error %s when looking for file %s\n!", @@ -4577,10 +4585,10 @@ pcl::visualization::PCLVisualizer::getUniqueCameraFile (int argc, char **argv) // Calculate sha1 using canonical paths for (const int &p_file_index : p_file_indices) { - boost::filesystem::path path (argv[p_file_index]); - if (boost::filesystem::exists (path)) + pcl_fs::path path (argv[p_file_index]); + if (pcl_fs::exists (path)) { - path = boost::filesystem::canonical (path); + path = pcl_fs::canonical (path); const auto pathStr = path.string (); sha1.process_bytes (pathStr.c_str(), pathStr.size()); valid = true; From b701652b58c4c698c19f542d36175b7bc797ec90 Mon Sep 17 00:00:00 2001 From: QiMingZhenFan <38323127+QiMingZhenFan@users.noreply.github.com> Date: Sat, 20 Jan 2024 18:48:20 +0800 Subject: [PATCH 184/288] Fix Bug in NormalSpaceSampling::findBin() (#5936) * Fix Bug in NormalSpaceSampling::findBin() * Avoid imprecise values for the normal[] variables --------- Co-authored-by: Ma Ruikai --- filters/include/pcl/filters/impl/normal_space.hpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/filters/include/pcl/filters/impl/normal_space.hpp b/filters/include/pcl/filters/impl/normal_space.hpp index e0100a2f4b4..3bbc610d532 100644 --- a/filters/include/pcl/filters/impl/normal_space.hpp +++ b/filters/include/pcl/filters/impl/normal_space.hpp @@ -80,9 +80,11 @@ pcl::NormalSpaceSampling::isEntireBinSampled (boost::dynamic_bi template unsigned int pcl::NormalSpaceSampling::findBin (const float *normal) { - const auto ix = static_cast (std::round (0.5f * (binsx_ - 1.f) * (normal[0] + 1.f))); - const auto iy = static_cast (std::round (0.5f * (binsy_ - 1.f) * (normal[1] + 1.f))); - const auto iz = static_cast (std::round (0.5f * (binsz_ - 1.f) * (normal[2] + 1.f))); + // in the case where normal[0] == 1.0f, ix will be binsx_, which is out of range. + // thus, use std::min to avoid this situation. + const auto ix = std::min (binsx_ - 1, static_cast (std::max (0.0f, std::floor (0.5f * (binsx_) * (normal[0] + 1.f))))); + const auto iy = std::min (binsy_ - 1, static_cast (std::max (0.0f, std::floor (0.5f * (binsy_) * (normal[1] + 1.f))))); + const auto iz = std::min (binsz_ - 1, static_cast (std::max (0.0f, std::floor (0.5f * (binsz_) * (normal[2] + 1.f))))); return ix * (binsy_*binsz_) + iy * binsz_ + iz; } From b09dff517ba6a4f4354296284496f329d0b71860 Mon Sep 17 00:00:00 2001 From: Kino Date: Sat, 20 Jan 2024 19:37:44 +0800 Subject: [PATCH 185/288] C++17 filesystem for doc/tutorials (#5934) * C++17 filesystem for doc/tutorials * Review changes --- .../iccv2011/src/build_all_object_models.cpp | 19 +++++++++---- .../iros2011/src/build_all_object_models.cpp | 19 +++++++++---- .../sources/vfh_recognition/build_tree.cpp | 20 +++++++++---- .../vfh_recognition/nearest_neighbors.cpp | 14 ++++++++-- doc/tutorials/content/vfh_recognition.rst | 28 +++++++++---------- 5 files changed, 65 insertions(+), 35 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 b9f2b423846..56f19c33d91 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 @@ -6,20 +6,27 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include // for split, is_any_of -namespace bf = boost::filesystem; inline void -getModelsInDirectory (bf::path & dir, std::string & rel_path_so_far, std::vector & relative_paths) +getModelsInDirectory (pcl_fs::path & dir, std::string & rel_path_so_far, std::vector & relative_paths) { - for (const auto& dir_entry : bf::directory_iterator(dir)) + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { //check if its a directory, then get models in it - if (bf::is_directory (dir_entry)) + if (pcl_fs::is_directory (dir_entry)) { std::string so_far = rel_path_so_far + dir_entry.path ().filename ().string () + "/"; - bf::path curr_path = dir_entry.path (); + pcl_fs::path curr_path = dir_entry.path (); getModelsInDirectory (curr_path, so_far, relative_paths); } else @@ -189,7 +196,7 @@ main (int argc, char ** argv) std::string directory (argv[1]); //Find all raw* files in input_directory - bf::path dir_path = directory; + pcl_fs::path dir_path = directory; std::vector < std::string > files; std::string start = ""; getModelsInDirectory (dir_path, start, files); 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 b9f2b423846..56f19c33d91 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 @@ -6,20 +6,27 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include // for split, is_any_of -namespace bf = boost::filesystem; inline void -getModelsInDirectory (bf::path & dir, std::string & rel_path_so_far, std::vector & relative_paths) +getModelsInDirectory (pcl_fs::path & dir, std::string & rel_path_so_far, std::vector & relative_paths) { - for (const auto& dir_entry : bf::directory_iterator(dir)) + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { //check if its a directory, then get models in it - if (bf::is_directory (dir_entry)) + if (pcl_fs::is_directory (dir_entry)) { std::string so_far = rel_path_so_far + dir_entry.path ().filename ().string () + "/"; - bf::path curr_path = dir_entry.path (); + pcl_fs::path curr_path = dir_entry.path (); getModelsInDirectory (curr_path, so_far, relative_paths); } else @@ -189,7 +196,7 @@ main (int argc, char ** argv) std::string directory (argv[1]); //Find all raw* files in input_directory - bf::path dir_path = directory; + pcl_fs::path dir_path = directory; std::vector < std::string > files; std::string start = ""; getModelsInDirectory (dir_path, start, files); diff --git a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp index 5ecb2325af5..0ff3dcaca1d 100644 --- a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp @@ -2,7 +2,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include #include #include @@ -15,7 +23,7 @@ typedef std::pair > vfh_model; * \param vfh the resultant VFH model */ bool -loadHist (const boost::filesystem::path &path, vfh_model &vfh) +loadHist (const pcl_fs::path &path, vfh_model &vfh) { int vfh_idx; // Load the file as a PCD @@ -63,22 +71,22 @@ loadHist (const boost::filesystem::path &path, vfh_model &vfh) * \param models the resultant vector of histogram models */ void -loadFeatureModels (const boost::filesystem::path &base_dir, const std::string &extension, +loadFeatureModels (const pcl_fs::path &base_dir, const std::string &extension, std::vector &models) { - if (!boost::filesystem::exists (base_dir) && !boost::filesystem::is_directory (base_dir)) + if (!pcl_fs::exists (base_dir) && !pcl_fs::is_directory (base_dir)) return; - for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it) + for (pcl_fs::directory_iterator it (base_dir); it != pcl_fs::directory_iterator (); ++it) { - if (boost::filesystem::is_directory (it->status ())) + if (pcl_fs::is_directory (it->status ())) { std::stringstream ss; ss << it->path (); pcl::console::print_highlight ("Loading %s (%lu models loaded so far).\n", ss.str ().c_str (), (unsigned long)models.size ()); loadFeatureModels (it->path (), extension, models); } - if (boost::filesystem::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) + if (pcl_fs::is_regular_file (it->status ()) && it->path ().extension ().string () == extension) { vfh_model m; if (loadHist (base_dir / it->path ().filename (), m)) diff --git a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp index e377394bcd6..5f68e8cafdd 100644 --- a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp @@ -10,7 +10,15 @@ #include #include #include + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else #include +namespace pcl_fs = boost::filesystem; +#endif + #include // for replace_last typedef std::pair > vfh_model; @@ -19,7 +27,7 @@ typedef std::pair > vfh_model; * \param vfh the resultant VFH model */ bool -loadHist (const boost::filesystem::path &path, vfh_model &vfh) +loadHist (const pcl_fs::path &path, vfh_model &vfh) { int vfh_idx; // Load the file as a PCD @@ -152,7 +160,7 @@ main (int argc, char** argv) flann::Matrix k_distances; flann::Matrix data; // Check if the data has already been saved to disk - if (!boost::filesystem::exists ("training_data.h5") || !boost::filesystem::exists ("training_data.list")) + if (!pcl_fs::exists ("training_data.h5") || !pcl_fs::exists ("training_data.list")) { pcl::console::print_error ("Could not find training data models files %s and %s!\n", training_data_h5_file_name.c_str (), training_data_list_file_name.c_str ()); @@ -167,7 +175,7 @@ main (int argc, char** argv) } // Check if the tree index has already been saved to disk - if (!boost::filesystem::exists (kdtree_idx_file_name)) + if (!pcl_fs::exists (kdtree_idx_file_name)) { pcl::console::print_error ("Could not find kd-tree index in file %s!", kdtree_idx_file_name.c_str ()); return (-1); diff --git a/doc/tutorials/content/vfh_recognition.rst b/doc/tutorials/content/vfh_recognition.rst index 41b9b626c09..24692b089c2 100644 --- a/doc/tutorials/content/vfh_recognition.rst +++ b/doc/tutorials/content/vfh_recognition.rst @@ -110,21 +110,21 @@ Once all VFH features have been loaded, we convert them to FLANN format, using: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 113-118 + :lines: 121-126 Since we're lazy, and we want to use this data (and not reload it again by crawling the directory structure in the testing phase), we dump the data to disk: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 120-126 + :lines: 128-134 Finally, we create the KdTree, and save its structure to disk: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 129-133 + :lines: 137-141 Here we will use a ``LinearIndex``, which does a brute-force search using a @@ -164,7 +164,7 @@ In lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 132-143 + :lines: 141-152 we load the first given user histogram (and ignore the rest). Then we proceed @@ -177,7 +177,7 @@ In lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 162-163 + :lines: 171-172 we load the training data from disk, together with the list of file names that @@ -185,7 +185,7 @@ we previously stored in ``build_tree.cpp``. Then, we read the kd-tree and rebuil .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 176-177 + :lines: 185-186 Here we need to make sure that we use the **exact** distance metric @@ -194,53 +194,53 @@ the tree. The most important part of the code comes here: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 178 + :lines: 187 Inside ``nearestKSearch``, we first convert the query point to FLANN format: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 75-76 + :lines: 84-85 Followed by obtaining the resultant nearest neighbor indices and distances for the query in: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 77-80 + :lines: 86-89 Lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 177-191 + :lines: 186-200 create a ``PCLVisualizer`` object, and sets up a set of different viewports (e.g., splits the screen into different chunks), which will be enabled in: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 211 + :lines: 220 Using the file names representing the models that we previously obtained in ``loadFileList``, we proceed at loading the model file names using: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 219-226 + :lines: 228-235 For visualization purposes, we demean the point cloud by computing its centroid and then subtracting it: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 238-243 + :lines: 247-252 Finally we check if the distance obtained by ``nearestKSearch`` is larger than the user given threshold, and if it is, we display a red line over the cloud that is being rendered in the viewport: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 252-258 + :lines: 261-267 Compiling and running the code From 37929839e5b9f0ab1eb2e384a0180b8df714fea8 Mon Sep 17 00:00:00 2001 From: cybaol Date: Mon, 22 Jan 2024 13:40:51 +0800 Subject: [PATCH 186/288] Add new googletest path --- cmake/Modules/FindGTestSource.cmake | 1 + 1 file changed, 1 insertion(+) diff --git a/cmake/Modules/FindGTestSource.cmake b/cmake/Modules/FindGTestSource.cmake index be2bfd1f2e9..a54c98e5baf 100644 --- a/cmake/Modules/FindGTestSource.cmake +++ b/cmake/Modules/FindGTestSource.cmake @@ -24,6 +24,7 @@ find_path(GTEST_SRC_DIR src/gtest-all.cc HINTS "${GTEST_ROOT}" "$ENV{GTEST_ROOT}" PATHS "$ENV{PROGRAMFILES}/gtest" "$ENV{PROGRAMW6432}/gtest" PATHS "$ENV{PROGRAMFILES}/gtest-1.7.0" "$ENV{PROGRAMW6432}/gtest-1.7.0" + PATH /usr/src/googletest PATH /usr/src/googletest/googletest PATH /usr/src/gtest PATH_SUFFIXES gtest src/gtest googletest/googletest) From 110739da7f0ae214b48f6a137ef40a159a85e026 Mon Sep 17 00:00:00 2001 From: Hoang Tran Date: Sun, 28 Jan 2024 21:24:20 -0500 Subject: [PATCH 187/288] Fix issue #5752. Added pragma once directive for qvtk_compatibility.h header file. --- visualization/include/pcl/visualization/qvtk_compatibility.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/visualization/include/pcl/visualization/qvtk_compatibility.h b/visualization/include/pcl/visualization/qvtk_compatibility.h index b6ac0e72f2f..8285bc6a87b 100644 --- a/visualization/include/pcl/visualization/qvtk_compatibility.h +++ b/visualization/include/pcl/visualization/qvtk_compatibility.h @@ -6,6 +6,8 @@ * * All rights reserved */ +#pragma once + #include #include From 511ea48f4ffccb4681706ad3aebd8fe17895f5db Mon Sep 17 00:00:00 2001 From: Kino Date: Thu, 1 Feb 2024 03:56:14 +0800 Subject: [PATCH 188/288] Make Boost filesystem optional for C++17 (#5937) * Make Boost filesystem optional for C++17 * Add more changes * Simpler changes * Review changes --- apps/3d_rec_framework/CMakeLists.txt | 7 +++++++ cmake/pcl_find_boost.cmake | 21 +++++++++++++++------ cmake/pcl_pclconfig.cmake | 7 +++++-- io/CMakeLists.txt | 5 ++++- outofcore/CMakeLists.txt | 10 ++++++++-- recognition/CMakeLists.txt | 10 ++++++++-- 6 files changed, 47 insertions(+), 13 deletions(-) diff --git a/apps/3d_rec_framework/CMakeLists.txt b/apps/3d_rec_framework/CMakeLists.txt index 3e8b8e997d7..504628de7e6 100644 --- a/apps/3d_rec_framework/CMakeLists.txt +++ b/apps/3d_rec_framework/CMakeLists.txt @@ -3,6 +3,13 @@ set(SUBSUBSYS_DESC "3D recognition framework") set(SUBSUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search recognition ml) set(SUBSUBSYS_EXT_DEPS vtk openni) +if(NOT TARGET Boost::filesystem) + set(DEFAULT FALSE) + set(REASON "Boost filesystem is not available.") +else() + set(DEFAULT TRUE) +endif() + # Default to not building for now if(${DEFAULT} STREQUAL "TRUE") set(DEFAULT FALSE) diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index 770607f82dc..f49e77060c9 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -19,16 +19,25 @@ set(Boost_ADDITIONAL_VERSIONS "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") -# Optional boost modules -find_package(Boost 1.65.0 QUIET COMPONENTS serialization mpi) -if(Boost_SERIALIZATION_FOUND) - set(BOOST_SERIALIZATION_FOUND TRUE) +if(CMAKE_CXX_STANDARD MATCHES "14") + # Optional boost modules + set(BOOST_OPTIONAL_MODULES serialization mpi) + # Required boost modules + set(BOOST_REQUIRED_MODULES filesystem iostreams system) +else() + # Optional boost modules + set(BOOST_OPTIONAL_MODULES filesystem serialization mpi) + # Required boost modules + set(BOOST_REQUIRED_MODULES iostreams system) endif() -# Required boost modules -set(BOOST_REQUIRED_MODULES filesystem iostreams system) +find_package(Boost 1.65.0 QUIET COMPONENTS ${BOOST_OPTIONAL_MODULES}) find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) +if(Boost_SERIALIZATION_FOUND) + set(BOOST_SERIALIZATION_FOUND TRUE) +endif() + if(Boost_FOUND) set(BOOST_FOUND TRUE) endif() diff --git a/cmake/pcl_pclconfig.cmake b/cmake/pcl_pclconfig.cmake index f0656e6ec3b..e5203284a78 100644 --- a/cmake/pcl_pclconfig.cmake +++ b/cmake/pcl_pclconfig.cmake @@ -85,7 +85,10 @@ foreach(_ss ${PCL_SUBSYSTEMS_MODULES}) endforeach() #Boost modules -set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system filesystem iostreams") +set(PCLCONFIG_AVAILABLE_BOOST_MODULES "system iostreams") +if(Boost_FILESYSTEM_FOUND) + string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " filesystem") +endif() if(Boost_SERIALIZATION_FOUND) string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " serialization") endif() @@ -101,4 +104,4 @@ install(FILES "${PCL_BINARY_DIR}/PCLConfig.cmake" "${PCL_BINARY_DIR}/PCLConfigVersion.cmake" COMPONENT pclconfig - DESTINATION ${PCLCONFIG_INSTALL_DIR}) \ No newline at end of file + DESTINATION ${PCLCONFIG_INSTALL_DIR}) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index 7fc86b26e64..be9e2f4bb74 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -343,7 +343,10 @@ PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${c target_include_directories(${LIB_NAME} PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") -target_link_libraries("${LIB_NAME}" Boost::boost Boost::filesystem Boost::iostreams pcl_common pcl_io_ply) +target_link_libraries("${LIB_NAME}" Boost::boost Boost::iostreams pcl_common pcl_io_ply) +if(TARGET Boost::filesystem) + target_link_libraries("${LIB_NAME}" Boost::filesystem) +endif() if(VTK_FOUND) if(${VTK_VERSION} VERSION_GREATER_EQUAL 9.0) diff --git a/outofcore/CMakeLists.txt b/outofcore/CMakeLists.txt index fbc515d0da8..dd2a7d8a9c5 100644 --- a/outofcore/CMakeLists.txt +++ b/outofcore/CMakeLists.txt @@ -2,8 +2,14 @@ set(SUBSYS_NAME outofcore) set(SUBSYS_DESC "Point cloud outofcore library") set(SUBSYS_DEPS common io filters octree visualization) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) +if(NOT TARGET Boost::filesystem) + set(DEFAULT FALSE) + set(REASON "Boost filesystem is not available.") +else() + set(DEFAULT TRUE) +endif() + +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 84158dc605f..3a8eb9fe19f 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -2,8 +2,14 @@ set(SUBSYS_NAME recognition) set(SUBSYS_DESC "Point cloud recognition library") set(SUBSYS_DEPS common io search kdtree octree features filters registration sample_consensus ml) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) +if(${PCL_VERSION} VERSION_LESS "1.15.0" AND NOT TARGET Boost::filesystem) + set(DEFAULT FALSE) + set(REASON "Boost filesystem is not available.") +else() + set(DEFAULT TRUE) +endif() + +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_ADD_DOC("${SUBSYS_NAME}") From 22eac9954a0a1fcae3f1e9b62ba9fbadd485f6c0 Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 09:53:02 +0100 Subject: [PATCH 189/288] Add option WITH_GLEW. Use ext_deps in simulation for Glew and Opengl. --- CMakeLists.txt | 6 ++++++ simulation/CMakeLists.txt | 5 ----- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8b015bff26f..73d03539989 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -419,6 +419,12 @@ if(WITH_OPENGL) include("${PCL_SOURCE_DIR}/cmake/pcl_find_gl.cmake") endif() +# GLEW +option(WITH_GLEW "Support for GLEW" TRUE) +if(WITH_GLEW) + find_package(GLEW QUIET) +endif() + # Boost (required) include("${PCL_SOURCE_DIR}/cmake/pcl_find_boost.cmake") diff --git a/simulation/CMakeLists.txt b/simulation/CMakeLists.txt index 22bb8207b71..1002f5d339f 100644 --- a/simulation/CMakeLists.txt +++ b/simulation/CMakeLists.txt @@ -2,11 +2,6 @@ set(SUBSYS_NAME simulation) set(SUBSYS_DESC "Point Cloud Library Simulation") set(SUBSYS_DEPS common io surface kdtree features search octree visualization filters geometry) -set(build FALSE) -find_package(OpenGL) - -find_package(GLEW) - PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS opengl glew) From 87958c2f885a78f46beae32243a20fb56f709d03 Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 09:56:40 +0100 Subject: [PATCH 190/288] Kinfu tools require glew. --- gpu/kinfu/tools/CMakeLists.txt | 2 +- gpu/kinfu_large_scale/tools/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gpu/kinfu/tools/CMakeLists.txt b/gpu/kinfu/tools/CMakeLists.txt index e1593b38001..2477f8669bf 100644 --- a/gpu/kinfu/tools/CMakeLists.txt +++ b/gpu/kinfu/tools/CMakeLists.txt @@ -2,7 +2,7 @@ set(SUBSUBSYS_NAME tools) set(SUBSUBSYS_DESC "Kinfu tools") set(SUBSUBSYS_DEPS gpu_kinfu visualization) set(SUBSUBSYS_OPT_DEPS opencv) -set(EXT_DEPS openni) +set(EXT_DEPS glew openni) set(DEFAULT TRUE) set(REASON "") diff --git a/gpu/kinfu_large_scale/tools/CMakeLists.txt b/gpu/kinfu_large_scale/tools/CMakeLists.txt index d8d654721bd..017a1907f54 100644 --- a/gpu/kinfu_large_scale/tools/CMakeLists.txt +++ b/gpu/kinfu_large_scale/tools/CMakeLists.txt @@ -2,7 +2,7 @@ set(SUBSUBSYS_NAME tools) set(SUBSUBSYS_DESC "Kinfu large scale tools") set(SUBSUBSYS_DEPS gpu_kinfu_large_scale visualization) set(SUBSUBSYS_OPT_DEPS ) -set(EXT_DEPS openni openni2) +set(EXT_DEPS glew openni openni2) set(DEFAULT TRUE) set(REASON "") From 1276628298dd44240921d6f28c15a1b5955f394a Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 10:00:04 +0100 Subject: [PATCH 191/288] Remove unncessary set build. --- common/CMakeLists.txt | 1 - features/CMakeLists.txt | 1 - filters/CMakeLists.txt | 1 - geometry/CMakeLists.txt | 1 - io/CMakeLists.txt | 1 - kdtree/CMakeLists.txt | 1 - keypoints/CMakeLists.txt | 1 - ml/CMakeLists.txt | 1 - octree/CMakeLists.txt | 1 - people/CMakeLists.txt | 1 - registration/CMakeLists.txt | 1 - sample_consensus/CMakeLists.txt | 1 - search/CMakeLists.txt | 1 - segmentation/CMakeLists.txt | 1 - tracking/CMakeLists.txt | 1 - 15 files changed, 15 deletions(-) diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index fe0ad8fa3ea..518a98df405 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME common) set(SUBSYS_DESC "Point cloud common library") set(SUBSYS_DEPS) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS eigen3 boost) diff --git a/features/CMakeLists.txt b/features/CMakeLists.txt index b5f902aece8..cdf17fdef29 100644 --- a/features/CMakeLists.txt +++ b/features/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME features) set(SUBSYS_DESC "Point cloud features library") set(SUBSYS_DEPS common search kdtree octree filters 2d) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) diff --git a/filters/CMakeLists.txt b/filters/CMakeLists.txt index f4541889fdf..a485505b5ab 100644 --- a/filters/CMakeLists.txt +++ b/filters/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME filters) set(SUBSYS_DESC "Point cloud filters library") set(SUBSYS_DEPS common sample_consensus search kdtree octree) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) diff --git a/geometry/CMakeLists.txt b/geometry/CMakeLists.txt index cafc32e43bb..0ec3e6fe5b0 100644 --- a/geometry/CMakeLists.txt +++ b/geometry/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME geometry) set(SUBSYS_DESC "Point cloud geometry library") set(SUBSYS_DEPS common) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index be9e2f4bb74..d89e5e2a6bd 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_DESC "Point cloud IO library") set(SUBSYS_DEPS common octree) set(SUBSYS_EXT_DEPS boost eigen3) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) if(WIN32) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk rssdk2 pcap png vtk OpenMP EXT_DEPS ${SUBSYS_EXT_DEPS}) diff --git a/kdtree/CMakeLists.txt b/kdtree/CMakeLists.txt index d9c94bbe45b..e015aa3178f 100644 --- a/kdtree/CMakeLists.txt +++ b/kdtree/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME kdtree) set(SUBSYS_DESC "Point cloud kd-tree library") set(SUBSYS_DEPS common) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS flann) diff --git a/keypoints/CMakeLists.txt b/keypoints/CMakeLists.txt index 480e022f253..de9189a7b47 100644 --- a/keypoints/CMakeLists.txt +++ b/keypoints/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME keypoints) set(SUBSYS_DESC "Point cloud keypoints library") set(SUBSYS_DEPS common search kdtree octree features filters) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) diff --git a/ml/CMakeLists.txt b/ml/CMakeLists.txt index 98209bea91e..a67a5835b8a 100644 --- a/ml/CMakeLists.txt +++ b/ml/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME ml) set(SUBSYS_DESC "Point cloud machine learning library") set(SUBSYS_DEPS common) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/octree/CMakeLists.txt b/octree/CMakeLists.txt index b5c58434fe8..5f5a431e928 100644 --- a/octree/CMakeLists.txt +++ b/octree/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME octree) set(SUBSYS_DESC "Point cloud octree library") set(SUBSYS_DEPS common) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/people/CMakeLists.txt b/people/CMakeLists.txt index dca32d662be..da76bb00440 100644 --- a/people/CMakeLists.txt +++ b/people/CMakeLists.txt @@ -11,7 +11,6 @@ else() include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") endif() -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/registration/CMakeLists.txt b/registration/CMakeLists.txt index 7dce51a2f91..bc8ae11a9f2 100644 --- a/registration/CMakeLists.txt +++ b/registration/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME registration) set(SUBSYS_DESC "Point cloud registration library") set(SUBSYS_DEPS common octree kdtree search sample_consensus features filters) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) diff --git a/sample_consensus/CMakeLists.txt b/sample_consensus/CMakeLists.txt index 8552beed7a7..65652158927 100644 --- a/sample_consensus/CMakeLists.txt +++ b/sample_consensus/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME sample_consensus) set(SUBSYS_DESC "Point cloud sample consensus library") set(SUBSYS_DEPS common search) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/search/CMakeLists.txt b/search/CMakeLists.txt index 0b93e5255c2..e0296cd8e95 100644 --- a/search/CMakeLists.txt +++ b/search/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME search) set(SUBSYS_DESC "Point cloud generic search library") set(SUBSYS_DEPS common kdtree octree) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS flann) diff --git a/segmentation/CMakeLists.txt b/segmentation/CMakeLists.txt index f6cdf291a5a..cb31b7bf16c 100644 --- a/segmentation/CMakeLists.txt +++ b/segmentation/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME segmentation) set(SUBSYS_DESC "Point cloud segmentation library") set(SUBSYS_DEPS common geometry search sample_consensus kdtree octree features filters ml) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) diff --git a/tracking/CMakeLists.txt b/tracking/CMakeLists.txt index 985e4ce64dc..78109d9724d 100644 --- a/tracking/CMakeLists.txt +++ b/tracking/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME tracking) set(SUBSYS_DESC "Point cloud tracking library") set(SUBSYS_DEPS common search kdtree filters octree) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS OpenMP) From c9e6b6523c4f84d203fb371af450eea4e4d62983 Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 10:01:17 +0100 Subject: [PATCH 192/288] Remove unnecessary code check for dependencies, using PCL_SUBSYS_DEPEND instead. --- cuda/CMakeLists.txt | 2 +- examples/CMakeLists.txt | 4 +--- gpu/CMakeLists.txt | 2 +- people/CMakeLists.txt | 12 ++---------- tools/CMakeLists.txt | 4 +--- visualization/CMakeLists.txt | 16 ++++++---------- 6 files changed, 12 insertions(+), 28 deletions(-) diff --git a/cuda/CMakeLists.txt b/cuda/CMakeLists.txt index c327f95e5dc..ed1c888f806 100644 --- a/cuda/CMakeLists.txt +++ b/cuda/CMakeLists.txt @@ -2,7 +2,7 @@ set(SUBSYS_NAME cuda) set(SUBSYS_DESC "Point cloud CUDA libraries") set(SUBSYS_DEPS) -option(BUILD_CUDA "Build the CUDA-related subsystems" ${DEFAULT}) +option(BUILD_CUDA "Build the CUDA-related subsystems" OFF) if(NOT (BUILD_CUDA AND CUDA_FOUND)) return() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index d89aa99bc11..62c02de49e0 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -2,9 +2,7 @@ set(SUBSYS_NAME examples) set(SUBSYS_DESC "PCL examples") set(SUBSYS_DEPS common io features search kdtree octree filters keypoints segmentation sample_consensus outofcore stereo geometry surface) -set(DEFAULT FALSE) -set(REASON "Code examples are disabled by default.") -PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON}) +PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) if(NOT build) diff --git a/gpu/CMakeLists.txt b/gpu/CMakeLists.txt index 45daad5c6ef..a126cef8ac7 100644 --- a/gpu/CMakeLists.txt +++ b/gpu/CMakeLists.txt @@ -2,7 +2,7 @@ set(SUBSYS_NAME gpu) set(SUBSYS_DESC "Point cloud GPU libraries") set(SUBSYS_DEPS) -option(BUILD_GPU "Build the GPU-related subsystems" ${DEFAULT}) +option(BUILD_GPU "Build the GPU-related subsystems" OFF) if(NOT (BUILD_GPU AND CUDA_FOUND)) return() diff --git a/people/CMakeLists.txt b/people/CMakeLists.txt index da76bb00440..73780f0a3ee 100644 --- a/people/CMakeLists.txt +++ b/people/CMakeLists.txt @@ -1,18 +1,10 @@ set(SUBSYS_NAME people) set(SUBSYS_DESC "Point cloud people library") set(SUBSYS_DEPS common kdtree search sample_consensus filters io visualization geometry segmentation octree) - -if(NOT VTK_FOUND) - set(DEFAULT FALSE) - set(REASON "VTK was not found.") -else() - set(DEFAULT TRUE) - set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") -endif() +set(EXT_DEPS vtk) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS}) PCL_ADD_DOC("${SUBSYS_NAME}") diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index a4151e9c2d4..3362164f66c 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -2,10 +2,8 @@ set(SUBSYS_NAME tools) set(SUBSYS_DESC "Useful PCL-based command line tools") set(SUBSYS_DEPS io) set(SUBSYS_OPT_DEPS filters sample_consensus segmentation search kdtree features surface octree registration recognition geometry keypoints ml visualization vtk) -set(DEFAULT ON) -set(REASON "") -PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON}) +PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS}) if(NOT build) diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index 9c4e000ecf3..586c475e353 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -2,16 +2,7 @@ set(SUBSYS_NAME visualization) set(SUBSYS_DESC "Point cloud visualization library") set(SUBSYS_DEPS common io kdtree geometry search octree) -if(NOT VTK_FOUND) - set(DEFAULT FALSE) - set(REASON "VTK was not found.") -else() - set(DEFAULT TRUE) - set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") -endif() - -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS vtk OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk) if(ANDROID) @@ -147,6 +138,11 @@ endif() set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${common_incs} ${impl_incs} ${common_impl_incs} ${vtk_incs}) +target_include_directories(${LIB_NAME} PUBLIC + $ + $ +) + # apple workaround (continued) if(APPLE) target_link_libraries("${LIB_NAME}" "-framework Cocoa") From fa56699510a926d0c669afc1e346b4be2dc9e855 Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 10:02:50 +0100 Subject: [PATCH 193/288] Kinfu_large_scale screenshot mananger depends on saveRgbPNGFile, which is in IO only if VTK is available. --- gpu/kinfu_large_scale/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gpu/kinfu_large_scale/CMakeLists.txt b/gpu/kinfu_large_scale/CMakeLists.txt index 0488fcb46aa..a5d4bac8fb5 100644 --- a/gpu/kinfu_large_scale/CMakeLists.txt +++ b/gpu/kinfu_large_scale/CMakeLists.txt @@ -2,6 +2,8 @@ set(SUBSYS_NAME gpu_kinfu_large_scale) set(SUBSYS_PATH gpu/kinfu_large_scale) set(SUBSYS_DESC "Kinect Fusion implementation, with volume shifting") set(SUBSYS_DEPS common io gpu_containers gpu_utils geometry search octree filters kdtree features surface) +set(EXT_DEPS vtk) # Uses saveRgbPNGFile from png_io, which requires VTK to be present + if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0") set(DEFAULT FALSE) set(REASON "Kinfu_large_scale uses textures which was removed in CUDA 12") @@ -10,7 +12,7 @@ else() endif() PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") mark_as_advanced("BUILD_${SUBSYS_NAME}") From 0220972c4c52ae7d41c1711846347bbbaffe748d Mon Sep 17 00:00:00 2001 From: = <=> Date: Fri, 2 Feb 2024 10:03:28 +0100 Subject: [PATCH 194/288] Remove dublicate BUILD_tools option. --- cmake/pcl_options.cmake | 2 -- 1 file changed, 2 deletions(-) diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index e4ca977857a..7955f1171e0 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -88,8 +88,6 @@ mark_as_advanced(CMAKE_MSVC_CODE_LINK_OPTIMIZATION) # Project folders set_property(GLOBAL PROPERTY USE_FOLDERS ON) -option(BUILD_tools "Useful PCL-based command line tools" ON) - option(WITH_DOCS "Build doxygen documentation" OFF) # set index size From aa667c1f19f991ae81d186c4d0150f59b2fefe76 Mon Sep 17 00:00:00 2001 From: Rasmus Date: Sat, 3 Feb 2024 16:00:15 +0100 Subject: [PATCH 195/288] VoxelGridOcclusionEstimation should always round down to go from coordinates to voxel indices. (#5942) * VoxelGrid coordinate to index mappoing should always round down * occlusion estimation: Fix floating point inaccuracies placing entry voxel outside of cloud bounding box * add VoxelGridOcclusionEstimation test * Fix incorrect doc * Fix missing include * add epsilon to ray entry coordinate in second location as well --- .../impl/voxel_grid_occlusion_estimation.hpp | 43 ++++++++++--------- .../filters/voxel_grid_occlusion_estimation.h | 5 +-- test/filters/test_filters.cpp | 22 ++++++++++ 3 files changed, 46 insertions(+), 24 deletions(-) diff --git a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp index 63fac68a267..f065e2da49d 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_occlusion_estimation.hpp @@ -47,7 +47,7 @@ pcl::VoxelGridOcclusionEstimation::initializeVoxelGrid () { // initialization set to true initialized_ = true; - + // create the voxel grid and store the output cloud this->filter (filtered_cloud_); @@ -162,13 +162,13 @@ pcl::VoxelGridOcclusionEstimation::occlusionEstimationAll (std::vector::occlusionEstimationAll (std::vector float -pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vector4f& origin, +pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vector4f& origin, const Eigen::Vector4f& direction) { float tmin, tmax, tymin, tymax, tzmin, tzmax; @@ -198,7 +198,7 @@ pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vect if (direction[1] >= 0) { tymin = (b_min_[1] - origin[1]) / direction[1]; - tymax = (b_max_[1] - origin[1]) / direction[1]; + tymax = (b_max_[1] - origin[1]) / direction[1]; } else { @@ -233,7 +233,7 @@ pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vect { PCL_ERROR ("no intersection with the bounding box \n"); tmin = -1.0f; - return tmin; + return tmin; } if (tzmin > tmin) @@ -246,15 +246,16 @@ pcl::VoxelGridOcclusionEstimation::rayBoxIntersection (const Eigen::Vect ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template int pcl::VoxelGridOcclusionEstimation::rayTraversal (const Eigen::Vector3i& target_voxel, - const Eigen::Vector4f& origin, + const Eigen::Vector4f& origin, const Eigen::Vector4f& direction, const float t_min) { - // coordinate of the boundary of the voxel grid - Eigen::Vector4f start = origin + t_min * direction; + // coordinate of the boundary of the voxel grid. To avoid numerical imprecision + // causing the start voxel index to be off by one, we add the machine epsilon + Eigen::Vector4f start = origin + (t_min > 0.0f ? (t_min + std::numeric_limits::epsilon()) : t_min) * direction; // i,j,k coordinate of the voxel were the ray enters the voxel grid - Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]); + Eigen::Vector3i ijk = this->getGridCoordinates(start[0], start[1], start[2]); // steps in which direction we have to travel in the voxel grid int step_x, step_y, step_z; @@ -296,13 +297,13 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (const Eigen::Vector3i& float t_max_x = t_min + (voxel_max[0] - start[0]) / direction[0]; float t_max_y = t_min + (voxel_max[1] - start[1]) / direction[1]; float t_max_z = t_min + (voxel_max[2] - start[2]) / direction[2]; - + float t_delta_x = leaf_size_[0] / static_cast (std::abs (direction[0])); float t_delta_y = leaf_size_[1] / static_cast (std::abs (direction[1])); float t_delta_z = leaf_size_[2] / static_cast (std::abs (direction[2])); - while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && - (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && + while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && + (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) ) { // check if we reached target voxel @@ -339,7 +340,7 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (const Eigen::Vector3i& template int pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector >& out_ray, const Eigen::Vector3i& target_voxel, - const Eigen::Vector4f& origin, + const Eigen::Vector4f& origin, const Eigen::Vector4f& direction, const float t_min) { @@ -347,12 +348,12 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector 0.0f ? (t_min + std::numeric_limits::epsilon()) : t_min) * direction; // i,j,k coordinate of the voxel were the ray enters the voxel grid - Eigen::Vector3i ijk = getGridCoordinatesRound (start[0], start[1], start[2]); - //Eigen::Vector3i ijk = this->getGridCoordinates (start_x, start_y, start_z); + Eigen::Vector3i ijk = this->getGridCoordinates (start[0], start[1], start[2]); // steps in which direction we have to travel in the voxel grid int step_x, step_y, step_z; @@ -394,7 +395,7 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector (std::abs (direction[0])); float t_delta_y = leaf_size_[1] / static_cast (std::abs (direction[1])); float t_delta_z = leaf_size_[2] / static_cast (std::abs (direction[2])); @@ -402,8 +403,8 @@ pcl::VoxelGridOcclusionEstimation::rayTraversal (std::vector= min_b_[0]) && - (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && + while ( (ijk[0] < max_b_[0]+1) && (ijk[0] >= min_b_[0]) && + (ijk[1] < max_b_[1]+1) && (ijk[1] >= min_b_[1]) && (ijk[2] < max_b_[2]+1) && (ijk[2] >= min_b_[2]) ) { // add voxel to ray diff --git a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h index a55b84b3f30..1518d329809 100644 --- a/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h +++ b/filters/include/pcl/filters/voxel_grid_occlusion_estimation.h @@ -216,7 +216,7 @@ namespace pcl const Eigen::Vector4f& direction, const float t_min); - /** \brief Returns a rounded value. + /** \brief Returns a value rounded to the nearest integer * \param[in] d * \return rounded value */ @@ -226,8 +226,7 @@ namespace pcl return static_cast (std::floor (d + 0.5f)); } - // We use round here instead of std::floor due to some numerical issues. - /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). + /** \brief Returns the corresponding (i,j,k) coordinates in the grid of point (x,y,z). * \param[in] x the X point coordinate to get the (i, j, k) index at * \param[in] y the Y point coordinate to get the (i, j, k) index at * \param[in] z the Z point coordinate to get the (i, j, k) index at diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index 2cc5b88361e..aa5f0408651 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #include #include #include @@ -2460,6 +2461,27 @@ TEST (NormalRefinement, Filters) EXPECT_LT(err_refined_var, err_est_var); } +TEST (VoxelGridOcclusionEstimation, Filters) +{ + auto input_cloud = pcl::make_shared>(); + input_cloud->emplace_back(0.0, 0.0, 0.0); + input_cloud->emplace_back(9.9, 9.9, 9.9); // we want a nice bounding box from (0, 0, 0) to (10, 10, 10) + input_cloud->sensor_origin_ << -0.1, 0.5, 0.5; // just outside the bounding box. Most rays will enter at voxel (0, 0, 0) + pcl::VoxelGridOcclusionEstimation vg; + vg.setInputCloud (input_cloud); + vg.setLeafSize (1.0, 1.0, 1.0); + vg.initializeVoxelGrid (); + std::vector > occluded_voxels; + vg.occlusionEstimationAll (occluded_voxels); + for(std::size_t y=0; y<10; ++y) { + for (std::size_t z=0; z<10; ++z) { + if(y==9 && z==9) continue; // voxel (9, 9, 9) is occupied by point (9.9, 9.9, 9.9), so it will not be counted as occluded + Eigen::Vector3i cell(9, y, z); + EXPECT_NE(std::find(occluded_voxels.begin(), occluded_voxels.end(), cell), occluded_voxels.end()); // not equal means it was found + } + } +} + /* ---[ */ int main (int argc, char** argv) From 047a24f989e59372ac45c9ea85b650bec0f5461f Mon Sep 17 00:00:00 2001 From: Kino Date: Sun, 4 Feb 2024 18:12:09 +0800 Subject: [PATCH 196/288] Move filesystem headers to pcl_filesystem.h (#5945) * Move filesystem headers to pcl_filesystem.h * Add missing pcl_filesystem.h * Corresponding line changes for vfh_recognition.rst --- .../utils/persistence_utils.h | 9 +--- .../src/offline_integration.cpp | 9 +--- .../face_detection_apps_utils.h | 8 +--- apps/include/pcl/apps/pcd_video_player.h | 9 +--- .../filesystem_face_detection.cpp | 9 +--- apps/src/openni_grab_frame.cpp | 9 +--- apps/src/stereo_ground_segmentation.cpp | 9 +--- common/CMakeLists.txt | 1 + common/include/pcl/common/impl/file_io.hpp | 8 +--- common/include/pcl/common/pcl_filesystem.h | 47 +++++++++++++++++++ cuda/apps/src/kinect_planes_cuda.cpp | 9 +--- .../iccv2011/src/build_all_object_models.cpp | 9 +--- .../iros2011/src/build_all_object_models.cpp | 9 +--- .../sources/vfh_recognition/build_tree.cpp | 9 +--- .../vfh_recognition/nearest_neighbors.cpp | 9 +--- doc/tutorials/content/vfh_recognition.rst | 28 +++++------ gpu/kinfu/tools/kinfu_app.cpp | 9 +--- .../kinfu_large_scale/screenshot_manager.h | 9 +--- gpu/kinfu_large_scale/tools/kinfuLS_app.cpp | 9 +--- .../tools/standalone_texture_mapping.cpp | 9 +--- gpu/people/tools/people_app.cpp | 9 +--- io/include/pcl/io/impl/auto_io.hpp | 10 +--- io/src/ascii_io.cpp | 9 +--- io/src/image_grabber.cpp | 9 +--- io/src/lzf_image_io.cpp | 9 +--- io/src/obj_io.cpp | 10 +--- io/src/openni2_grabber.cpp | 9 +--- io/src/openni_grabber.cpp | 9 +--- io/src/pcd_io.cpp | 9 +--- io/src/ply_io.cpp | 11 +---- test/io/test_grabbers.cpp | 9 +--- tools/converter.cpp | 9 +--- tools/fast_bilateral_filter.cpp | 9 +--- tools/grid_min.cpp | 9 +--- tools/image_grabber_saver.cpp | 9 +--- tools/image_grabber_viewer.cpp | 9 +--- tools/local_max.cpp | 9 +--- tools/morph.cpp | 9 +--- tools/normal_estimation.cpp | 9 +--- tools/passthrough_filter.cpp | 9 +--- tools/pcd_grabber_viewer.cpp | 9 +--- tools/progressive_morphological_filter.cpp | 9 +--- tools/radius_filter.cpp | 10 +--- tools/sac_segmentation_plane.cpp | 9 +--- tools/tiff2pcd.cpp | 9 +--- tools/unary_classifier_segment.cpp | 9 +--- tools/uniform_sampling.cpp | 9 +--- tools/virtual_scanner.cpp | 9 +--- visualization/src/interactor_style.cpp | 9 +--- visualization/src/pcl_visualizer.cpp | 9 +--- 50 files changed, 110 insertions(+), 392 deletions(-) create mode 100644 common/include/pcl/common/pcl_filesystem.h diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h index 9415c366fe8..528a7daf4a8 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/utils/persistence_utils.h @@ -1,15 +1,8 @@ +#include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include namespace pcl { diff --git a/apps/in_hand_scanner/src/offline_integration.cpp b/apps/in_hand_scanner/src/offline_integration.cpp index 626320a4959..9de7bee7fb6 100644 --- a/apps/in_hand_scanner/src/offline_integration.cpp +++ b/apps/in_hand_scanner/src/offline_integration.cpp @@ -40,20 +40,13 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include diff --git a/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h b/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h index bce884062a0..5c3c36fea9d 100644 --- a/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h +++ b/apps/include/pcl/apps/face_detection/face_detection_apps_utils.h @@ -7,13 +7,7 @@ #pragma once -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif +#include namespace face_detection_apps_utils { diff --git a/apps/include/pcl/apps/pcd_video_player.h b/apps/include/pcl/apps/pcd_video_player.h index 657b3626e63..b10c087079a 100644 --- a/apps/include/pcl/apps/pcd_video_player.h +++ b/apps/include/pcl/apps/pcd_video_player.h @@ -35,6 +35,7 @@ */ #include +#include #include #include #include @@ -42,14 +43,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include diff --git a/apps/src/face_detection/filesystem_face_detection.cpp b/apps/src/face_detection/filesystem_face_detection.cpp index 58dbb329329..f69b8f94f73 100644 --- a/apps/src/face_detection/filesystem_face_detection.cpp +++ b/apps/src/face_detection/filesystem_face_detection.cpp @@ -5,6 +5,7 @@ * Author: Aitor Aldoma */ +#include #include #include #include @@ -13,14 +14,6 @@ #include // clang-format on -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - bool SHOW_GT = false; bool VIDEO = false; diff --git a/apps/src/openni_grab_frame.cpp b/apps/src/openni_grab_frame.cpp index cc7c454c763..2f126259619 100644 --- a/apps/src/openni_grab_frame.cpp +++ b/apps/src/openni_grab_frame.cpp @@ -35,6 +35,7 @@ * Christian Potthast (potthast@usc.edu) */ +#include #include #include #include @@ -45,14 +46,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include using namespace std::chrono_literals; diff --git a/apps/src/stereo_ground_segmentation.cpp b/apps/src/stereo_ground_segmentation.cpp index b2b8743b3d1..576705de5d6 100755 --- a/apps/src/stereo_ground_segmentation.cpp +++ b/apps/src/stereo_ground_segmentation.cpp @@ -36,6 +36,7 @@ #include // for computeMeanAndCovarianceMatrix #include #include +#include #include #include #include @@ -50,14 +51,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for directory_iterator -namespace pcl_fs = std::filesystem; -#else -#include // for directory_iterator -namespace pcl_fs = boost::filesystem; -#endif - #include using PointT = pcl::PointXYZRGB; diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index fe0ad8fa3ea..a83e6174a0d 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -98,6 +98,7 @@ set(common_incs include/pcl/common/file_io.h include/pcl/common/intersections.h include/pcl/common/norms.h + include/pcl/common/pcl_filesystem.h include/pcl/common/piecewise_linear_function.h include/pcl/common/polynomial_calculations.h include/pcl/common/poses_from_matches.h diff --git a/common/include/pcl/common/impl/file_io.hpp b/common/include/pcl/common/impl/file_io.hpp index 503c34d2437..1719e80dbd9 100644 --- a/common/include/pcl/common/impl/file_io.hpp +++ b/common/include/pcl/common/impl/file_io.hpp @@ -39,13 +39,7 @@ #ifndef PCL_COMMON_FILE_IO_IMPL_HPP_ #define PCL_COMMON_FILE_IO_IMPL_HPP_ -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif +#include #include diff --git a/common/include/pcl/common/pcl_filesystem.h b/common/include/pcl/common/pcl_filesystem.h new file mode 100644 index 00000000000..06b062be676 --- /dev/null +++ b/common/include/pcl/common/pcl_filesystem.h @@ -0,0 +1,47 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (C) 2024 Kino + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + */ + +#pragma once + +#if (__cplusplus >= 201703L) +#include +namespace pcl_fs = std::filesystem; +#else +#include +namespace pcl_fs = boost::filesystem; +#endif diff --git a/cuda/apps/src/kinect_planes_cuda.cpp b/cuda/apps/src/kinect_planes_cuda.cpp index 9282bf68410..33157b5305e 100644 --- a/cuda/apps/src/kinect_planes_cuda.cpp +++ b/cuda/apps/src/kinect_planes_cuda.cpp @@ -49,6 +49,7 @@ #include #include #include +#include #include #include #include @@ -61,14 +62,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #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 56f19c33d91..562e2edbc27 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 @@ -3,18 +3,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for split, is_any_of inline void 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 56f19c33d91..562e2edbc27 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 @@ -3,18 +3,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for split, is_any_of inline void diff --git a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp index 0ff3dcaca1d..01babb17b4b 100644 --- a/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/build_tree.cpp @@ -1,16 +1,9 @@ #include #include +#include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include diff --git a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp index 5f68e8cafdd..b168d4f43e6 100644 --- a/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp +++ b/doc/tutorials/content/sources/vfh_recognition/nearest_neighbors.cpp @@ -3,6 +3,7 @@ #include #include // for compute3DCentroid #include +#include #include #include #include @@ -11,14 +12,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for replace_last typedef std::pair > vfh_model; diff --git a/doc/tutorials/content/vfh_recognition.rst b/doc/tutorials/content/vfh_recognition.rst index 24692b089c2..095fe6ec69f 100644 --- a/doc/tutorials/content/vfh_recognition.rst +++ b/doc/tutorials/content/vfh_recognition.rst @@ -110,21 +110,21 @@ Once all VFH features have been loaded, we convert them to FLANN format, using: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 121-126 + :lines: 114-119 Since we're lazy, and we want to use this data (and not reload it again by crawling the directory structure in the testing phase), we dump the data to disk: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 128-134 + :lines: 121-127 Finally, we create the KdTree, and save its structure to disk: .. literalinclude:: sources/vfh_recognition/build_tree.cpp :language: cpp - :lines: 137-141 + :lines: 130-134 Here we will use a ``LinearIndex``, which does a brute-force search using a @@ -164,7 +164,7 @@ In lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 141-152 + :lines: 134-145 we load the first given user histogram (and ignore the rest). Then we proceed @@ -177,7 +177,7 @@ In lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 171-172 + :lines: 164-165 we load the training data from disk, together with the list of file names that @@ -185,7 +185,7 @@ we previously stored in ``build_tree.cpp``. Then, we read the kd-tree and rebuil .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 185-186 + :lines: 178-179 Here we need to make sure that we use the **exact** distance metric @@ -194,53 +194,53 @@ the tree. The most important part of the code comes here: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 187 + :lines: 180 Inside ``nearestKSearch``, we first convert the query point to FLANN format: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 84-85 + :lines: 77-78 Followed by obtaining the resultant nearest neighbor indices and distances for the query in: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 86-89 + :lines: 79-82 Lines: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 186-200 + :lines: 179-193 create a ``PCLVisualizer`` object, and sets up a set of different viewports (e.g., splits the screen into different chunks), which will be enabled in: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 220 + :lines: 213 Using the file names representing the models that we previously obtained in ``loadFileList``, we proceed at loading the model file names using: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 228-235 + :lines: 221-228 For visualization purposes, we demean the point cloud by computing its centroid and then subtracting it: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 247-252 + :lines: 240-245 Finally we check if the distance obtained by ``nearestKSearch`` is larger than the user given threshold, and if it is, we display a red line over the cloud that is being rendered in the viewport: .. literalinclude:: sources/vfh_recognition/nearest_neighbors.cpp :language: cpp - :lines: 261-267 + :lines: 254-260 Compiling and running the code diff --git a/gpu/kinfu/tools/kinfu_app.cpp b/gpu/kinfu/tools/kinfu_app.cpp index 7feb67f4dbe..7564e62c88e 100644 --- a/gpu/kinfu/tools/kinfu_app.cpp +++ b/gpu/kinfu/tools/kinfu_app.cpp @@ -41,16 +41,9 @@ #include #include +#include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include diff --git a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h index 520877494ae..7ade37975ce 100644 --- a/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h +++ b/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/screenshot_manager.h @@ -49,16 +49,9 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include +#include #include diff --git a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp index b5f92881919..73c943e3941 100644 --- a/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp +++ b/gpu/kinfu_large_scale/tools/kinfuLS_app.cpp @@ -53,16 +53,9 @@ Work in progress: patch by Marco (AUG,19th 2012) #include #include +#include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include diff --git a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp index a7c58e413d7..8a9f6faae23 100644 --- a/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp +++ b/gpu/kinfu_large_scale/tools/standalone_texture_mapping.cpp @@ -36,18 +36,11 @@ * Author: Raphael Favier, Technical University Eindhoven, (r.mysurname tue.nl) */ -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include #include +#include #include #include #include diff --git a/gpu/people/tools/people_app.cpp b/gpu/people/tools/people_app.cpp index 816188ff13a..109974ab73d 100644 --- a/gpu/people/tools/people_app.cpp +++ b/gpu/people/tools/people_app.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -55,14 +56,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include diff --git a/io/include/pcl/io/impl/auto_io.hpp b/io/include/pcl/io/impl/auto_io.hpp index 748dd0bc408..f8fec231588 100644 --- a/io/include/pcl/io/impl/auto_io.hpp +++ b/io/include/pcl/io/impl/auto_io.hpp @@ -40,19 +40,13 @@ #ifndef PCL_IO_AUTO_IO_IMPL_H_ #define PCL_IO_AUTO_IO_IMPL_H_ +#include + #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path -namespace pcl_fs = std::filesystem; -#else -#include // for path -namespace pcl_fs = boost::filesystem; -#endif - namespace pcl { namespace io diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index 1b52d89a168..b3ae2c7db55 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -36,19 +36,12 @@ */ #include // for getFieldSize +#include #include // pcl::utils::ignore #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for lexical_cast #include // for split #include diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index e436dd6a8c6..2ce2e3dfa47 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -35,6 +35,7 @@ * */ // Looking for PCL_BUILT_WITH_VTK +#include #include #include #include @@ -43,14 +44,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for exists, basename, is_directory, ... -namespace pcl_fs = std::filesystem; -#else -#include // for exists, basename, is_directory, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy #ifdef PCL_BUILT_WITH_VTK diff --git a/io/src/lzf_image_io.cpp b/io/src/lzf_image_io.cpp index e6104748935..5c01cfbd8af 100644 --- a/io/src/lzf_image_io.cpp +++ b/io/src/lzf_image_io.cpp @@ -37,18 +37,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index e77d350fbf6..108481a69bc 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -38,19 +38,11 @@ #include #include #include +#include #include #include #include // for lexical_cast - -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - #include // for trim pcl::MTLReader::MTLReader () diff --git a/io/src/openni2_grabber.cpp b/io/src/openni2_grabber.cpp index 68dce0cf1d3..0cdaa947ff2 100644 --- a/io/src/openni2_grabber.cpp +++ b/io/src/openni2_grabber.cpp @@ -46,19 +46,12 @@ #include #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - using namespace pcl::io::openni2; namespace diff --git a/io/src/openni_grabber.cpp b/io/src/openni_grabber.cpp index 4f577c4a523..1ff5887aadd 100644 --- a/io/src/openni_grabber.cpp +++ b/io/src/openni_grabber.cpp @@ -42,20 +42,13 @@ #include #include #include +#include #include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - using namespace std::chrono_literals; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 0bcd3a40fdf..4a49e1c61f3 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -43,6 +43,7 @@ #include #include // pcl::utils::ignore #include +#include #include #include #include @@ -52,14 +53,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for permissions -namespace pcl_fs = std::filesystem; -#else -#include // for permissions -namespace pcl_fs = boost::filesystem; -#endif - /////////////////////////////////////////////////////////////////////////////////////////// void pcl::PCDWriter::setLockingPermissions (const std::string &file_name, diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 9197eb2f53f..6008c014527 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -37,6 +37,7 @@ #include #include +#include #include #include @@ -46,16 +47,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -// https://www.boost.org/doc/libs/1_70_0/libs/filesystem/doc/index.htm#Coding-guidelines -#define BOOST_FILESYSTEM_NO_DEPRECATED -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for split std::tuple, std::function > diff --git a/test/io/test_grabbers.cpp b/test/io/test_grabbers.cpp index 81e3e4fb670..732c0faf203 100644 --- a/test/io/test_grabbers.cpp +++ b/test/io/test_grabbers.cpp @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -8,14 +9,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for directory_iterator, extension -namespace pcl_fs = std::filesystem; -#else -#include // for directory_iterator, extension -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace std::chrono_literals; diff --git a/tools/converter.cpp b/tools/converter.cpp index 68deafdcd95..89ef59c7677 100644 --- a/tools/converter.cpp +++ b/tools/converter.cpp @@ -46,20 +46,13 @@ #include +#include #include #include #include #include #include // for pcl::make_shared -#if (__cplusplus >= 201703L) -#include // for std::filesystem::path -namespace pcl_fs = std::filesystem; -#else -#include // for boost::filesystem::path -namespace pcl_fs = boost::filesystem; -#endif - #include // for boost::algorithm::ends_with #define ASCII 0 diff --git a/tools/fast_bilateral_filter.cpp b/tools/fast_bilateral_filter.cpp index 3c9a6ca0aa1..09a653fad7f 100644 --- a/tools/fast_bilateral_filter.cpp +++ b/tools/fast_bilateral_filter.cpp @@ -38,18 +38,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/grid_min.cpp b/tools/grid_min.cpp index d3bf263b48b..5563864fdf2 100644 --- a/tools/grid_min.cpp +++ b/tools/grid_min.cpp @@ -40,19 +40,12 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/image_grabber_saver.cpp b/tools/image_grabber_saver.cpp index 34af68249b1..8f89a8765dc 100644 --- a/tools/image_grabber_saver.cpp +++ b/tools/image_grabber_saver.cpp @@ -37,18 +37,11 @@ * */ #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - using pcl::console::print_error; using pcl::console::print_info; using pcl::console::print_value; diff --git a/tools/image_grabber_viewer.cpp b/tools/image_grabber_viewer.cpp index 19b365c3a0e..3622cb4620d 100644 --- a/tools/image_grabber_viewer.cpp +++ b/tools/image_grabber_viewer.cpp @@ -38,6 +38,7 @@ */ #include +#include #include #include #include @@ -46,14 +47,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - using namespace std::chrono_literals; using pcl::console::print_error; using pcl::console::print_info; diff --git a/tools/local_max.cpp b/tools/local_max.cpp index 18806a8d035..d7035d01d0f 100644 --- a/tools/local_max.cpp +++ b/tools/local_max.cpp @@ -40,19 +40,12 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/morph.cpp b/tools/morph.cpp index 0f37f006d59..0cd696d76da 100644 --- a/tools/morph.cpp +++ b/tools/morph.cpp @@ -40,19 +40,12 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/normal_estimation.cpp b/tools/normal_estimation.cpp index 61aae380223..51baec2e8d2 100644 --- a/tools/normal_estimation.cpp +++ b/tools/normal_estimation.cpp @@ -42,18 +42,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/passthrough_filter.cpp b/tools/passthrough_filter.cpp index 7a23172df57..fe31ed1df63 100644 --- a/tools/passthrough_filter.cpp +++ b/tools/passthrough_filter.cpp @@ -38,19 +38,12 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/pcd_grabber_viewer.cpp b/tools/pcd_grabber_viewer.cpp index f68761edb9e..966f055b041 100644 --- a/tools/pcd_grabber_viewer.cpp +++ b/tools/pcd_grabber_viewer.cpp @@ -37,19 +37,12 @@ * */ #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for exists, extension, ... -namespace pcl_fs = std::filesystem; -#else -#include // for exists, extension, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy #include #include diff --git a/tools/progressive_morphological_filter.cpp b/tools/progressive_morphological_filter.cpp index 95fc9327eda..fd6cebca9f2 100644 --- a/tools/progressive_morphological_filter.cpp +++ b/tools/progressive_morphological_filter.cpp @@ -40,6 +40,7 @@ #include #include +#include #include #include #include @@ -47,14 +48,6 @@ #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/radius_filter.cpp b/tools/radius_filter.cpp index 1617ffabefc..163789e425a 100644 --- a/tools/radius_filter.cpp +++ b/tools/radius_filter.cpp @@ -36,22 +36,14 @@ #include #include +#include #include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy - using PointType = pcl::PointXYZ; using Cloud = pcl::PointCloud; using CloudConstPtr = Cloud::ConstPtr; diff --git a/tools/sac_segmentation_plane.cpp b/tools/sac_segmentation_plane.cpp index cc71f5ffaac..6508352da91 100644 --- a/tools/sac_segmentation_plane.cpp +++ b/tools/sac_segmentation_plane.cpp @@ -40,18 +40,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - #include // for to_upper_copy using namespace pcl; diff --git a/tools/tiff2pcd.cpp b/tools/tiff2pcd.cpp index c181068492c..011d26b08e5 100644 --- a/tools/tiff2pcd.cpp +++ b/tools/tiff2pcd.cpp @@ -41,16 +41,9 @@ #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include +#include #include #include #include diff --git a/tools/unary_classifier_segment.cpp b/tools/unary_classifier_segment.cpp index 785dc233227..926d8c7880f 100644 --- a/tools/unary_classifier_segment.cpp +++ b/tools/unary_classifier_segment.cpp @@ -39,6 +39,7 @@ #include +#include #include #include #include @@ -46,14 +47,6 @@ #include -#if (__cplusplus >= 201703L) -#include // for path, exists, ... -namespace pcl_fs = std::filesystem; -#else -#include // for path, exists, ... -namespace pcl_fs = boost::filesystem; -#endif - using namespace pcl; using namespace pcl::io; using namespace pcl::console; diff --git a/tools/uniform_sampling.cpp b/tools/uniform_sampling.cpp index 674971859fa..fef5cfd5105 100644 --- a/tools/uniform_sampling.cpp +++ b/tools/uniform_sampling.cpp @@ -38,18 +38,11 @@ #include #include #include +#include #include #include #include -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include #include diff --git a/tools/virtual_scanner.cpp b/tools/virtual_scanner.cpp index 19a854db861..8d714241c2f 100644 --- a/tools/virtual_scanner.cpp +++ b/tools/virtual_scanner.cpp @@ -53,6 +53,7 @@ #include #include // for pcl::make_shared #include +#include #include #include @@ -65,14 +66,6 @@ #include // for boost::is_any_of, boost::split, boost::token_compress_on, boost::trim -#if (__cplusplus >= 201703L) -#include // for std::filesystem::create_directories, std::filesystem::exists, std::filesystem::path, std::filesystem::path::extension -namespace pcl_fs = std::filesystem; -#else -#include // for boost::filesystem::create_directories, boost::filesystem::exists, boost::filesystem::path, boost::filesystem::path::extension -namespace pcl_fs = boost::filesystem; -#endif - using namespace pcl; #define EPS 0.00001 diff --git a/visualization/src/interactor_style.cpp b/visualization/src/interactor_style.cpp index 91728eb56f8..3d6c23f956b 100644 --- a/visualization/src/interactor_style.cpp +++ b/visualization/src/interactor_style.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -70,14 +71,6 @@ #include // for is_any_of #include // for split -#if (__cplusplus >= 201703L) -#include // for exists -namespace pcl_fs = std::filesystem; -#else -#include // for exists -namespace pcl_fs = boost::filesystem; -#endif - #define ORIENT_MODE 0 #define SELECT_MODE 1 diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index cb3f0151f50..5290114b631 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -93,6 +93,7 @@ #endif #include +#include #include #include @@ -103,14 +104,6 @@ #include #endif -#if (__cplusplus >= 201703L) -#include -namespace pcl_fs = std::filesystem; -#else -#include -namespace pcl_fs = boost::filesystem; -#endif - #include // for split #include // pcl::utils::ignore #include From 3e699e0817b879bcf817b12b41600dd5c84d0bd8 Mon Sep 17 00:00:00 2001 From: cybaol Date: Sun, 4 Feb 2024 09:44:11 +0800 Subject: [PATCH 197/288] Remove unused cmake boost variables --- cmake/pcl_find_boost.cmake | 4 ---- cmake/pcl_pclconfig.cmake | 3 --- 2 files changed, 7 deletions(-) diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index f49e77060c9..f5ba550af0f 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -34,10 +34,6 @@ endif() find_package(Boost 1.65.0 QUIET COMPONENTS ${BOOST_OPTIONAL_MODULES}) find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) -if(Boost_SERIALIZATION_FOUND) - set(BOOST_SERIALIZATION_FOUND TRUE) -endif() - if(Boost_FOUND) set(BOOST_FOUND TRUE) endif() diff --git a/cmake/pcl_pclconfig.cmake b/cmake/pcl_pclconfig.cmake index e5203284a78..f9941b14355 100644 --- a/cmake/pcl_pclconfig.cmake +++ b/cmake/pcl_pclconfig.cmake @@ -92,9 +92,6 @@ endif() if(Boost_SERIALIZATION_FOUND) string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " serialization") endif() -if(Boost_CHRONO_FOUND) - string(APPEND PCLCONFIG_AVAILABLE_BOOST_MODULES " chrono") -endif() configure_file("${PCL_SOURCE_DIR}/PCLConfig.cmake.in" "${PCL_BINARY_DIR}/PCLConfig.cmake" @ONLY) From b881de693ec19b34a549be5078c57f6a3caff196 Mon Sep 17 00:00:00 2001 From: = <=> Date: Mon, 5 Feb 2024 07:51:40 +0100 Subject: [PATCH 198/288] Update system wide include for metslib. --- CMakeLists.txt | 5 ----- recognition/CMakeLists.txt | 7 +++++++ recognition/include/pcl/recognition/hv/hv_go.h | 3 ++- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 8b015bff26f..6e73895551e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -354,12 +354,7 @@ if(PKG_CONFIG_FOUND) pkg_check_modules(METSLIB metslib) if(METSLIB_FOUND) set(HAVE_METSLIB ON) - include_directories(SYSTEM ${METSLIB_INCLUDE_DIRS}) - else() - include_directories(SYSTEM "${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/") endif() -else() - include_directories(SYSTEM ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/) endif() # LibPNG diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 3a8eb9fe19f..5fa40bdc989 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -161,6 +161,13 @@ 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} ${face_detection_incs} ${ransac_based_incs} ${ransac_based_impl_incs} ${hv_incs} ${hv_impl_incs} ${cg_incs} ${cg_impl_incs} ${metslib_incs}) target_link_libraries("${LIB_NAME}" pcl_common pcl_kdtree pcl_octree pcl_search pcl_features pcl_registration pcl_sample_consensus pcl_filters pcl_ml pcl_io) + +if(HAVE_METSLIB) + target_include_directories(${LIB_NAME} SYSTEM PUBLIC ${METSLIB_INCLUDE_DIRS}) +else() + target_include_directories(${LIB_NAME} SYSTEM PUBLIC ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/) +endif() + PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) # Install include files PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) diff --git a/recognition/include/pcl/recognition/hv/hv_go.h b/recognition/include/pcl/recognition/hv/hv_go.h index e4bbf1b9201..3a5e575ec4e 100644 --- a/recognition/include/pcl/recognition/hv/hv_go.h +++ b/recognition/include/pcl/recognition/hv/hv_go.h @@ -19,9 +19,10 @@ #include #include -#include #include +#include // Either include 3.party in pcl/recognition/3rdparty or system installed metslib + #include namespace pcl From 879a07f1a8884afc9b5061ad68cb0b4e03e1c35f Mon Sep 17 00:00:00 2001 From: = <=> Date: Mon, 5 Feb 2024 08:07:52 +0100 Subject: [PATCH 199/288] Update system wide include for PNG. --- CMakeLists.txt | 1 - apps/CMakeLists.txt | 4 ++-- io/CMakeLists.txt | 1 + 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6e73895551e..91c31f629b8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -363,7 +363,6 @@ if(WITH_PNG) find_package(PNG) if(PNG_FOUND) set(HAVE_PNG ON) - include_directories(SYSTEM "${PNG_INCLUDE_DIR}") endif() endif() diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index 670f2d8fac1..219d64c8bf8 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -117,8 +117,8 @@ if(VTK_FOUND) target_link_libraries(pcl_openni_octree_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree) if(HAVE_PNG) - PCL_ADD_EXECUTABLE(pcl_openni_organized_compression COMPONENT ${SUBSYS_NAME} SOURCES src/openni_organized_compression.cpp BUNDLE) - target_link_libraries(pcl_openni_organized_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree) + PCL_ADD_EXECUTABLE(pcl_openni_organized_compression COMPONENT ${SUBSYS_NAME} SOURCES src/openni_organized_compression.cpp BUNDLE) + target_link_libraries(pcl_openni_organized_compression pcl_common pcl_io pcl_filters pcl_visualization pcl_octree) endif() PCL_ADD_EXECUTABLE(pcl_openni_shift_to_depth_conversion COMPONENT ${SUBSYS_NAME} SOURCES src/openni_shift_to_depth_conversion.cpp BUNDLE) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index be9e2f4bb74..1b978a9484b 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -374,6 +374,7 @@ if(VTK_FOUND) endif() if(PNG_FOUND) + target_include_directories("${LIB_NAME}" SYSTEM PRIVATE ${PNG_INCLUDE_DIRS}) target_link_libraries("${LIB_NAME}" ${PNG_LIBRARIES}) endif() From 2fd6558919cf6ab8d117e46a92deebbd47ef9271 Mon Sep 17 00:00:00 2001 From: Johannes Thyssen Tishman Date: Mon, 5 Feb 2024 16:40:24 +0100 Subject: [PATCH 200/288] Rename variables with reserved names MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit From the GNU libc manual[0]: In addition to the names documented in this manual, reserved names include all external identifiers (global functions and variables) that begin with an underscore (‘_’) and all identifiers regardless of use that begin with either two underscores or an underscore followed by a capital letter are reserved names. This is so that the library and header files can define functions, variables, and macros for internal purposes without risk of conflict with names in user programs. [0] https://www.gnu.org/software/libc/manual/html_node/Reserved-Names.html --- common/include/pcl/impl/point_types.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index cb08b4deb25..076385267d6 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -691,8 +691,8 @@ namespace pcl inline constexpr PointXYZLAB() : PointXYZLAB{0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f} {} inline constexpr PointXYZLAB (float _x, float _y, float _z, - float _L, float _a, float _b) : - _PointXYZLAB{ {{_x, _y, _z, 1.0f}}, {{_L, _a, _b}} } {} + float _l, float _a, float _b) : + _PointXYZLAB{ {{_x, _y, _z, 1.0f}}, {{_l, _a, _b}} } {} friend std::ostream& operator << (std::ostream& os, const PointXYZLAB& p); PCL_MAKE_ALIGNED_OPERATOR_NEW From 440cdbca1e36cc332989a7dda24a7646be10efd8 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 8 Feb 2024 14:49:33 +0100 Subject: [PATCH 201/288] Improve documentation in vtk_lib_io --- io/include/pcl/io/vtk_lib_io.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/io/include/pcl/io/vtk_lib_io.h b/io/include/pcl/io/vtk_lib_io.h index a7a42ac95a3..de57bf20063 100644 --- a/io/include/pcl/io/vtk_lib_io.h +++ b/io/include/pcl/io/vtk_lib_io.h @@ -92,6 +92,7 @@ namespace pcl /** \brief Load a \ref PolygonMesh object given an input file name, based on the file extension * \param[in] file_name the name of the file containing the polygon data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int @@ -113,6 +114,7 @@ namespace pcl /** \brief Load a VTK file into a \ref PolygonMesh object * \param[in] file_name the name of the file that contains the data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int @@ -122,6 +124,7 @@ namespace pcl /** \brief Load a PLY file into a \ref PolygonMesh object * \param[in] file_name the name of the file that contains the data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int @@ -131,6 +134,7 @@ namespace pcl /** \brief Load an OBJ file into a \ref PolygonMesh object * \param[in] file_name the name of the file that contains the data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int @@ -143,6 +147,7 @@ namespace pcl * load the material information. * \param[in] file_name the name of the file that contains the data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int @@ -153,6 +158,7 @@ namespace pcl /** \brief Load an STL file into a \ref PolygonMesh object * \param[in] file_name the name of the file that contains the data * \param[out] mesh the object that we want to load the data in + * \return Number of points in the point cloud of the mesh. * \ingroup io */ PCL_EXPORTS int From be65ef79638e02ffb4c38e85222c6015b5af50e1 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 8 Feb 2024 15:51:06 +0100 Subject: [PATCH 202/288] Fix behaviour of eigen33 function if smallest eigenvalue is not unique The documentation of the eigen33 function says: "if the smallest eigenvalue is not unique, this function may return any eigenvector that is consistent to the eigenvalue" Currently however, in that case the returned eigenvector is usually a vector of NaNs. This commit applies the same logic as the other eigen33 function below. The effect on run time is minimal (one subtraction and one comparison). In practice, it is rare that the smallest eigenvalue is not unique but it can happen, for example when normals are estimated with a very small neighbourhood. In the PCL tests, this is the case in the NormalRefinement test in test_filters.cpp --- common/include/pcl/common/impl/eigen.hpp | 19 +++++++++++++++---- 1 file changed, 15 insertions(+), 4 deletions(-) diff --git a/common/include/pcl/common/impl/eigen.hpp b/common/include/pcl/common/impl/eigen.hpp index 031a8ee0b7c..8f628f1d4ea 100644 --- a/common/include/pcl/common/impl/eigen.hpp +++ b/common/include/pcl/common/impl/eigen.hpp @@ -308,10 +308,21 @@ eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenve computeRoots (scaledMat, eigenvalues); eigenvalue = eigenvalues (0) * scale; - - scaledMat.diagonal ().array () -= eigenvalues (0); - - eigenvector = detail::getLargest3x3Eigenvector (scaledMat).vector; + if ( (eigenvalues (1) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) { + // usual case: first and second are not equal (so first and third are also not equal). + // second and third could be equal, but that does not matter here + scaledMat.diagonal ().array () -= eigenvalues (0); + eigenvector = detail::getLargest3x3Eigenvector (scaledMat).vector; + } + else if ( (eigenvalues (2) - eigenvalues (0)) > Eigen::NumTraits < Scalar > ::epsilon ()) { + // first and second equal: choose any unit vector that is orthogonal to third eigenvector + scaledMat.diagonal ().array () -= eigenvalues (2); + eigenvector = detail::getLargest3x3Eigenvector (scaledMat).vector.unitOrthogonal (); + } + else { + // all three equal: just use an arbitrary unit vector + eigenvector << Scalar (1.0), Scalar (0.0), Scalar (0.0); + } } From 5d7143581f894530716b66bafd4e3c8a3686aa18 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 8 Feb 2024 21:36:02 +0100 Subject: [PATCH 203/288] Add special implementation for raw_fallocate for OpenBSD --- io/include/pcl/io/low_level_io.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/io/include/pcl/io/low_level_io.h b/io/include/pcl/io/low_level_io.h index 7cc26fd95c9..5d82ddf4083 100644 --- a/io/include/pcl/io/low_level_io.h +++ b/io/include/pcl/io/low_level_io.h @@ -181,6 +181,12 @@ namespace pcl // All other errors are passed up. if (errno != EINVAL) return -1; +# elif defined(__OpenBSD__) + // OpenBSD has neither posix_fallocate nor fallocate + if (::ftruncate(fd, length) == 0) + return 0; + if (errno != EINVAL) + return -1; # else // Conforming POSIX systems have posix_fallocate. const int res = ::posix_fallocate(fd, 0, length); From 4ab87d43432b5497b715ace7415f799da7be4a77 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 15 Feb 2024 16:41:19 +0100 Subject: [PATCH 204/288] Use common file for boost versions. (#5960) * Use common file for boost versions. * Keep listing the version PCL was build with as the first one. --- PCLConfig.cmake.in | 10 +++------- cmake/Modules/AdditionalBoostVersions.cmake | 6 ++++++ cmake/pcl_find_boost.cmake | 6 +----- 3 files changed, 10 insertions(+), 12 deletions(-) create mode 100644 cmake/Modules/AdditionalBoostVersions.cmake diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index cf21c443742..98f9bcef95c 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -93,13 +93,9 @@ macro(find_boost) elseif(NOT BOOST_INCLUDEDIR) set(BOOST_INCLUDEDIR "@Boost_INCLUDE_DIR@") endif() - - set(Boost_ADDITIONAL_VERSIONS - "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" - "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" - "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" - "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" - "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") + + include(${CMAKE_CURRENT_LIST_DIR}/Modules/AdditionalBoostVersions.cmake) + set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" ${Boost_ADDITIONAL_VERSIONS}) find_package(Boost 1.65.0 ${QUIET_} COMPONENTS @PCLCONFIG_AVAILABLE_BOOST_MODULES@) diff --git a/cmake/Modules/AdditionalBoostVersions.cmake b/cmake/Modules/AdditionalBoostVersions.cmake new file mode 100644 index 00000000000..a4698e0061a --- /dev/null +++ b/cmake/Modules/AdditionalBoostVersions.cmake @@ -0,0 +1,6 @@ + +set(Boost_ADDITIONAL_VERSIONS + "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" + "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" + "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" + "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index f5ba550af0f..f9e0b28d12c 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -13,11 +13,7 @@ else() endif() endif() -set(Boost_ADDITIONAL_VERSIONS - "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" - "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" - "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" - "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") +include(${CMAKE_CURRENT_LIST_DIR}/Modules/AdditionalBoostVersions.cmake) if(CMAKE_CXX_STANDARD MATCHES "14") # Optional boost modules From e5e79726535d27a8952b307d3390a38763561535 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sat, 17 Feb 2024 17:25:23 +0100 Subject: [PATCH 205/288] Additional cmake cleanup (#5952) * Remove more set(build X). * Don't check if "build" var exists, as it doesn't. * 2d doesn't depend on vtk. * People doesn't depend on vtk. * Check if QTX is empty, ie. WITH_QT = NO. * Cleanup apps * Revert "Don't check if "build" var exists, as it doesn't." This reverts commit 79e3bac711846603d55703f740aa07627a7ac355. It does indeed exists. * Rename FALSE to OFF and TRUE to ON. * Unify and clean the 5 apps. Default all to OFF. --- 2d/CMakeLists.txt | 7 +------ apps/3d_rec_framework/CMakeLists.txt | 10 ++-------- apps/CMakeLists.txt | 4 +--- apps/cloud_composer/CMakeLists.txt | 17 +++++++---------- apps/in_hand_scanner/CMakeLists.txt | 10 +++++----- apps/modeler/CMakeLists.txt | 10 +++------- apps/point_cloud_editor/CMakeLists.txt | 7 ++----- benchmarks/CMakeLists.txt | 6 ++---- cuda/common/CMakeLists.txt | 1 - cuda/features/CMakeLists.txt | 1 - cuda/io/CMakeLists.txt | 1 - cuda/sample_consensus/CMakeLists.txt | 1 - cuda/segmentation/CMakeLists.txt | 1 - gpu/containers/CMakeLists.txt | 1 - gpu/features/CMakeLists.txt | 1 - gpu/octree/CMakeLists.txt | 1 - gpu/people/CMakeLists.txt | 1 - gpu/segmentation/CMakeLists.txt | 1 - gpu/surface/CMakeLists.txt | 1 - gpu/tracking/CMakeLists.txt | 1 - gpu/utils/CMakeLists.txt | 1 - people/CMakeLists.txt | 5 +---- recognition/CMakeLists.txt | 4 ++-- stereo/CMakeLists.txt | 1 - surface/CMakeLists.txt | 1 - test/2d/CMakeLists.txt | 8 ++------ test/CMakeLists.txt | 5 +---- test/common/CMakeLists.txt | 4 +--- test/features/CMakeLists.txt | 4 +--- test/filters/CMakeLists.txt | 4 +--- test/geometry/CMakeLists.txt | 4 +--- test/gpu/octree/CMakeLists.txt | 5 +---- test/io/CMakeLists.txt | 4 +--- test/kdtree/CMakeLists.txt | 4 +--- test/keypoints/CMakeLists.txt | 4 +--- test/ml/CMakeLists.txt | 4 +--- test/octree/CMakeLists.txt | 4 +--- test/outofcore/CMakeLists.txt | 4 +--- test/people/CMakeLists.txt | 4 +--- test/recognition/CMakeLists.txt | 4 +--- test/registration/CMakeLists.txt | 4 +--- test/sample_consensus/CMakeLists.txt | 4 +--- test/search/CMakeLists.txt | 4 +--- test/segmentation/CMakeLists.txt | 4 +--- test/surface/CMakeLists.txt | 4 +--- test/visualization/CMakeLists.txt | 4 +--- visualization/CMakeLists.txt | 2 +- 47 files changed, 49 insertions(+), 138 deletions(-) diff --git a/2d/CMakeLists.txt b/2d/CMakeLists.txt index e97d4adbb7a..e706ca4e7a6 100644 --- a/2d/CMakeLists.txt +++ b/2d/CMakeLists.txt @@ -2,9 +2,8 @@ set(SUBSYS_NAME 2d) set(SUBSYS_DESC "Point cloud 2d") set(SUBSYS_DEPS common filters) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS vtk) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_ADD_DOC("${SUBSYS_NAME}") @@ -30,10 +29,6 @@ set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/morphology.hpp" ) -if(${VTK_FOUND}) - set(VTK_IO_TARGET_LINK_LIBRARIES vtkCommon vtkWidgets vtkIO vtkImaging) -endif() - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") set(LIB_NAME "pcl_${SUBSYS_NAME}") diff --git a/apps/3d_rec_framework/CMakeLists.txt b/apps/3d_rec_framework/CMakeLists.txt index 504628de7e6..57015b61634 100644 --- a/apps/3d_rec_framework/CMakeLists.txt +++ b/apps/3d_rec_framework/CMakeLists.txt @@ -2,17 +2,11 @@ set(SUBSUBSYS_NAME 3d_rec_framework) set(SUBSUBSYS_DESC "3D recognition framework") set(SUBSUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search recognition ml) set(SUBSUBSYS_EXT_DEPS vtk openni) +set(REASON "") +set(DEFAULT OFF) if(NOT TARGET Boost::filesystem) - set(DEFAULT FALSE) set(REASON "Boost filesystem is not available.") -else() - set(DEFAULT TRUE) -endif() - -# Default to not building for now -if(${DEFAULT} STREQUAL "TRUE") - set(DEFAULT FALSE) endif() PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index 219d64c8bf8..b501bac85c5 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Application examples/samples that show how PCL works") set(SUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search recognition ml stereo 2d) set(SUBSYS_OPT_DEPS openni vtk ${QTX}) -set(DEFAULT FALSE) -set(REASON "Disabled by default") -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${SUBSYS_OPT_DEPS}) if(NOT build) diff --git a/apps/cloud_composer/CMakeLists.txt b/apps/cloud_composer/CMakeLists.txt index 24196bcc274..3e2629fa1c8 100644 --- a/apps/cloud_composer/CMakeLists.txt +++ b/apps/cloud_composer/CMakeLists.txt @@ -7,19 +7,16 @@ set(SUBSUBSYS_NAME cloud_composer) set(SUBSUBSYS_DESC "Cloud Composer - Application for Manipulating Point Clouds") set(SUBSUBSYS_DEPS common io visualization filters apps) set(SUBSUBSYS_EXT_DEPS vtk ${QTX}) +set(REASON "") +set(DEFAULT OFF) -# QVTK? -if(NOT HAVE_QVTK) - set(DEFAULT AUTO_OFF) - set(REASON "Cloud composer requires QVTK") -elseif(NOT ${DEFAULT} STREQUAL "AUTO_OFF") - set(DEFAULT TRUE) - set(REASON) +# Have Qt? +if("${QTX}" STREQUAL "") + set(REASON "Cloud composer requires Qt.") endif() -#Default to not building for now -if("${DEFAULT}" STREQUAL "TRUE") - set(DEFAULT FALSE) +if(NOT HAVE_QVTK) + set(REASON "VTK was not built with Qt support.") endif() PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/apps/in_hand_scanner/CMakeLists.txt b/apps/in_hand_scanner/CMakeLists.txt index 5c3350ff43b..97e2c72ee11 100644 --- a/apps/in_hand_scanner/CMakeLists.txt +++ b/apps/in_hand_scanner/CMakeLists.txt @@ -3,12 +3,12 @@ set(SUBSUBSYS_DESC "In-hand scanner for small objects") set(SUBSUBSYS_DEPS common features io kdtree apps) set(SUBSUBSYS_LIBS pcl_common pcl_features pcl_io pcl_kdtree) set(SUBSUBSYS_EXT_DEPS ${QTX} OpenGL OpenGL_GLU openni) +set(REASON "") +set(DEFAULT OFF) -################################################################################ - -# Default to not building for now -if(${DEFAULT} STREQUAL "TRUE") - set(DEFAULT FALSE) +# Have Qt? +if("${QTX}" STREQUAL "") + set(REASON "Cloud composer requires Qt.") endif() pcl_subsubsys_option(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/apps/modeler/CMakeLists.txt b/apps/modeler/CMakeLists.txt index 7c621248279..c48442c2f1c 100644 --- a/apps/modeler/CMakeLists.txt +++ b/apps/modeler/CMakeLists.txt @@ -3,19 +3,15 @@ set(SUBSUBSYS_DESC "PCLModeler: PCL based reconstruction platform") set(SUBSUBSYS_DEPS common geometry io filters sample_consensus segmentation visualization kdtree features surface octree registration keypoints tracking search apps) set(SUBSUBSYS_EXT_DEPS vtk ${QTX}) set(REASON "") +set(DEFAULT OFF) # QVTK? if(NOT HAVE_QVTK) - set(DEFAULT AUTO_OFF) set(REASON "VTK was not built with Qt support.") -elseif(NOT ${DEFAULT} STREQUAL "AUTO_OFF") - set(DEFAULT TRUE) - set(REASON) endif() -# Default to not building for now -if(${DEFAULT} STREQUAL "TRUE") - set(DEFAULT FALSE) +if(NOT HAVE_QVTK) + set(REASON "VTK was not built with Qt support.") endif() PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/apps/point_cloud_editor/CMakeLists.txt b/apps/point_cloud_editor/CMakeLists.txt index 7374b72e0d7..07f92057728 100644 --- a/apps/point_cloud_editor/CMakeLists.txt +++ b/apps/point_cloud_editor/CMakeLists.txt @@ -2,11 +2,8 @@ set(SUBSUBSYS_NAME point_cloud_editor) set(SUBSUBSYS_DESC "Point Cloud Editor - Simple editor for 3D point clouds") set(SUBSUBSYS_DEPS common filters io apps) set(SUBSUBSYS_EXT_DEPS vtk ${QTX} OpenGL) - -# Default to not building for now -if(${DEFAULT} STREQUAL "TRUE") - set(DEFAULT FALSE) -endif() +set(REASON "") +set(DEFAULT OFF) PCL_SUBSUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSUBSYS_NAME}" "${SUBSUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSUBSYS_NAME} PARENT_NAME ${SUBSYS_NAME} DEPS ${SUBSUBSYS_DEPS} EXT_DEPS ${SUBSUBSYS_EXT_DEPS}) diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt index 95f421db5f6..c73a786c28a 100644 --- a/benchmarks/CMakeLists.txt +++ b/benchmarks/CMakeLists.txt @@ -1,10 +1,8 @@ set(SUBSYS_NAME benchmarks) set(SUBSYS_DESC "Point cloud library benchmarks") set(SUBSYS_DEPS common filters features search kdtree io) -set(DEFAULT OFF) -set(build TRUE) -set(REASON "Disabled by default") -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") + +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) if(NOT build) return() diff --git a/cuda/common/CMakeLists.txt b/cuda/common/CMakeLists.txt index 2c4c119afa0..164c3a8ef13 100644 --- a/cuda/common/CMakeLists.txt +++ b/cuda/common/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH cuda/common) set(SUBSYS_DESC "Point cloud CUDA common library") set(SUBSYS_DEPS) -set(build TRUE) PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ON) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/cuda/features/CMakeLists.txt b/cuda/features/CMakeLists.txt index 7d271029708..a40975d2a99 100644 --- a/cuda/features/CMakeLists.txt +++ b/cuda/features/CMakeLists.txt @@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common) # ---[ Point Cloud Library - pcl/cuda/io -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/cuda/io/CMakeLists.txt b/cuda/io/CMakeLists.txt index fcf78689437..5ddfc90b1b4 100644 --- a/cuda/io/CMakeLists.txt +++ b/cuda/io/CMakeLists.txt @@ -6,7 +6,6 @@ set(SUBSYS_EXT_DEPS openni) # ---[ Point Cloud Library - pcl/cuda/io -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${SUBSYS_EXT_DEPS}) diff --git a/cuda/sample_consensus/CMakeLists.txt b/cuda/sample_consensus/CMakeLists.txt index 42cdc30c875..537c10efae2 100644 --- a/cuda/sample_consensus/CMakeLists.txt +++ b/cuda/sample_consensus/CMakeLists.txt @@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common) # ---[ Point Cloud Library - pcl/cuda/io -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/cuda/segmentation/CMakeLists.txt b/cuda/segmentation/CMakeLists.txt index 38a17aa490f..ce73fb8260f 100644 --- a/cuda/segmentation/CMakeLists.txt +++ b/cuda/segmentation/CMakeLists.txt @@ -5,7 +5,6 @@ set(SUBSYS_DEPS cuda_common io common) # ---[ Point Cloud Library - pcl/cuda/io -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/gpu/containers/CMakeLists.txt b/gpu/containers/CMakeLists.txt index f25120bafc0..f81db10a309 100644 --- a/gpu/containers/CMakeLists.txt +++ b/gpu/containers/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/containers) set(SUBSYS_DESC "Containers with reference counting for GPU memory. This module can be compiled without Cuda Toolkit.") set(SUBSYS_DEPS common) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/gpu/features/CMakeLists.txt b/gpu/features/CMakeLists.txt index 2d2954fe7fa..ebc1a6cd829 100644 --- a/gpu/features/CMakeLists.txt +++ b/gpu/features/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/features) set(SUBSYS_DESC "Temporary GPU_common module. Weak CUDA dependency: a code that use this module requires CUDA Toolkit installed, but should be compiled without nvcc") set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree geometry) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/gpu/octree/CMakeLists.txt b/gpu/octree/CMakeLists.txt index 8477bb75ea3..ddc043276bb 100644 --- a/gpu/octree/CMakeLists.txt +++ b/gpu/octree/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/octree) set(SUBSYS_DESC "Octree GPU") set(SUBSYS_DEPS common gpu_containers gpu_utils) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) mark_as_advanced("BUILD_${SUBSYS_NAME}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/gpu/people/CMakeLists.txt b/gpu/people/CMakeLists.txt index a3404263569..95c495c975d 100644 --- a/gpu/people/CMakeLists.txt +++ b/gpu/people/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/people) set(SUBSYS_DESC "Point cloud people library") set(SUBSYS_DEPS common features filters geometry gpu_containers gpu_utils io kdtree octree search segmentation surface visualization) -set(build FALSE) PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) mark_as_advanced("BUILD_${SUBSYS_NAME}") diff --git a/gpu/segmentation/CMakeLists.txt b/gpu/segmentation/CMakeLists.txt index 0c1838ec94b..42cb57850cc 100644 --- a/gpu/segmentation/CMakeLists.txt +++ b/gpu/segmentation/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/segmentation) set(SUBSYS_DESC "Point cloud GPU segmentation library") 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 NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/gpu/surface/CMakeLists.txt b/gpu/surface/CMakeLists.txt index 6970f0e8cc6..64eea2ae17e 100644 --- a/gpu/surface/CMakeLists.txt +++ b/gpu/surface/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/surface) set(SUBSYS_DESC "Surface algorithms with GPU") set(SUBSYS_DEPS common gpu_containers gpu_utils geometry) -set(build FALSE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/gpu/tracking/CMakeLists.txt b/gpu/tracking/CMakeLists.txt index e464a9e8e26..3b8221208dd 100644 --- a/gpu/tracking/CMakeLists.txt +++ b/gpu/tracking/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/tracking) set(SUBSYS_DESC "Tracking with GPU") set(SUBSYS_DEPS common gpu_containers gpu_utils gpu_octree tracking search kdtree filters octree) -set(build FALSE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/gpu/utils/CMakeLists.txt b/gpu/utils/CMakeLists.txt index 8775067ccff..6f0aac6a22a 100644 --- a/gpu/utils/CMakeLists.txt +++ b/gpu/utils/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_PATH gpu/utils) set(SUBSYS_DESC "Device layer functions.") set(SUBSYS_DEPS common gpu_containers) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_SET_SUBSYS_INCLUDE_DIR("${SUBSYS_NAME}" "${SUBSYS_PATH}") diff --git a/people/CMakeLists.txt b/people/CMakeLists.txt index 73780f0a3ee..d49ebf2947e 100644 --- a/people/CMakeLists.txt +++ b/people/CMakeLists.txt @@ -1,10 +1,9 @@ set(SUBSYS_NAME people) set(SUBSYS_DESC "Point cloud people library") set(SUBSYS_DEPS common kdtree search sample_consensus filters io visualization geometry segmentation octree) -set(EXT_DEPS vtk) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS}) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) PCL_ADD_DOC("${SUBSYS_NAME}") @@ -44,8 +43,6 @@ PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_ PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs}) -#SET_TARGET_PROPERTIES("${LIB_NAME}" PROPERTIES LINKER_LANGUAGE CXX) - if(WITH_OPENNI) PCL_ADD_EXECUTABLE(pcl_ground_based_rgbd_people_detector COMPONENT ${SUBSYS_NAME} SOURCES apps/main_ground_based_people_detection.cpp BUNDLE) target_link_libraries(pcl_ground_based_rgbd_people_detector pcl_common pcl_kdtree pcl_search pcl_sample_consensus pcl_filters pcl_io pcl_visualization pcl_segmentation pcl_people) diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 5fa40bdc989..2cda7232be4 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -3,10 +3,10 @@ set(SUBSYS_DESC "Point cloud recognition library") set(SUBSYS_DEPS common io search kdtree octree features filters registration sample_consensus ml) if(${PCL_VERSION} VERSION_LESS "1.15.0" AND NOT TARGET Boost::filesystem) - set(DEFAULT FALSE) + set(DEFAULT OFF) set(REASON "Boost filesystem is not available.") else() - set(DEFAULT TRUE) + set(DEFAULT ON) endif() PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/stereo/CMakeLists.txt b/stereo/CMakeLists.txt index c8973635d95..5d980a327a3 100644 --- a/stereo/CMakeLists.txt +++ b/stereo/CMakeLists.txt @@ -2,7 +2,6 @@ set(SUBSYS_NAME stereo) set(SUBSYS_DESC "Point cloud stereo library") set(SUBSYS_DEPS common io) -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index b86614fe471..4536cbbe1eb 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -3,7 +3,6 @@ set(SUBSYS_DESC "Point cloud surface library") set(SUBSYS_DEPS common search kdtree octree) set(SUBSYS_EXT_DEPS "") -set(build TRUE) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS qhull vtk OpenMP) diff --git a/test/2d/CMakeLists.txt b/test/2d/CMakeLists.txt index 4e74c0f511d..e140984e633 100644 --- a/test/2d/CMakeLists.txt +++ b/test/2d/CMakeLists.txt @@ -2,12 +2,8 @@ set(SUBSYS_NAME tests_2d) set(SUBSYS_DESC "Point cloud library 2d module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS 2d) -set(OPT_DEPS) - -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") -PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) +PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) if(NOT build) return() diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 555b4c7969d..5a489065e58 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -1,10 +1,7 @@ set(SUBSYS_NAME global_tests) set(SUBSYS_DESC "Point cloud library global unit tests") -set(DEFAULT OFF) -set(build TRUE) -set(REASON "Disabled by default") -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" OFF) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/common/CMakeLists.txt b/test/common/CMakeLists.txt index a4ef890c3d5..5851543b3c3 100644 --- a/test/common/CMakeLists.txt +++ b/test/common/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library common module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS common) set(OPT_DEPS io search kdtree octree) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/features/CMakeLists.txt b/test/features/CMakeLists.txt index 4dbab6e8bc2..c686f506f10 100644 --- a/test/features/CMakeLists.txt +++ b/test/features/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library features module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS features) set(OPT_DEPS io keypoints) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/filters/CMakeLists.txt b/test/filters/CMakeLists.txt index 64c87097a10..80fb22c75d7 100644 --- a/test/filters/CMakeLists.txt +++ b/test/filters/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library filters module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS filters) set(OPT_DEPS io features segmentation) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/geometry/CMakeLists.txt b/test/geometry/CMakeLists.txt index 4b9f788c8da..7074ede0c6f 100644 --- a/test/geometry/CMakeLists.txt +++ b/test/geometry/CMakeLists.txt @@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_geometry) set(SUBSYS_DESC "Point cloud library geometry module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS geometry) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/gpu/octree/CMakeLists.txt b/test/gpu/octree/CMakeLists.txt index d351641a035..a2a8f2c354c 100644 --- a/test/gpu/octree/CMakeLists.txt +++ b/test/gpu/octree/CMakeLists.txt @@ -2,10 +2,7 @@ set(SUBSYS_NAME tests_gpu_octree) set(SUBSYS_DESC "Point cloud library gpu octree tests") set(SUBSYS_DEPS common octree gpu_containers gpu_octree gpu_utils) -set(DEFAULT ON) -set(build TRUE) -set(REASON "") -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/io/CMakeLists.txt b/test/io/CMakeLists.txt index 6a57a682662..16546ecb189 100644 --- a/test/io/CMakeLists.txt +++ b/test/io/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library io module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS io) set(OPT_DEPS visualization) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/kdtree/CMakeLists.txt b/test/kdtree/CMakeLists.txt index e88a4a346b5..a597d1938e8 100644 --- a/test/kdtree/CMakeLists.txt +++ b/test/kdtree/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library kdtree module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS kdtree) set(OPT_DEPS io) # io is not a mandatory dependency in kdtree -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT (build AND BUILD_io)) diff --git a/test/keypoints/CMakeLists.txt b/test/keypoints/CMakeLists.txt index a8a3498da48..173bf4473d4 100644 --- a/test/keypoints/CMakeLists.txt +++ b/test/keypoints/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library keypoints module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS keypoints) set(OPT_DEPS io) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT (build AND BUILD_io)) diff --git a/test/ml/CMakeLists.txt b/test/ml/CMakeLists.txt index c345583489e..ada0833f5ef 100644 --- a/test/ml/CMakeLists.txt +++ b/test/ml/CMakeLists.txt @@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_ml) set(SUBSYS_DESC "Point cloud library ml module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS ml) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/octree/CMakeLists.txt b/test/octree/CMakeLists.txt index 7c71c702ba0..b6de3599c3d 100644 --- a/test/octree/CMakeLists.txt +++ b/test/octree/CMakeLists.txt @@ -2,9 +2,7 @@ set(SUBSYS_NAME tests_octree) set(SUBSYS_DESC "Point cloud library octree module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS octree) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/outofcore/CMakeLists.txt b/test/outofcore/CMakeLists.txt index e4b4b449177..7a6cb9323e4 100644 --- a/test/outofcore/CMakeLists.txt +++ b/test/outofcore/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library outofcore module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS outofcore) set(OPT_DEPS) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/people/CMakeLists.txt b/test/people/CMakeLists.txt index 4dc04fe0e87..6c3840df5c0 100644 --- a/test/people/CMakeLists.txt +++ b/test/people/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library people module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS people) set(OPT_DEPS) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/recognition/CMakeLists.txt b/test/recognition/CMakeLists.txt index 06dc86c9503..09a4953da90 100644 --- a/test/recognition/CMakeLists.txt +++ b/test/recognition/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library recognition module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS recognition) set(OPT_DEPS keypoints) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/registration/CMakeLists.txt b/test/registration/CMakeLists.txt index db199f02cbc..2be909db052 100644 --- a/test/registration/CMakeLists.txt +++ b/test/registration/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library registration module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS registration) set(OPT_DEPS io) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/sample_consensus/CMakeLists.txt b/test/sample_consensus/CMakeLists.txt index 7656f9bf4aa..fbf004e4a79 100644 --- a/test/sample_consensus/CMakeLists.txt +++ b/test/sample_consensus/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library sample_consensus module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS sample_consensus) set(OPT_DEPS io) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/search/CMakeLists.txt b/test/search/CMakeLists.txt index be1e13814c4..22f95007838 100644 --- a/test/search/CMakeLists.txt +++ b/test/search/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library search module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS search) set(OPT_DEPS io) -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/segmentation/CMakeLists.txt b/test/segmentation/CMakeLists.txt index 32dca586313..ae83d990e1e 100644 --- a/test/segmentation/CMakeLists.txt +++ b/test/segmentation/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library segmentation module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS segmentation) set(OPT_DEPS) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/test/surface/CMakeLists.txt b/test/surface/CMakeLists.txt index 3abd8c60fbc..7c01b28a663 100644 --- a/test/surface/CMakeLists.txt +++ b/test/surface/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library surface module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS surface) set(OPT_DEPS io features sample_consensus filters) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT (build AND BUILD_io AND BUILD_features)) diff --git a/test/visualization/CMakeLists.txt b/test/visualization/CMakeLists.txt index c02630ecdb2..ae3a0e40159 100644 --- a/test/visualization/CMakeLists.txt +++ b/test/visualization/CMakeLists.txt @@ -3,9 +3,7 @@ set(SUBSYS_DESC "Point cloud library visualization module unit tests") PCL_SET_TEST_DEPENDENCIES(SUBSYS_DEPS visualization) set(OPT_DEPS features) # module does not depend on these -set(DEFAULT ON) -set(build TRUE) -PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") +PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} OPT_DEPS ${OPT_DEPS}) if(NOT build) diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index 586c475e353..a629b4cc897 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -6,8 +6,8 @@ PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS} EXT_DEPS vtk OPT_DEPS openni openni2 ensenso davidSDK dssdk rssdk) if(ANDROID) - set(build FALSE) message("VTK was found, but cannot be compiled for Android. Please use VES instead.") + return() endif() if(OPENGL_FOUND) From ee9fb5c6d816670e13c158d44caa2996a68136bc Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sun, 18 Feb 2024 10:05:18 +0100 Subject: [PATCH 206/288] Add OpenGL_GLU as external dependency. --- apps/point_cloud_editor/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/point_cloud_editor/CMakeLists.txt b/apps/point_cloud_editor/CMakeLists.txt index 07f92057728..814c88eafcf 100644 --- a/apps/point_cloud_editor/CMakeLists.txt +++ b/apps/point_cloud_editor/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSUBSYS_NAME point_cloud_editor) set(SUBSUBSYS_DESC "Point Cloud Editor - Simple editor for 3D point clouds") set(SUBSUBSYS_DEPS common filters io apps) -set(SUBSUBSYS_EXT_DEPS vtk ${QTX} OpenGL) +set(SUBSUBSYS_EXT_DEPS vtk ${QTX} OpenGL OpenGL_GLU) set(REASON "") set(DEFAULT OFF) From 61b2e8e5336d7d8b0e1ae7c1168035faa083310b Mon Sep 17 00:00:00 2001 From: Transporter Date: Sun, 18 Feb 2024 10:38:12 +0100 Subject: [PATCH 207/288] Fix missing include (#5962) --- io/include/pcl/io/ply/ply_parser.h | 1 + 1 file changed, 1 insertion(+) diff --git a/io/include/pcl/io/ply/ply_parser.h b/io/include/pcl/io/ply/ply_parser.h index 3023d566607..244f3719506 100644 --- a/io/include/pcl/io/ply/ply_parser.h +++ b/io/include/pcl/io/ply/ply_parser.h @@ -49,6 +49,7 @@ #include #include #include +#include #include // for lexical_cast #include // for fold #include // for inherit From 24e244ffb9280b5a61e59527363618dcb74b2c17 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 21 Feb 2024 21:02:02 +0100 Subject: [PATCH 208/288] NDT: allow access to target cloud distribution --- registration/include/pcl/registration/ndt.h | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index 7fbb6403b32..773151be9a1 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -220,6 +220,20 @@ class NormalDistributionsTransform return nr_iterations_; } + /** \brief Get access to the `VoxelGridCovariance` generated from target cloud + * containing point means and covariances. Set the input target cloud before calling + * this. Useful for debugging, e.g. + * \code + * pcl::PointCloud visualize_cloud; + * ndt.getTargetCells().getDisplayCloud(visualize_cloud); + * \endcode + */ + inline const TargetGrid& + getTargetCells() const + { + return target_cells_; + } + /** \brief Convert 6 element transformation vector to affine transformation. * \param[in] x transformation vector of the form [x, y, z, roll, pitch, yaw] * \param[out] trans affine transform corresponding to given transformation @@ -292,6 +306,10 @@ class NormalDistributionsTransform target_cells_.setInputCloud(target_); // Initiate voxel structure. target_cells_.filter(true); + PCL_DEBUG("[pcl::%s::init] Computed voxel structure, got %zu voxels with valid " + "normal distributions.\n", + getClassName().c_str(), + target_cells_.getCentroids()->size()); } /** \brief Compute derivatives of likelihood function w.r.t. the From b4afe1b86776fdb12c544eb2989c2f725cd3c0c8 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 24 Feb 2024 17:15:40 +0100 Subject: [PATCH 209/288] Preparation for default hidden visibility on gcc Add PCL_EXPORTS where missing in template instantiations, change order of template instantiations where otherwise the visibility attribute of the parent class would be overwritten by the child class. --- .../src/pipeline/global_nn_classifier.cpp | 19 +++++++++++-------- .../features/moment_of_inertia_estimation.h | 2 +- .../include/pcl/features/rops_estimation.h | 2 +- recognition/src/implicit_shape_model.cpp | 4 ++-- ...imate_progressive_morphological_filter.hpp | 2 +- .../segmentation/impl/crf_segmentation.hpp | 2 +- .../impl/min_cut_segmentation.hpp | 2 +- .../impl/progressive_morphological_filter.hpp | 2 +- .../pcl/segmentation/impl/region_growing.hpp | 2 +- .../segmentation/impl/unary_classifier.hpp | 2 +- segmentation/src/crf_segmentation.cpp | 6 +++--- segmentation/src/region_growing_rgb.cpp | 8 ++++---- tracking/src/coherence.cpp | 4 +++- 13 files changed, 31 insertions(+), 26 deletions(-) diff --git a/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp b/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp index 6a88b8f46ea..edeff123b8d 100644 --- a/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp +++ b/apps/3d_rec_framework/src/pipeline/global_nn_classifier.cpp @@ -9,13 +9,16 @@ #include // Instantiation -template class pcl::rec_3d_framework:: +// GlobalClassifier is the parent class of GlobalNNPipeline. They must be instantiated +// in this order, otherwise visibility attributes of the former are not applied +// correctly. +template class PCL_EXPORTS pcl::rec_3d_framework::GlobalClassifier; + +template class PCL_EXPORTS pcl::rec_3d_framework:: GlobalNNPipeline; -template class pcl::rec_3d_framework::GlobalNNPipeline< - Metrics::HistIntersectionUnionDistance, - pcl::PointXYZ, - pcl::VFHSignature308>; -template class pcl::rec_3d_framework:: +template class PCL_EXPORTS + pcl::rec_3d_framework::GlobalNNPipeline; +template class PCL_EXPORTS pcl::rec_3d_framework:: GlobalNNPipeline; - -template class pcl::rec_3d_framework::GlobalClassifier; diff --git a/features/include/pcl/features/moment_of_inertia_estimation.h b/features/include/pcl/features/moment_of_inertia_estimation.h index 9d96d407157..9fa7669d6db 100644 --- a/features/include/pcl/features/moment_of_inertia_estimation.h +++ b/features/include/pcl/features/moment_of_inertia_estimation.h @@ -352,7 +352,7 @@ namespace pcl }; } -#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class pcl::MomentOfInertiaEstimation; +#define PCL_INSTANTIATE_MomentOfInertiaEstimation(T) template class PCL_EXPORTS pcl::MomentOfInertiaEstimation; #ifdef PCL_NO_PRECOMPILE #include diff --git a/features/include/pcl/features/rops_estimation.h b/features/include/pcl/features/rops_estimation.h index a34e09fc941..b46c504c59e 100644 --- a/features/include/pcl/features/rops_estimation.h +++ b/features/include/pcl/features/rops_estimation.h @@ -227,7 +227,7 @@ namespace pcl }; } -#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class pcl::ROPSEstimation; +#define PCL_INSTANTIATE_ROPSEstimation(InT, OutT) template class PCL_EXPORTS pcl::ROPSEstimation; #ifdef PCL_NO_PRECOMPILE #include diff --git a/recognition/src/implicit_shape_model.cpp b/recognition/src/implicit_shape_model.cpp index ed851c35009..9efa48f4cb8 100644 --- a/recognition/src/implicit_shape_model.cpp +++ b/recognition/src/implicit_shape_model.cpp @@ -43,6 +43,6 @@ #include // Instantiations of specific point types -template class pcl::features::ISMVoteList; +template class PCL_EXPORTS pcl::features::ISMVoteList; -template class pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>; +template class PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>; diff --git a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp index 8a054c54c1d..564d3e9471a 100644 --- a/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/approximate_progressive_morphological_filter.hpp @@ -266,7 +266,7 @@ pcl::ApproximateProgressiveMorphologicalFilter::extract (Indices& ground } -#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class pcl::ApproximateProgressiveMorphologicalFilter; +#define PCL_INSTANTIATE_ApproximateProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ApproximateProgressiveMorphologicalFilter; #endif // PCL_SEGMENTATION_APPROXIMATE_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp index 2c2f9f5bac0..ff061567519 100644 --- a/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/crf_segmentation.hpp @@ -595,6 +595,6 @@ pcl::CrfSegmentation::segmentPoints (pcl::PointCloud } -#define PCL_INSTANTIATE_CrfSegmentation(T) template class pcl::CrfSegmentation; +#define PCL_INSTANTIATE_CrfSegmentation(T) template class PCL_EXPORTS pcl::CrfSegmentation; #endif // PCL_CRF_SEGMENTATION_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp index 0ec614a8e53..64364911886 100644 --- a/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/min_cut_segmentation.hpp @@ -579,6 +579,6 @@ pcl::MinCutSegmentation::getColoredCloud () return (colored_cloud); } -#define PCL_INSTANTIATE_MinCutSegmentation(T) template class pcl::MinCutSegmentation; +#define PCL_INSTANTIATE_MinCutSegmentation(T) template class PCL_EXPORTS pcl::MinCutSegmentation; #endif // PCL_SEGMENTATION_MIN_CUT_SEGMENTATION_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp index 68a3d3cd240..e65aa01bb58 100644 --- a/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp +++ b/segmentation/include/pcl/segmentation/impl/progressive_morphological_filter.hpp @@ -134,7 +134,7 @@ pcl::ProgressiveMorphologicalFilter::extract (Indices& ground) deinitCompute (); } -#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class pcl::ProgressiveMorphologicalFilter; +#define PCL_INSTANTIATE_ProgressiveMorphologicalFilter(T) template class PCL_EXPORTS pcl::ProgressiveMorphologicalFilter; #endif // PCL_SEGMENTATION_PROGRESSIVE_MORPHOLOGICAL_FILTER_HPP_ diff --git a/segmentation/include/pcl/segmentation/impl/region_growing.hpp b/segmentation/include/pcl/segmentation/impl/region_growing.hpp index 0677cfbe17e..efbbe2fb22c 100644 --- a/segmentation/include/pcl/segmentation/impl/region_growing.hpp +++ b/segmentation/include/pcl/segmentation/impl/region_growing.hpp @@ -705,5 +705,5 @@ pcl::RegionGrowing::getColoredCloudRGBA () return (colored_cloud); } -#define PCL_INSTANTIATE_RegionGrowing(T) template class pcl::RegionGrowing; +#define PCL_INSTANTIATE_RegionGrowing(T) template class PCL_EXPORTS pcl::RegionGrowing; diff --git a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp index dc4ef677a38..5b7e6a1ca60 100644 --- a/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp +++ b/segmentation/include/pcl/segmentation/impl/unary_classifier.hpp @@ -420,6 +420,6 @@ pcl::UnaryClassifier::segment (pcl::PointCloud::Ptr & } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -#define PCL_INSTANTIATE_UnaryClassifier(T) template class pcl::UnaryClassifier; +#define PCL_INSTANTIATE_UnaryClassifier(T) template class PCL_EXPORTS pcl::UnaryClassifier; #endif // PCL_UNARY_CLASSIFIER_HPP_ diff --git a/segmentation/src/crf_segmentation.cpp b/segmentation/src/crf_segmentation.cpp index cb06b73b75f..fffdcccb5f6 100644 --- a/segmentation/src/crf_segmentation.cpp +++ b/segmentation/src/crf_segmentation.cpp @@ -43,6 +43,6 @@ #include // Instantiations of specific point types -template class pcl::CrfSegmentation; -template class pcl::CrfSegmentation; -template class pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; +template class PCL_EXPORTS pcl::CrfSegmentation; diff --git a/segmentation/src/region_growing_rgb.cpp b/segmentation/src/region_growing_rgb.cpp index 76b724e1cae..f377ca0e983 100644 --- a/segmentation/src/region_growing_rgb.cpp +++ b/segmentation/src/region_growing_rgb.cpp @@ -43,7 +43,7 @@ #include // Instantiations of specific point types -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; -template class pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; +template class PCL_EXPORTS pcl::RegionGrowingRGB; diff --git a/tracking/src/coherence.cpp b/tracking/src/coherence.cpp index 325e03aee83..f5bcb8061ed 100644 --- a/tracking/src/coherence.cpp +++ b/tracking/src/coherence.cpp @@ -45,13 +45,15 @@ #include // clang-format off -PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(DistanceCoherence, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(HSVColorCoherence, (pcl::PointXYZRGB) (pcl::PointXYZRGBNormal) (pcl::PointXYZRGBA)) PCL_INSTANTIATE(NearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) +// NearestPairPointCloudCoherence is the parent class of ApproxNearestPairPointCloudCoherence. +// They must be instantiated in this order, otherwise visibility attributes of the former are not applied correctly. +PCL_INSTANTIATE(ApproxNearestPairPointCloudCoherence, PCL_XYZ_POINT_TYPES) PCL_INSTANTIATE(NormalCoherence, PCL_NORMAL_POINT_TYPES) // clang-format on #endif // PCL_NO_PRECOMPILE From 99ff2dd563d4c2c9e61fac5de1dd65dca6029f15 Mon Sep 17 00:00:00 2001 From: Minhaj Uddin Ahmad <69266728+minhaj6@users.noreply.github.com> Date: Fri, 1 Mar 2024 09:32:16 -0600 Subject: [PATCH 210/288] updated broken link to FLANN project page (#5973) * updated broken link to FLANN project page * updated kdtree tutorial link --- doc/tutorials/content/walkthrough.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/tutorials/content/walkthrough.rst b/doc/tutorials/content/walkthrough.rst index e8fecd9e642..706be8f7970 100644 --- a/doc/tutorials/content/walkthrough.rst +++ b/doc/tutorials/content/walkthrough.rst @@ -249,7 +249,7 @@ Kd-tree A theoretical primer explaining how Kd-trees work can be found in the `Kd-tree tutorial `_. - The *kdtree* library provides the kd-tree data-structure, using `FLANN `_, that allows for fast `nearest neighbor searches `_. + The *kdtree* library provides the kd-tree data-structure, using `FLANN `_, that allows for fast `nearest neighbor searches `_. A `Kd-tree `_ (k-dimensional tree) is a space-partitioning data structure that stores a set of k-dimensional points in a tree structure that enables efficient range searches and nearest neighbor searches. Nearest neighbor searches are a core operation when working with point cloud data and can be used to find correspondences between groups of points or feature descriptors or to define the local neighborhood around a point or points. @@ -261,7 +261,7 @@ Kd-tree **Documentation:** https://pointclouds.org/documentation/group__kdtree.html -**Tutorials:** http://pointclouds.org/documentation/tutorials/#kdtree-tutorial +**Tutorials:** https://pcl.readthedocs.io/projects/tutorials/en/master/kdtree_search.html **Interacts with:** Common_ From 6c22ff9bf88c537b0ce40518a22a3c8e571ff22a Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 3 Mar 2024 17:09:56 +0100 Subject: [PATCH 211/288] Optimize Eigen block operations According to https://eigen.tuxfamily.org/dox/group__TutorialBlockOperations.html , Eigen should receive as much information as possible at compile time, to generate optimal machine code. This means specifying the block size as a template parameter (if fixed size), using topLeftCorner if block starts at (0, 0) --- .../filesystem_face_detection.cpp | 4 ++-- common/include/pcl/common/impl/centroid.hpp | 8 ++++---- common/include/pcl/common/impl/transforms.hpp | 2 +- .../pcl/people/impl/head_based_subcluster.hpp | 4 ++-- .../include/pcl/people/impl/height_map_2d.hpp | 8 ++++---- .../face_detector_data_provider.cpp | 4 ++-- .../rf_face_detector_trainer.cpp | 4 ++-- .../include/pcl/registration/impl/elch.hpp | 4 ++-- .../include/pcl/registration/impl/gicp.hpp | 8 ++++---- .../include/pcl/registration/impl/ia_fpcs.hpp | 2 +- .../include/pcl/registration/impl/ia_kfpcs.hpp | 6 +++--- .../include/pcl/registration/impl/lum.hpp | 4 ++-- .../impl/transformation_estimation_2D.hpp | 9 +++++---- .../impl/transformation_estimation_3point.hpp | 18 +++++++++--------- .../impl/transformation_estimation_svd.hpp | 9 +++++---- .../transformation_estimation_svd_scale.hpp | 11 ++++++----- .../pcl/registration/warp_point_rigid.h | 4 ++-- .../pcl/registration/warp_point_rigid_3d.h | 4 ++-- .../pcl/registration/warp_point_rigid_6d.h | 2 +- registration/src/gicp6d.cpp | 8 ++------ test/filters/test_filters.cpp | 4 ++-- tools/transform_point_cloud.cpp | 4 ++-- .../pcl/visualization/impl/pcl_visualizer.hpp | 4 ++-- visualization/src/interactor_style.cpp | 2 +- visualization/src/pcl_visualizer.cpp | 4 ++-- 25 files changed, 70 insertions(+), 71 deletions(-) diff --git a/apps/src/face_detection/filesystem_face_detection.cpp b/apps/src/face_detection/filesystem_face_detection.cpp index f69b8f94f73..a13a49c752f 100644 --- a/apps/src/face_detection/filesystem_face_detection.cpp +++ b/apps/src/face_detection/filesystem_face_detection.cpp @@ -98,7 +98,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf, bool result = face_detection_apps_utils::readMatrixFromFile(pose_file, pose_mat); if (result) { - Eigen::Vector3f ea = pose_mat.block<3, 3>(0, 0).eulerAngles(0, 1, 2); + Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3>().eulerAngles(0, 1, 2); Eigen::Vector3f trans_vector = Eigen::Vector3f(pose_mat(0, 3), pose_mat(1, 3), pose_mat(2, 3)); std::cout << ea << std::endl; @@ -127,7 +127,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf, Eigen::AngleAxisf(ea[1], Eigen::Vector3f::UnitY()) * Eigen::AngleAxisf(ea[2], Eigen::Vector3f::UnitZ()); - // matrixxx = pose_mat.block<3,3>(0,0); + // matrixxx = pose_mat.topLeftCorner<3,3>(); vec = matrixxx * vec; cylinder_coeff.values[3] = vec[0]; diff --git a/common/include/pcl/common/impl/centroid.hpp b/common/include/pcl/common/impl/centroid.hpp index 30697e79e3a..bc0885be58f 100644 --- a/common/include/pcl/common/impl/centroid.hpp +++ b/common/include/pcl/common/impl/centroid.hpp @@ -695,8 +695,8 @@ computeCentroidAndOBB (const pcl::PointCloud &cloud, //[R^t , -R^t*Centroid ] //[0 , 1 ] Eigen::Matrix transform = Eigen::Matrix::Identity(); - transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose(); - transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid; + transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose(); + transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid; //when Scalar==double on a Windows 10 machine and MSVS: //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse @@ -829,8 +829,8 @@ computeCentroidAndOBB (const pcl::PointCloud &cloud, //[R^t , -R^t*Centroid ] //[0 , 1 ] Eigen::Matrix transform = Eigen::Matrix::Identity(); - transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose(); - transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid; + transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose(); + transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid; //when Scalar==double on a Windows 10 machine and MSVS: //if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse diff --git a/common/include/pcl/common/impl/transforms.hpp b/common/include/pcl/common/impl/transforms.hpp index 6c884d16c08..c255161b51e 100644 --- a/common/include/pcl/common/impl/transforms.hpp +++ b/common/include/pcl/common/impl/transforms.hpp @@ -507,7 +507,7 @@ getPrincipalTransformation (const pcl::PointCloud &cloud, double rel1 = eigen_vals.coeff (0) / eigen_vals.coeff (1); double rel2 = eigen_vals.coeff (1) / eigen_vals.coeff (2); - transform.translation () = centroid.head (3); + transform.translation () = centroid.template head<3> (); transform.linear () = eigen_vects; return (std::min (rel1, rel2)); diff --git a/people/include/pcl/people/impl/head_based_subcluster.hpp b/people/include/pcl/people/impl/head_based_subcluster.hpp index 7c9866fcf27..950f56854de 100644 --- a/people/include/pcl/people/impl/head_based_subcluster.hpp +++ b/people/include/pcl/people/impl/head_based_subcluster.hpp @@ -136,7 +136,7 @@ pcl::people::HeadBasedSubclustering::mergeClustersCloseInFloorCoordinate { float min_distance_between_cluster_centers = 0.4; // meters float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed) - Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed) + Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>(); // ground plane normal (precomputed for speed) std::vector > connected_clusters; connected_clusters.resize(input_clusters.size()); std::vector used_clusters; // 0 in correspondence of clusters remained to process, 1 for already used clusters @@ -196,7 +196,7 @@ pcl::people::HeadBasedSubclustering::createSubClusters (pcl::people::Per { // create new clusters from the current cluster and put corresponding indices into sub_clusters_indices: float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed) - Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed) + Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>(); // ground plane normal (precomputed for speed) Eigen::Matrix3Xf maxima_projected(3,maxima_number); // matrix containing the projection of maxima onto the ground plane Eigen::VectorXi subclusters_number_of_points(maxima_number); // subclusters number of points std::vector sub_clusters_indices; // vector of vectors with the cluster indices for every maximum diff --git a/people/include/pcl/people/impl/height_map_2d.hpp b/people/include/pcl/people/impl/height_map_2d.hpp index e8640ebd768..df93b822c60 100644 --- a/people/include/pcl/people/impl/height_map_2d.hpp +++ b/people/include/pcl/people/impl/height_map_2d.hpp @@ -213,16 +213,16 @@ pcl::people::HeightMap2D::filterMaxima () PointT* p_current = &(*cloud_)[maxima_cloud_indices_[i]]; // pointcloud point referring to the current maximum Eigen::Vector3f p_current_eigen(p_current->x, p_current->y, p_current->z); // conversion to eigen - float t = p_current_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground - p_current_eigen -= ground_coeffs_.head(3) * t; // projection of the point on the groundplane + float t = p_current_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground + p_current_eigen -= ground_coeffs_.head<3>() * t; // projection of the point on the groundplane int j = i-1; while ((j >= 0) && (good_maximum)) { PointT* p_previous = &(*cloud_)[maxima_cloud_indices_[j]]; // pointcloud point referring to an already validated maximum Eigen::Vector3f p_previous_eigen(p_previous->x, p_previous->y, p_previous->z); // conversion to eigen - float t = p_previous_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground - p_previous_eigen -= ground_coeffs_.head(3) * t; // projection of the point on the groundplane + float t = p_previous_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground + p_previous_eigen -= ground_coeffs_.head<3>() * t; // projection of the point on the groundplane // distance of the projection of the points on the groundplane: float distance = (p_current_eigen-p_previous_eigen).norm(); diff --git a/recognition/src/face_detection/face_detector_data_provider.cpp b/recognition/src/face_detection/face_detector_data_provider.cpp index 558c7f10773..f2b7ab62520 100644 --- a/recognition/src/face_detection/face_detector_data_provider.cpp +++ b/recognition/src/face_detection/face_detector_data_provider.cpp @@ -93,7 +93,7 @@ void pcl::face_detection::FaceDetectorDataProvider (0, 0).eulerAngles (0, 1, 2); + Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2); ea *= 57.2957795f; //transform it to degrees to do the binning int y = static_cast(pcl_round ((ea[0] + static_cast(std::abs (min_yaw))) / res_yaw)); int p = static_cast(pcl_round ((ea[1] + static_cast(std::abs (min_pitch))) / res_pitch)); @@ -354,7 +354,7 @@ void pcl::face_detection::FaceDetectorDataProvider (0, 0).eulerAngles (0, 1, 2); + Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2); Eigen::Vector3f trans_vector = Eigen::Vector3f (pose_mat (0, 3), pose_mat (1, 3), pose_mat (2, 3)); pcl::PointXYZ center_point; diff --git a/recognition/src/face_detection/rf_face_detector_trainer.cpp b/recognition/src/face_detection/rf_face_detector_trainer.cpp index e4a447b4d81..327c132c47a 100644 --- a/recognition/src/face_detection/rf_face_detector_trainer.cpp +++ b/recognition/src/face_detection/rf_face_detector_trainer.cpp @@ -479,7 +479,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces() Eigen::Matrix4f guess; guess.setIdentity (); - guess.block<3, 3> (0, 0) = matrixxx; + guess.topLeftCorner<3, 3> () = matrixxx; guess (0, 3) = head_clusters_centers_[i][0]; guess (1, 3) = head_clusters_centers_[i][1]; guess (2, 3) = head_clusters_centers_[i][2]; @@ -519,7 +519,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces() head_clusters_centers_[i][1] = icp_trans (1, 3); head_clusters_centers_[i][2] = icp_trans (2, 3); - Eigen::Vector3f ea = icp_trans.block<3, 3> (0, 0).eulerAngles (0, 1, 2); + Eigen::Vector3f ea = icp_trans.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2); head_clusters_rotation_[i][0] = ea[0]; head_clusters_rotation_[i][1] = ea[1]; head_clusters_rotation_[i][2] = ea[2]; diff --git a/registration/include/pcl/registration/impl/elch.hpp b/registration/include/pcl/registration/impl/elch.hpp index 647386cf880..b1dc7535c53 100644 --- a/registration/include/pcl/registration/impl/elch.hpp +++ b/registration/include/pcl/registration/impl/elch.hpp @@ -192,7 +192,7 @@ pcl::registration::ELCH::initCompute() PointCloudPtr tmp(new PointCloud); // Eigen::Vector4f diff = pose_start - pose_end; - // Eigen::Translation3f translation (diff.head (3)); + // Eigen::Translation3f translation (diff.head<3> ()); // Eigen::Affine3f trans = translation * Eigen::Quaternionf::Identity (); // pcl::transformPointCloud (*(*loop_graph_)[loop_end_].cloud, *tmp, trans); @@ -240,7 +240,7 @@ pcl::registration::ELCH::compute() // TODO use pose // Eigen::Vector4f cend; // pcl::compute3DCentroid (*((*loop_graph_)[loop_end_].cloud), cend); - // Eigen::Translation3f tend (cend.head (3)); + // Eigen::Translation3f tend (cend.head<3> ()); // Eigen::Affine3f aend (tend); // Eigen::Affine3f aendI = aend.inverse (); diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index 3e1bcb62ed6..f2101ad3a45 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -635,9 +635,9 @@ GeneralizedIterativeClosestPoint:: p_trans_src[1] - p_tgt[1], p_trans_src[2] - p_tgt[2]); const Eigen::Matrix3d& M = gicp_->mahalanobis(src_idx); - const Eigen::Vector3d Md(M * d); // Md = M*d - gradient.head<3>() += Md; // translation gradient - hessian.block<3, 3>(0, 0) += M; // translation-translation hessian + const Eigen::Vector3d Md(M * d); // Md = M*d + gradient.head<3>() += Md; // translation gradient + hessian.topLeftCorner<3, 3>() += M; // translation-translation hessian p_trans_src = base_transformation_float * p_src; const Eigen::Vector3d p_base_src(p_trans_src[0], p_trans_src[1], p_trans_src[2]); dCost_dR_T.noalias() += p_base_src * Md.transpose(); @@ -657,7 +657,7 @@ GeneralizedIterativeClosestPoint:: gradient.head<3>() *= 2.0 / m; // translation gradient dCost_dR_T *= 2.0 / m; gicp_->computeRDerivative(x, dCost_dR_T, gradient); // rotation gradient - hessian.block<3, 3>(0, 0) *= 2.0 / m; // translation-translation hessian + hessian.topLeftCorner<3, 3>() *= 2.0 / m; // translation-translation hessian // translation-rotation hessian dCost_dR_T1.row(0) = dCost_dR_T1b.col(0); dCost_dR_T1.row(1) = dCost_dR_T2b.col(0); diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index 4521bb0c0d2..b3445f22d64 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -350,7 +350,7 @@ pcl::registration::FPCSInitialAlignmentgetVector3fMap() - centre_pt.head(3)).squaredNorm(); + float d4 = (pt4->getVector3fMap() - centre_pt.head<3>()).squaredNorm(); // check distance between points w.r.t minimum sampling distance; EDITED -> 4th // point now also limited by max base line diff --git a/registration/include/pcl/registration/impl/ia_kfpcs.hpp b/registration/include/pcl/registration/impl/ia_kfpcs.hpp index 68237fb7059..b42ae57e32f 100644 --- a/registration/include/pcl/registration/impl/ia_kfpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_kfpcs.hpp @@ -166,7 +166,7 @@ KFPCSInitialAlignment:: // translation score (solutions with small translation are down-voted) float scale = 1.f; if (use_trl_score_) { - float trl = transformation.rightCols<1>().head(3).norm(); + float trl = transformation.rightCols<1>().head<3>().norm(); float trl_ratio = (trl - lower_trl_boundary_) / (upper_trl_boundary_ - lower_trl_boundary_); @@ -244,7 +244,7 @@ KFPCSInitialAlignment::getNBestCandid for (const auto& c2 : candidates) { Eigen::Matrix4f diff = candidate.transformation.colPivHouseholderQr().solve(c2.transformation); - const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle(); + const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle(); const float translation3d = diff.block<3, 1>(0, 3).norm(); unique = angle3d > min_angle3d && translation3d > min_translation3d; if (!unique) { @@ -281,7 +281,7 @@ KFPCSInitialAlignment::getTBestCandid for (const auto& c2 : candidates) { Eigen::Matrix4f diff = candidate.transformation.colPivHouseholderQr().solve(c2.transformation); - const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle(); + const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle(); const float translation3d = diff.block<3, 1>(0, 3).norm(); unique = angle3d > min_angle3d && translation3d > min_translation3d; if (!unique) { diff --git a/registration/include/pcl/registration/impl/lum.hpp b/registration/include/pcl/registration/impl/lum.hpp index faa1d6f575d..534c4951684 100644 --- a/registration/include/pcl/registration/impl/lum.hpp +++ b/registration/include/pcl/registration/impl/lum.hpp @@ -254,8 +254,8 @@ LUM::compute() // Fill in elements of G and B if (vj > 0) - G.block(6 * (vi - 1), 6 * (vj - 1), 6, 6) = -(*slam_graph_)[e].cinv_; - G.block(6 * (vi - 1), 6 * (vi - 1), 6, 6) += (*slam_graph_)[e].cinv_; + G.block<6, 6>(6 * (vi - 1), 6 * (vj - 1)) = -(*slam_graph_)[e].cinv_; + G.block<6, 6>(6 * (vi - 1), 6 * (vi - 1)) += (*slam_graph_)[e].cinv_; B.segment(6 * (vi - 1), 6) += (present1 ? 1 : -1) * (*slam_graph_)[e].cinvd_; } } diff --git a/registration/include/pcl/registration/impl/transformation_estimation_2D.hpp b/registration/include/pcl/registration/impl/transformation_estimation_2D.hpp index c2aae92c166..1140880b547 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_2D.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_2D.hpp @@ -166,7 +166,7 @@ TransformationEstimation2D:: // Assemble the correlation matrix H = source * target' Eigen::Matrix H = - (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3); + (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>(); float angle = std::atan2((H(0, 1) - H(1, 0)), (H(0, 0) + H(1, 1))); @@ -176,9 +176,10 @@ TransformationEstimation2D:: R(1, 0) = std::sin(angle); // Return the correct transformation - transformation_matrix.topLeftCorner(3, 3).matrix() = R; - const Eigen::Matrix Rc(R * centroid_src.head(3).matrix()); - transformation_matrix.block(0, 3, 3, 1).matrix() = centroid_tgt.head(3) - Rc; + transformation_matrix.template topLeftCorner<3, 3>().matrix() = R; + const Eigen::Matrix Rc(R * centroid_src.template head<3>().matrix()); + transformation_matrix.template block<3, 1>(0, 3).matrix() = + centroid_tgt.template head<3>() - Rc; } } // namespace registration diff --git a/registration/include/pcl/registration/impl/transformation_estimation_3point.hpp b/registration/include/pcl/registration/impl/transformation_estimation_3point.hpp index cceac5530db..c4cf1671aee 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_3point.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_3point.hpp @@ -155,11 +155,11 @@ pcl::registration::TransformationEstimation3Point s1 = - source_demean.col(1).head(3) - source_demean.col(0).head(3); + source_demean.col(1).template head<3>() - source_demean.col(0).template head<3>(); s1.normalize(); Eigen::Matrix s2 = - source_demean.col(2).head(3) - source_demean.col(0).head(3); + source_demean.col(2).template head<3>() - source_demean.col(0).template head<3>(); s2 -= s2.dot(s1) * s1; s2.normalize(); @@ -169,11 +169,11 @@ pcl::registration::TransformationEstimation3Point t1 = - target_demean.col(1).head(3) - target_demean.col(0).head(3); + target_demean.col(1).template head<3>() - target_demean.col(0).template head<3>(); t1.normalize(); Eigen::Matrix t2 = - target_demean.col(2).head(3) - target_demean.col(0).head(3); + target_demean.col(2).template head<3>() - target_demean.col(0).template head<3>(); t2 -= t2.dot(t1) * t1; t2.normalize(); @@ -184,11 +184,11 @@ pcl::registration::TransformationEstimation3Point R = source_rot * target_rot.transpose (); Eigen::Matrix R = target_rot * source_rot.transpose(); - transformation_matrix.topLeftCorner(3, 3) = R; - // transformation_matrix.block (0, 3, 3, 1) = source_mean.head (3) - R * - // target_mean.head (3); - transformation_matrix.block(0, 3, 3, 1) = - target_mean.head(3) - R * source_mean.head(3); + transformation_matrix.template topLeftCorner<3, 3>() = R; + // transformation_matrix.block<3, 1>(0, 3) = source_mean.head<3>() - R * + // target_mean.head<3>(); + transformation_matrix.template block<3, 1>(0, 3) = + target_mean.template head<3>() - R * source_mean.template head<3>(); } //#define PCL_INSTANTIATE_TransformationEstimation3Point(T,U) template class PCL_EXPORTS diff --git a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp index 6e62bd92f4f..8ebb59b5770 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp @@ -194,7 +194,7 @@ TransformationEstimationSVD:: // Assemble the correlation matrix H = source * target' Eigen::Matrix H = - (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3); + (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>(); // Compute the Singular Value Decomposition Eigen::JacobiSVD> svd( @@ -211,9 +211,10 @@ TransformationEstimationSVD:: Eigen::Matrix R = v * u.transpose(); // Return the correct transformation - transformation_matrix.topLeftCorner(3, 3) = R; - const Eigen::Matrix Rc(R * centroid_src.head(3)); - transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc; + transformation_matrix.template topLeftCorner<3, 3>() = R; + const Eigen::Matrix Rc(R * centroid_src.template head<3>()); + transformation_matrix.template block<3, 1>(0, 3) = + centroid_tgt.template head<3>() - Rc; if (pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG)) { size_t N = cloud_src_demean.cols(); diff --git a/registration/include/pcl/registration/impl/transformation_estimation_svd_scale.hpp b/registration/include/pcl/registration/impl/transformation_estimation_svd_scale.hpp index 51a5b2174f7..9b2035af77e 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_svd_scale.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_svd_scale.hpp @@ -58,7 +58,7 @@ TransformationEstimationSVDScale:: // Assemble the correlation matrix H = source * target' Eigen::Matrix H = - (cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3); + (cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>(); // Compute the Singular Value Decomposition Eigen::JacobiSVD> svd( @@ -76,7 +76,7 @@ TransformationEstimationSVDScale:: // rotated cloud Eigen::Matrix R4; - R4.block(0, 0, 3, 3) = R; + R4.template topLeftCorner<3, 3>() = R; R4(0, 3) = 0; R4(1, 3) = 0; R4(2, 3) = 0; @@ -96,9 +96,10 @@ TransformationEstimationSVDScale:: } float scale = sum_tt / sum_ss; - transformation_matrix.topLeftCorner(3, 3) = scale * R; - const Eigen::Matrix Rc(scale * R * centroid_src.head(3)); - transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc; + transformation_matrix.template topLeftCorner<3, 3>() = scale * R; + const Eigen::Matrix Rc(scale * R * centroid_src.template head<3>()); + transformation_matrix.template block<3, 1>(0, 3) = + centroid_tgt.template head<3>() - Rc; } } // namespace registration diff --git a/registration/include/pcl/registration/warp_point_rigid.h b/registration/include/pcl/registration/warp_point_rigid.h index 2aa6dec1603..228ea9c9092 100644 --- a/registration/include/pcl/registration/warp_point_rigid.h +++ b/registration/include/pcl/registration/warp_point_rigid.h @@ -95,9 +95,9 @@ class WarpPointRigid { pnt_out.z = static_cast( transform_matrix_(2, 0) * pnt_in.x + transform_matrix_(2, 1) * pnt_in.y + transform_matrix_(2, 2) * pnt_in.z + transform_matrix_(2, 3)); - // pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner (3, 3) * + // pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner<3, 3> () * // pnt_in.getVector3fMap () + - // transform_matrix_.block (0, 3, 3, 1); + // transform_matrix_.block<3, 1> (0, 3); // pnt_out.data[3] = pnt_in.data[3]; } diff --git a/registration/include/pcl/registration/warp_point_rigid_3d.h b/registration/include/pcl/registration/warp_point_rigid_3d.h index 459681ccae2..03f2cae9188 100644 --- a/registration/include/pcl/registration/warp_point_rigid_3d.h +++ b/registration/include/pcl/registration/warp_point_rigid_3d.h @@ -82,11 +82,11 @@ class WarpPointRigid3D : public WarpPointRigid(p[0], p[1], 0, 1.0); + trans.template block<4, 1>(0, 3) = Eigen::Matrix(p[0], p[1], 0, 1.0); // Compute w from the unit quaternion Eigen::Rotation2D r(p[2]); - trans.topLeftCorner(2, 2) = r.toRotationMatrix(); + trans.template topLeftCorner<2, 2>() = r.toRotationMatrix(); } }; } // namespace registration diff --git a/registration/include/pcl/registration/warp_point_rigid_6d.h b/registration/include/pcl/registration/warp_point_rigid_6d.h index 30b07d7c216..ec1302acf1a 100644 --- a/registration/include/pcl/registration/warp_point_rigid_6d.h +++ b/registration/include/pcl/registration/warp_point_rigid_6d.h @@ -89,7 +89,7 @@ class WarpPointRigid6D : public WarpPointRigid q(0, p[3], p[4], p[5]); q.w() = static_cast(std::sqrt(1 - q.dot(q))); q.normalize(); - transform_matrix_.topLeftCorner(3, 3) = q.toRotationMatrix(); + transform_matrix_.template topLeftCorner<3, 3>() = q.toRotationMatrix(); } }; } // namespace registration diff --git a/registration/src/gicp6d.cpp b/registration/src/gicp6d.cpp index c06bc2c2664..513c4ef796f 100644 --- a/registration/src/gicp6d.cpp +++ b/registration/src/gicp6d.cpp @@ -225,12 +225,8 @@ GeneralizedIterativeClosestPoint6D::computeTransformation(PointCloudSource& outp PCL_DEBUG("[pcl::%s::computeTransformation] Convergence failed\n", getClassName().c_str()); } - // for some reason the static equivalent method raises an error - // final_transformation_.block<3,3> (0,0) = (transformation_.block<3,3> (0,0)) * - // (guess.block<3,3> (0,0)); final_transformation_.block <3, 1> (0, 3) = - // transformation_.block <3, 1> (0, 3) + guess.rightCols<1>.block <3, 1> (0, 3); - final_transformation_.topLeftCorner(3, 3) = - previous_transformation_.topLeftCorner(3, 3) * guess.topLeftCorner(3, 3); + final_transformation_.topLeftCorner<3, 3>() = + previous_transformation_.topLeftCorner<3, 3>() * guess.topLeftCorner<3, 3>(); final_transformation_(0, 3) = previous_transformation_(0, 3) + guess(0, 3); final_transformation_(1, 3) = previous_transformation_(1, 3) + guess(1, 3); final_transformation_(2, 3) = previous_transformation_(2, 3) + guess(2, 3); diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index aa5f0408651..15e678ab062 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -1998,11 +1998,11 @@ TEST (FrustumCulling, Filters) Eigen::AngleAxisf (0 * M_PI / 180, Eigen::Vector3f::UnitY ()) * Eigen::AngleAxisf (0 * M_PI / 180, Eigen::Vector3f::UnitZ ()); - camera_pose.block (0, 0, 3, 3) = R; + camera_pose.topLeftCorner<3, 3> () = R; Eigen::Vector3f T; T (0) = -5; T (1) = 0; T (2) = 0; - camera_pose.block (0, 3, 3, 1) = T; + camera_pose.block<3, 1> (0, 3) = T; camera_pose (3, 3) = 1; fc.setCameraPose (camera_pose); diff --git a/tools/transform_point_cloud.cpp b/tools/transform_point_cloud.cpp index e7dcfd6b7ae..9b7c51f5896 100644 --- a/tools/transform_point_cloud.cpp +++ b/tools/transform_point_cloud.cpp @@ -295,7 +295,7 @@ main (int argc, char** argv) const float& y = values[1]; const float& z = values[2]; const float& w = values[3]; - tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::Quaternionf (w, x, y, z)); + tform.topLeftCorner<3, 3> () = Eigen::Matrix3f (Eigen::Quaternionf (w, x, y, z)); } else { @@ -312,7 +312,7 @@ main (int argc, char** argv) const float& ay = values[1]; const float& az = values[2]; const float& theta = values[3]; - tform.topLeftCorner (3, 3) = Eigen::Matrix3f (Eigen::AngleAxisf (theta, Eigen::Vector3f (ax, ay, az))); + tform.topLeftCorner<3, 3> () = Eigen::Matrix3f (Eigen::AngleAxisf (theta, Eigen::Vector3f (ax, ay, az))); } else { diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index 0f746cabb83..6c0f42a5f54 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -1249,10 +1249,10 @@ pcl::visualization::PCLVisualizer::addCorrespondences ( Eigen::Affine3f source_transformation; source_transformation.linear () = source_points->sensor_orientation_.matrix (); - source_transformation.translation () = source_points->sensor_origin_.head (3); + source_transformation.translation () = source_points->sensor_origin_.template head<3> (); Eigen::Affine3f target_transformation; target_transformation.linear () = target_points->sensor_orientation_.matrix (); - target_transformation.translation () = target_points->sensor_origin_.head (3); + target_transformation.translation () = target_points->sensor_origin_.template head<3> (); int j = 0; // Draw lines between the best corresponding points diff --git a/visualization/src/interactor_style.cpp b/visualization/src/interactor_style.cpp index 3d6c23f956b..3d1a89c1437 100644 --- a/visualization/src/interactor_style.cpp +++ b/visualization/src/interactor_style.cpp @@ -225,7 +225,7 @@ pcl::visualization::PCLVisualizerInteractorStyle::setCameraParameters (const Eig Eigen::Vector3f pos_vec = extrinsics.block<3, 1> (0, 3); // Rotate the view vector - Eigen::Matrix3f rotation = extrinsics.block<3, 3> (0, 0); + Eigen::Matrix3f rotation = extrinsics.topLeftCorner<3, 3> (); Eigen::Vector3f y_axis (0.f, 1.f, 0.f); Eigen::Vector3f up_vec (rotation * y_axis); diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 5290114b631..fe1b15fabc1 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -4162,8 +4162,8 @@ pcl::visualization::PCLVisualizer::getTransformationMatrix ( Eigen::Matrix4f &transformation) { transformation.setIdentity (); - transformation.block<3, 3> (0, 0) = orientation.toRotationMatrix (); - transformation.block<3, 1> (0, 3) = origin.head (3); + transformation.topLeftCorner<3, 3> () = orientation.toRotationMatrix (); + transformation.block<3, 1> (0, 3) = origin.head<3> (); } ////////////////////////////////////////////////////////////////////////////////////////////// From 1bf96dc1f5a42af4cc828ba9752e29623c5c33a5 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 5 Mar 2024 07:32:33 +0100 Subject: [PATCH 212/288] Cmake cuda find_package cuda is deprecated. (#5953) * find_package cuda is deprecated. CMAKE_CUDA_COMPILED was added to cmake 3.11. * Disable gpu_people if cuda >=12.0 * If cmake is newer than 3.17 use the CUDAToolkit package instead of CUDA. * Use the default and reason variables. * Search for CUDA quietly in find_packages calls. Print message if not found --------- Co-authored-by: = <=> --- cmake/pcl_find_cuda.cmake | 27 ++++++++++++++++++++++++--- gpu/people/CMakeLists.txt | 36 +++++++++++++++++++++++------------- 2 files changed, 47 insertions(+), 16 deletions(-) diff --git a/cmake/pcl_find_cuda.cmake b/cmake/pcl_find_cuda.cmake index 21aeac2e1dc..26b6d908d5d 100644 --- a/cmake/pcl_find_cuda.cmake +++ b/cmake/pcl_find_cuda.cmake @@ -4,13 +4,32 @@ if(MSVC) set(CUDA_ATTACH_VS_BUILD_RULE_TO_CUDA_FILE OFF CACHE BOOL "CUDA_ATTACH_VS_BUILD_RULE_TO_CUDA_FILE") endif() -set(CUDA_FIND_QUIETLY TRUE) -find_package(CUDA 9.0) +if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.11) + include(CheckLanguage) + check_language(CUDA) + if(CMAKE_CUDA_COMPILER) + enable_language(CUDA) + + if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.17) + find_package(CUDAToolkit QUIET) + else() + set(CUDA_FIND_QUIETLY TRUE) + find_package(CUDA 9.0) + endif() + + set(CUDA_FOUND TRUE) + set(CUDA_VERSION_STRING ${CMAKE_CUDA_COMPILER_VERSION}) + else() + message(STATUS "No CUDA compiler found") + endif() +else() + set(CUDA_FIND_QUIETLY TRUE) + find_package(CUDA 9.0) +endif() if(CUDA_FOUND) message(STATUS "Found CUDA Toolkit v${CUDA_VERSION_STRING}") - enable_language(CUDA) set(HAVE_CUDA TRUE) if (CMAKE_CUDA_COMPILER_ID STREQUAL "NVIDIA") @@ -60,4 +79,6 @@ if(CUDA_FOUND) target_include_directories(pcl_cuda INTERFACE ${CUDA_TOOLKIT_INCLUDE}) endif () +else() + message(STATUS "CUDA was not found.") endif() diff --git a/gpu/people/CMakeLists.txt b/gpu/people/CMakeLists.txt index 95c495c975d..ebcb5fd875b 100644 --- a/gpu/people/CMakeLists.txt +++ b/gpu/people/CMakeLists.txt @@ -3,7 +3,14 @@ set(SUBSYS_PATH gpu/people) set(SUBSYS_DESC "Point cloud people library") set(SUBSYS_DEPS common features filters geometry gpu_containers gpu_utils io kdtree octree search segmentation surface visualization) -PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} OFF) +if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0") + set(DEFAULT FALSE) + set(REASON "gpu_people uses textures which was removed in CUDA 12") +else() + set(DEFAULT TRUE) +endif() + +PCL_SUBSYS_OPTION(build ${SUBSYS_NAME} ${SUBSYS_DESC} ${DEFAULT} ${REASON}) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) mark_as_advanced("BUILD_${SUBSYS_NAME}") @@ -13,19 +20,22 @@ if(NOT build) return() endif() -#find NPP -unset(CUDA_npp_LIBRARY CACHE) -find_cuda_helper_libs(nppc) -find_cuda_helper_libs(npps) -if(CUDA_VERSION VERSION_GREATER "9.0" OR CUDA_VERSION VERSION_EQUAL "9.0") - find_cuda_helper_libs(nppim) - find_cuda_helper_libs(nppidei) - set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppim_LIBRARY} ${CUDA_nppidei_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library") +if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.17) + set(CUDA_npp_LIBRARY CUDA::nppc CUDA::nppim CUDA::nppidei CUDA::npps CACHE STRING "npp library") else() - find_cuda_helper_libs(nppi) - set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppi_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library") + #find NPP + unset(CUDA_npp_LIBRARY CACHE) + find_cuda_helper_libs(nppc) + find_cuda_helper_libs(npps) + if(CUDA_VERSION VERSION_GREATER_EQUAL "9.0") + find_cuda_helper_libs(nppim) + find_cuda_helper_libs(nppidei) + set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppim_LIBRARY} ${CUDA_nppidei_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library") + else() + find_cuda_helper_libs(nppi) + set(CUDA_npp_LIBRARY ${CUDA_nppc_LIBRARY} ${CUDA_nppi_LIBRARY} ${CUDA_npps_LIBRARY} CACHE STRING "npp library") + endif() endif() - #Label_skeleton file(GLOB srcs src/*.cpp src/*.h*) @@ -46,7 +56,7 @@ include_directories( set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${hdrs} ${srcs_cuda}) -target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers "${CUDA_CUDART_LIBRARY}" ${CUDA_npp_LIBRARY}) +target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers ${CUDA_CUDART_LIBRARY} ${CUDA_npp_LIBRARY}) if(UNIX OR APPLE) target_compile_options(${LIB_NAME} INTERFACE $<$:"-Xcompiler=-fPIC">) From d39bfc3b0dc5fdf0fd8dd190aa06c855e11f6796 Mon Sep 17 00:00:00 2001 From: Norm Evangelista Date: Tue, 5 Mar 2024 01:16:25 -0800 Subject: [PATCH 213/288] Add bugprone-macro-parentheses clang-tidy check (#5967) * Added bugprone-macro-parentheses check to .clang-tidy * Added exceptions to bugprone-macro-parentheses * Addressed CI issues, review comments * Addressed clang-tidy issue for untracked(?) file * Addressed pcl_config.h issue properly * Fixed another clang-tidy complaint * Rebased, reverted mistaken commit * Exempted uncooperative macro from check --- .clang-tidy | 2 ++ common/include/pcl/console/print.h | 2 ++ common/include/pcl/exceptions.h | 2 ++ common/include/pcl/pcl_macros.h | 10 +++++----- features/include/pcl/features/esf.h | 2 +- .../pcl/filters/impl/conditional_removal.hpp | 4 ++-- io/src/ascii_io.cpp | 2 +- io/src/lzf.cpp | 2 +- io/src/pcd_io.cpp | 14 +++++++------- ml/include/pcl/ml/svm_wrapper.h | 1 + ml/src/svm.cpp | 2 ++ pcl_config.h.in | 2 +- .../surface/3rdparty/poisson4/poisson_exceptions.h | 2 ++ tools/oni_viewer_simple.cpp | 2 +- tools/openni2_viewer.cpp | 2 +- tools/openni_image.cpp | 8 ++++---- tools/openni_pcd_recorder.cpp | 2 +- tools/openni_save_image.cpp | 2 +- tools/openni_viewer.cpp | 2 +- tools/openni_viewer_simple.cpp | 2 +- tools/transform_point_cloud.cpp | 2 +- 21 files changed, 40 insertions(+), 29 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index b4a145f8353..ba61a35b958 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -1,6 +1,8 @@ --- Checks: > -*, + bugprone-copy-constructor-init, + bugprone-macro-parentheses, cppcoreguidelines-pro-type-cstyle-cast, cppcoreguidelines-pro-type-static-cast-downcast, google-readability-casting, diff --git a/common/include/pcl/console/print.h b/common/include/pcl/console/print.h index 0e84427b1c9..355b5ef28dd 100644 --- a/common/include/pcl/console/print.h +++ b/common/include/pcl/console/print.h @@ -45,7 +45,9 @@ // 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); +// NOLINTBEGIN(bugprone-macro-parentheses) #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); } +// NOLINTEND(bugprone-macro-parentheses) #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) diff --git a/common/include/pcl/exceptions.h b/common/include/pcl/exceptions.h index 3814839c89c..3c1a3d1838c 100644 --- a/common/include/pcl/exceptions.h +++ b/common/include/pcl/exceptions.h @@ -46,12 +46,14 @@ * PCL_THROW_EXCEPTION(IOException, * "encountered an error while opening " << filename << " PCD file"); */ +// NOLINTBEGIN(bugprone-macro-parentheses) #define PCL_THROW_EXCEPTION(ExceptionName, message) \ { \ std::ostringstream s; \ s << message; \ throw ExceptionName(s.str(), __FILE__, BOOST_CURRENT_FUNCTION, __LINE__); \ } +// NOLINTEND(bugprone-macro-parentheses) namespace pcl { diff --git a/common/include/pcl/pcl_macros.h b/common/include/pcl/pcl_macros.h index 608b3ecdfc4..074b11149ed 100644 --- a/common/include/pcl/pcl_macros.h +++ b/common/include/pcl/pcl_macros.h @@ -120,7 +120,7 @@ * \brief A handy way to inform the user of the removal deadline */ #define _PCL_PREPARE_REMOVAL_MESSAGE(Major, Minor, Msg) \ - Msg " (It will be removed in PCL " BOOST_PP_STRINGIZE(Major.Minor) ")" + Msg " (It will be removed in PCL " BOOST_PP_STRINGIZE((Major).Minor) ")" /** * \brief Tests for Minor < PCL_MINOR_VERSION @@ -294,18 +294,18 @@ pcl_round (float number) #endif #define FIXED(s) \ - std::fixed << s << std::resetiosflags(std::ios_base::fixed) + std::fixed << (s) << std::resetiosflags(std::ios_base::fixed) #ifndef ERASE_STRUCT -#define ERASE_STRUCT(var) memset(&var, 0, sizeof(var)) +#define ERASE_STRUCT(var) memset(&(var), 0, sizeof(var)) #endif #ifndef ERASE_ARRAY -#define ERASE_ARRAY(var, size) memset(var, 0, size*sizeof(*var)) +#define ERASE_ARRAY(var, size) memset(var, 0, (size)*sizeof(*(var))) #endif #ifndef SET_ARRAY -#define SET_ARRAY(var, value, size) { for (decltype(size) i = 0; i < size; ++i) var[i]=value; } +#define SET_ARRAY(var, value, size) { for (decltype(size) i = 0; i < (size); ++i) (var)[i]=value; } #endif #ifndef PCL_EXTERN_C diff --git a/features/include/pcl/features/esf.h b/features/include/pcl/features/esf.h index 503d110c4a0..221a9444400 100644 --- a/features/include/pcl/features/esf.h +++ b/features/include/pcl/features/esf.h @@ -42,7 +42,7 @@ #include #define GRIDSIZE 64 -#define GRIDSIZE_H GRIDSIZE/2 +#define GRIDSIZE_H (GRIDSIZE/2) #include namespace pcl diff --git a/filters/include/pcl/filters/impl/conditional_removal.hpp b/filters/include/pcl/filters/impl/conditional_removal.hpp index 99cc9295b58..57baf8e1951 100644 --- a/filters/include/pcl/filters/impl/conditional_removal.hpp +++ b/filters/include/pcl/filters/impl/conditional_removal.hpp @@ -529,8 +529,8 @@ pcl::PointDataAtOffset::compare (const PointT& p, const double& val) case CASE_LABEL: { \ pcl::traits::asType_t pt_val; \ memcpy(&pt_val, pt_data + this->offset_, sizeof(pt_val)); \ - return (pt_val > static_cast>(val)) - \ - (pt_val < static_cast>(val)); \ + return (pt_val > static_cast>(val)) - \ + (pt_val < static_cast>(val)); \ } switch (datatype_) diff --git a/io/src/ascii_io.cpp b/io/src/ascii_io.cpp index b3ae2c7db55..efd6614df2c 100644 --- a/io/src/ascii_io.cpp +++ b/io/src/ascii_io.cpp @@ -198,7 +198,7 @@ pcl::ASCIIReader::parse ( #define ASSIGN_TOKEN(CASE_LABEL) \ case CASE_LABEL: { \ *(reinterpret_cast*>(data_target)) = \ - boost::lexical_cast>(token); \ + boost::lexical_cast>(token); \ return sizeof(pcl::traits::asType_t); \ } switch (field.datatype) diff --git a/io/src/lzf.cpp b/io/src/lzf.cpp index c666f234cd3..2d6443f3947 100644 --- a/io/src/lzf.cpp +++ b/io/src/lzf.cpp @@ -75,7 +75,7 @@ using LZF_STATE = unsigned int[1 << (HLOG)]; // IDX works because it is very similar to a multiplicative hash, e.g. // ((h * 57321 >> (3*8 - HLOG)) & ((1 << (HLOG)) - 1)) -#define IDX(h) ((( h >> (3*8 - HLOG)) - h ) & ((1 << (HLOG)) - 1)) +#define IDX(h) ((( (h) >> (3*8 - HLOG)) - (h) ) & ((1 << (HLOG)) - 1)) /////////////////////////////////////////////////////////////////////////////////////////// // diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 4a49e1c61f3..767f65e7d4b 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -509,7 +509,7 @@ pcl::PCDReader::readBodyASCII (std::istream &fs, pcl::PCLPointCloud2 &cloud, int { #define COPY_STRING(CASE_LABEL) \ case CASE_LABEL: { \ - copyStringValue>( \ + copyStringValue>( \ st.at(total + c), cloud, idx, d, c, is); \ break; \ } @@ -640,11 +640,11 @@ pcl::PCDReader::readBodyBinary (const unsigned char *map, pcl::PCLPointCloud2 &c { for (uindex_t c = 0; c < cloud.fields[d].count; ++c) { -#define SET_CLOUD_DENSE(CASE_LABEL) \ - case CASE_LABEL: { \ - if (!isValueFinite>(cloud, i, point_size, d, c)) \ - cloud.is_dense = false; \ - break; \ +#define SET_CLOUD_DENSE(CASE_LABEL) \ + case CASE_LABEL: { \ + if (!isValueFinite>(cloud, i, point_size, d, c)) \ + cloud.is_dense = false; \ + break; \ } switch (cloud.fields[d].datatype) { @@ -1156,7 +1156,7 @@ pcl::PCDWriter::writeASCII (const std::string &file_name, const pcl::PCLPointClo { #define COPY_VALUE(CASE_LABEL) \ case CASE_LABEL: { \ - copyValueString>( \ + copyValueString>( \ cloud, i, point_size, d, c, stream); \ break; \ } diff --git a/ml/include/pcl/ml/svm_wrapper.h b/ml/include/pcl/ml/svm_wrapper.h index b125b700798..8190cc221b1 100644 --- a/ml/include/pcl/ml/svm_wrapper.h +++ b/ml/include/pcl/ml/svm_wrapper.h @@ -47,6 +47,7 @@ #include // for numeric_limits #include // for string #include +// NOLINTNEXTLINE(bugprone-macro-parentheses) #define Malloc(type, n) static_cast(malloc((n) * sizeof(type))) namespace pcl { diff --git a/ml/src/svm.cpp b/ml/src/svm.cpp index 1a27bf9a99f..59e8dfcf450 100644 --- a/ml/src/svm.cpp +++ b/ml/src/svm.cpp @@ -104,8 +104,10 @@ powi(double base, int times) #define INF HUGE_VAL #define TAU 1e-12 +// NOLINTBEGIN(bugprone-macro-parentheses) #define Malloc(type, n) static_cast(malloc((n) * sizeof(type))) #define Realloc(var, type, n) static_cast(realloc(var, (n) * sizeof(type))) +// NOLINTEND(bugprone-macro-parentheses) static void print_string_stdout(const char* s) diff --git a/pcl_config.h.in b/pcl_config.h.in index 13d04c3fbfc..5f96e2faeaa 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -14,7 +14,7 @@ #define PCL_REVISION_VERSION ${PCL_VERSION_PATCH} #define PCL_DEV_VERSION ${PCL_DEV_VERSION} #define PCL_VERSION_PRETTY "${PCL_VERSION_PRETTY}" -#define PCL_VERSION_CALC(MAJ, MIN, PATCH) (MAJ*100000+MIN*100+PATCH) +#define PCL_VERSION_CALC(MAJ, MIN, PATCH) ((MAJ)*100000+(MIN)*100+(PATCH)) #define PCL_VERSION \ PCL_VERSION_CALC(PCL_MAJOR_VERSION, PCL_MINOR_VERSION, PCL_REVISION_VERSION) #define PCL_VERSION_COMPARE(OP, MAJ, MIN, PATCH) \ diff --git a/surface/include/pcl/surface/3rdparty/poisson4/poisson_exceptions.h b/surface/include/pcl/surface/3rdparty/poisson4/poisson_exceptions.h index 6a861a64ea6..6c012b0856c 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/poisson_exceptions.h +++ b/surface/include/pcl/surface/3rdparty/poisson4/poisson_exceptions.h @@ -48,12 +48,14 @@ * Adapted from PCL_THROW_EXCEPTION. We intentionally do not reuse PCL_THROW_EXCEPTION here * to avoid introducing any dependencies on PCL in this 3rd party module. */ +// NOLINTBEGIN(bugprone-macro-parentheses) #define POISSON_THROW_EXCEPTION(ExceptionName, message) \ { \ std::ostringstream s; \ s << message; \ throw ExceptionName(s.str(), __FILE__, BOOST_CURRENT_FUNCTION, __LINE__); \ } +// NOLINTEND(bugprone-macro-parentheses) namespace pcl { diff --git a/tools/oni_viewer_simple.cpp b/tools/oni_viewer_simple.cpp index fcf331d6f23..c46f168687e 100644 --- a/tools/oni_viewer_simple.cpp +++ b/tools/oni_viewer_simple.cpp @@ -58,7 +58,7 @@ do \ if (pcl::getTime() - last >= 1.0) \ { \ double now = pcl::getTime (); \ - std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ + std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni2_viewer.cpp b/tools/openni2_viewer.cpp index 9df14649ec2..1dcc879e5fd 100644 --- a/tools/openni2_viewer.cpp +++ b/tools/openni2_viewer.cpp @@ -58,7 +58,7 @@ ++count; \ if (now - last >= 1.0) \ { \ - std::cout << "Average framerate ("<< _WHAT_ << "): " << double (count)/double (now - last) << " Hz" << std::endl; \ + std::cout << "Average framerate ("<< (_WHAT_) << "): " << double (count)/double (now - last) << " Hz" << std::endl; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni_image.cpp b/tools/openni_image.cpp index 2cdb269c235..c70c75e1f3b 100644 --- a/tools/openni_image.cpp +++ b/tools/openni_image.cpp @@ -97,7 +97,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << ", number of frames written so far: " << nr_frames_total << "\n"; \ + std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << ", number of frames written so far: " << nr_frames_total << "\n"; \ count = 0; \ last = now; \ } \ @@ -112,7 +112,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \ + std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << "\n"; \ count = 0; \ last = now; \ } \ @@ -128,9 +128,9 @@ do \ if (now - last >= 1.0) \ { \ if (visualize && global_visualize) \ - std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w) / " << buff2.getSize () << " (v)\n"; \ + std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff1).getSize () << " (w) / " << (buff2).getSize () << " (v)\n"; \ else \ - std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff1.getSize () << " (w)\n"; \ + std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff1).getSize () << " (w)\n"; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni_pcd_recorder.cpp b/tools/openni_pcd_recorder.cpp index 0f3bfed73de..91d06fb16a8 100644 --- a/tools/openni_pcd_recorder.cpp +++ b/tools/openni_pcd_recorder.cpp @@ -200,7 +200,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cerr << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz. Queue size: " << buff.getSize () << "\n"; \ + std::cerr << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz. Queue size: " << (buff).getSize () << "\n"; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni_save_image.cpp b/tools/openni_save_image.cpp index 1787c977d3c..0c3dfb10772 100644 --- a/tools/openni_save_image.cpp +++ b/tools/openni_save_image.cpp @@ -64,7 +64,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ + std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni_viewer.cpp b/tools/openni_viewer.cpp index 3b131c8a820..509fa886dee 100644 --- a/tools/openni_viewer.cpp +++ b/tools/openni_viewer.cpp @@ -56,7 +56,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ + std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ count = 0; \ last = now; \ } \ diff --git a/tools/openni_viewer_simple.cpp b/tools/openni_viewer_simple.cpp index 90190279d29..927d8bd6354 100644 --- a/tools/openni_viewer_simple.cpp +++ b/tools/openni_viewer_simple.cpp @@ -66,7 +66,7 @@ do \ ++count; \ if (now - last >= 1.0) \ { \ - std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ + std::cout << "Average framerate("<< (_WHAT_) << "): " << double(count)/double(now - last) << " Hz" << std::endl; \ count = 0; \ last = now; \ } \ diff --git a/tools/transform_point_cloud.cpp b/tools/transform_point_cloud.cpp index e7dcfd6b7ae..77347184221 100644 --- a/tools/transform_point_cloud.cpp +++ b/tools/transform_point_cloud.cpp @@ -225,7 +225,7 @@ scaleInPlace (pcl::PCLPointCloud2 &cloud, double* multiplier) #define MULTIPLY(CASE_LABEL) \ case CASE_LABEL: { \ for (int i = 0; i < 3; ++i) \ - multiply>( \ + multiply>( \ cloud, xyz_offset[i], multiplier[i]); \ break; \ } From aa05e54491a5a0f5ca766823e812fa71fee34191 Mon Sep 17 00:00:00 2001 From: Guillaume Batun <35939648+kaipomauli@users.noreply.github.com> Date: Tue, 5 Mar 2024 05:46:56 -0400 Subject: [PATCH 214/288] Add PLYwriter::writeBinary ostream overload (#5975) * Added PLYWriter::writeBinary() ofstream overload modified existing PLYWriter::writeBinary() to open file and then call new overload for data aggregation added PLYWriter::writeBinary() overload that adds data to referenced ofstream buffer * Correct new PLYWriter::writeBinary() header removed unnecessary class qualifiers * Apply suggestions from code review Improved description of new overload Added default zero value for Eigen::Vector4f$ origin Formatting Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> * Modified PLYWriter::writeBinary to use std::ostream instead of std::ofstream * Changed pclWriter::writeBinary ostream variable name to os --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- io/include/pcl/io/ply_io.h | 14 ++- io/src/ply_io.cpp | 231 ++++++++++++++++++++++--------------- 2 files changed, 148 insertions(+), 97 deletions(-) diff --git a/io/include/pcl/io/ply_io.h b/io/include/pcl/io/ply_io.h index 86e540771ae..dbad3424a3a 100644 --- a/io/include/pcl/io/ply_io.h +++ b/io/include/pcl/io/ply_io.h @@ -591,7 +591,19 @@ namespace pcl const Eigen::Quaternionf &orientation = Eigen::Quaternionf::Identity (), int precision = 8, bool use_camera = true); - + /** \brief Save point cloud data to a std::ostream containing n-D points, in BINARY format + * \param[in] os the output buffer + * \param[in] cloud the point cloud data message + * \param[in] origin the sensor data acquisition origin + * (translation) \param[in] orientation the sensor data acquisition origin + * (rotation) \param[in] use_camera if set to true then PLY file will use element + * camera else element range_grid will be used + */ + int + writeBinary(std::ostream& os, const pcl::PCLPointCloud2& cloud, + const Eigen::Vector4f& origin = Eigen::Vector4f::Zero (), const Eigen::Quaternionf& orientation= Eigen::Quaternionf::Identity (), + bool use_camera=true); + /** \brief Save point cloud data to a PLY file containing n-D points, in BINARY format * \param[in] file_name the output file name * \param[in] cloud the point cloud data message diff --git a/io/src/ply_io.cpp b/io/src/ply_io.cpp index 6008c014527..47b8de6adba 100644 --- a/io/src/ply_io.cpp +++ b/io/src/ply_io.cpp @@ -1196,10 +1196,10 @@ pcl::PLYWriter::writeContentWithRangeGridASCII (int nr_points, //////////////////////////////////////////////////////////////////////////////////////// int -pcl::PLYWriter::writeBinary (const std::string &file_name, - const pcl::PCLPointCloud2 &cloud, - const Eigen::Vector4f &origin, - const Eigen::Quaternionf &orientation, +pcl::PLYWriter::writeBinary (const std::string& file_name, + const pcl::PCLPointCloud2& cloud, + const Eigen::Vector4f& origin, + const Eigen::Quaternionf& orientation, bool use_camera) { if (cloud.data.empty ()) @@ -1209,14 +1209,36 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, } std::ofstream fs; - fs.open (file_name.c_str ()); // Open file + fs.open (file_name.c_str (), + std::ios::out | std::ios::binary | + std::ios::trunc); // Open file in binary mode and erase current contents + // if any if (!fs) { - PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during opening (%s)!\n", file_name.c_str ()); + PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during opening (%s)!\n", + file_name.c_str ()); return (-1); } - unsigned int nr_points = cloud.width * cloud.height; + if (!(writeBinary (fs, cloud, origin, orientation, use_camera) == 0)) + { + fs.close(); + return -1; + } + fs.close(); + return 0; +} + +int +pcl::PLYWriter::writeBinary (std::ostream& os, + const pcl::PCLPointCloud2& cloud, + const Eigen::Vector4f& origin, + const Eigen::Quaternionf& orientation, + bool use_camera) +{ + os.imbue(std::locale::classic()); + + unsigned int nr_points = cloud.width * cloud.height; // Compute the range_grid, if necessary, and then write out the PLY header bool doRangeGrid = !use_camera && cloud.height > 1; @@ -1233,17 +1255,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, // If no x-coordinate field exists, then assume all points are valid if (xfield < 0) { - for (unsigned int i=0; i < nr_points; ++i) + for (unsigned int i = 0; i < nr_points; ++i) rangegrid[i] = i; valid_points = nr_points; } // Otherwise, look at their x-coordinates to determine if points are valid else { - for (std::size_t i=0; i < nr_points; ++i) + for (std::size_t i = 0; i < nr_points; ++i) { - const float& value = cloud.at(i, cloud.fields[xfield].offset); - if (std::isfinite(value)) + const float& value = cloud.at (i, cloud.fields[xfield].offset); + if (std::isfinite (value)) { rangegrid[i] = valid_points; ++valid_points; @@ -1252,21 +1274,11 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, rangegrid[i] = -1; } } - fs << generateHeader (cloud, origin, orientation, true, use_camera, valid_points); + os << generateHeader (cloud, origin, orientation, true, use_camera, valid_points); } else { - fs << generateHeader (cloud, origin, orientation, true, use_camera, nr_points); - } - - // Close the file - fs.close (); - // Open file in binary appendable - std::ofstream fpout (file_name.c_str (), std::ios::app | std::ios::binary); - if (!fpout) - { - PCL_ERROR ("[pcl::PLYWriter::writeBinary] Error during reopening (%s)!\n", file_name.c_str ()); - return (-1); + os << generateHeader (cloud, origin, orientation, true, use_camera, nr_points); } // Iterate through the points @@ -1281,16 +1293,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, { int count = cloud.fields[d].count; if (count == 0) - count = 1; //workaround + count = 1; // workaround if (count > 1) { static unsigned int ucount (count); - fpout.write (reinterpret_cast (&ucount), sizeof (unsigned int)); + os.write (reinterpret_cast (&ucount), sizeof (unsigned int)); } // Ignore invalid padded dimensions that are inherited from binary data if (cloud.fields[d].name == "_") { - total += cloud.fields[d].count; // jump over this many elements in the string token + total += + cloud.fields[d].count; // jump over this many elements in the string token continue; } @@ -1298,70 +1311,93 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, { switch (cloud.fields[d].datatype) { - case pcl::PCLPointField::INT8: - { - fpout.write (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (char)), sizeof (char)); - break; - } - case pcl::PCLPointField::UINT8: - { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned char))), sizeof (unsigned char)); - break; - } - case pcl::PCLPointField::INT16: - { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (short))), sizeof (short)); - break; - } - case pcl::PCLPointField::UINT16: - { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned short))), sizeof (unsigned short)); - break; - } - case pcl::PCLPointField::INT32: + case pcl::PCLPointField::INT8: + { + os.write ( + &cloud.at (i, cloud.fields[d].offset + (total + c) * sizeof (char)), + sizeof (char)); + break; + } + case pcl::PCLPointField::UINT8: + { + os.write ( + reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (unsigned char))), + sizeof (unsigned char)); + break; + } + case pcl::PCLPointField::INT16: + { + os.write (reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (short))), + sizeof (short)); + break; + } + case pcl::PCLPointField::UINT16: + { + os.write ( + reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (unsigned short))), + sizeof (unsigned short)); + break; + } + case pcl::PCLPointField::INT32: + { + os.write (reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (int))), + sizeof (int)); + break; + } + case pcl::PCLPointField::UINT32: + { + if (cloud.fields[d].name.find ("rgba") == std::string::npos) { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (int))), sizeof (int)); - break; + os.write ( + reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (unsigned int))), + sizeof (unsigned int)); } - case pcl::PCLPointField::UINT32: + else { - if (cloud.fields[d].name.find ("rgba") == std::string::npos) - { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (unsigned int))), sizeof (unsigned int)); - } - else - { - const auto& color = cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB)); - fpout.write (reinterpret_cast (&color.r), sizeof (unsigned char)); - fpout.write (reinterpret_cast (&color.g), sizeof (unsigned char)); - fpout.write (reinterpret_cast (&color.b), sizeof (unsigned char)); - fpout.write (reinterpret_cast (&color.a), sizeof (unsigned char)); - } - break; + const auto& color = cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB)); + os.write (reinterpret_cast (&color.r), sizeof (unsigned char)); + os.write (reinterpret_cast (&color.g), sizeof (unsigned char)); + os.write (reinterpret_cast (&color.b), sizeof (unsigned char)); + os.write (reinterpret_cast (&color.a), sizeof (unsigned char)); } - case pcl::PCLPointField::FLOAT32: + break; + } + case pcl::PCLPointField::FLOAT32: + { + if (cloud.fields[d].name.find ("rgb") == std::string::npos) { - if (cloud.fields[d].name.find ("rgb") == std::string::npos) - { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (float))), sizeof (float)); - } - else - { - const auto& color = cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB)); - fpout.write (reinterpret_cast (&color.r), sizeof (unsigned char)); - fpout.write (reinterpret_cast (&color.g), sizeof (unsigned char)); - fpout.write (reinterpret_cast (&color.b), sizeof (unsigned char)); - } - break; + os.write (reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (float))), + sizeof (float)); } - case pcl::PCLPointField::FLOAT64: + else { - fpout.write (reinterpret_cast (&cloud.at(i, cloud.fields[d].offset + (total + c) * sizeof (double))), sizeof (double)); - break; + const auto& color = cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (pcl::RGB)); + os.write (reinterpret_cast (&color.r), sizeof (unsigned char)); + os.write (reinterpret_cast (&color.g), sizeof (unsigned char)); + os.write (reinterpret_cast (&color.b), sizeof (unsigned char)); } - default: - PCL_WARN ("[pcl::PLYWriter::writeBinary] Incorrect field data type specified (%d)!\n", cloud.fields[d].datatype); - break; + break; + } + case pcl::PCLPointField::FLOAT64: + { + os.write (reinterpret_cast (&cloud.at ( + i, cloud.fields[d].offset + (total + c) * sizeof (double))), + sizeof (double)); + break; + } + default: + PCL_WARN ("[pcl::PLYWriter::writeBinary] Incorrect field data type specified " + "(%d)!\n", + cloud.fields[d].datatype); + break; } } } @@ -1374,17 +1410,17 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, for (int i = 0; i < 3; ++i) { if (origin[3] != 0) - t = origin[i]/origin[3]; + t = origin[i] / origin[3]; else t = origin[i]; - fpout.write (reinterpret_cast (&t), sizeof (float)); + os.write (reinterpret_cast (&t), sizeof (float)); } Eigen::Matrix3f R = orientation.toRotationMatrix (); for (int i = 0; i < 3; ++i) for (int j = 0; j < 3; ++j) - { - fpout.write (reinterpret_cast (&R (i, j)),sizeof (float)); - } + { + os.write (reinterpret_cast (&R (i, j)), sizeof (float)); + } ///////////////////////////////////////////////////// // Append those properties directly. // @@ -1402,41 +1438,44 @@ pcl::PLYWriter::writeBinary (const std::string &file_name, const float zerof = 0; for (int i = 0; i < 5; ++i) - fpout.write (reinterpret_cast (&zerof), sizeof (float)); + os.write (reinterpret_cast (&zerof), sizeof (float)); // width and height int width = cloud.width; - fpout.write (reinterpret_cast (&width), sizeof (int)); + os.write (reinterpret_cast (&width), sizeof (int)); int height = cloud.height; - fpout.write (reinterpret_cast (&height), sizeof (int)); + os.write (reinterpret_cast (&height), sizeof (int)); for (int i = 0; i < 2; ++i) - fpout.write (reinterpret_cast (&zerof), sizeof (float)); + os.write (reinterpret_cast (&zerof), sizeof (float)); } else if (doRangeGrid) { // Write out range_grid - for (std::size_t i=0; i < nr_points; ++i) + for (std::size_t i = 0; i < nr_points; ++i) { pcl::io::ply::uint8 listlen; if (rangegrid[i] >= 0) { listlen = 1; - fpout.write (reinterpret_cast (&listlen), sizeof (pcl::io::ply::uint8)); - fpout.write (reinterpret_cast (&rangegrid[i]), sizeof (pcl::io::ply::int32)); + os.write (reinterpret_cast (&listlen), + sizeof (pcl::io::ply::uint8)); + os.write (reinterpret_cast (&rangegrid[i]), + sizeof (pcl::io::ply::int32)); } else { listlen = 0; - fpout.write (reinterpret_cast (&listlen), sizeof (pcl::io::ply::uint8)); + os.write (reinterpret_cast (&listlen), + sizeof (pcl::io::ply::uint8)); } } } // Close file - fpout.close (); + return (0); } From ccc4eee90a7242cf0d3c5e1ddb79716eabe4eb8c Mon Sep 17 00:00:00 2001 From: daizhirui Date: Sat, 9 Mar 2024 06:11:45 -0800 Subject: [PATCH 215/288] fix build with CUDA (#5976) * fix build with CUDA * update cmake/pcl_find_cuda.cmake * fix build with CUDA 12.4 --- cmake/pcl_find_cuda.cmake | 1 + gpu/features/src/centroid.cu | 37 +-- gpu/octree/src/cuda/octree_builder.cu | 117 ++++---- gpu/octree/src/utils/approx_nearest_utils.hpp | 1 + gpu/surface/src/cuda/convex_hull.cu | 270 +++++++++--------- 5 files changed, 215 insertions(+), 211 deletions(-) diff --git a/cmake/pcl_find_cuda.cmake b/cmake/pcl_find_cuda.cmake index 26b6d908d5d..466d033feac 100644 --- a/cmake/pcl_find_cuda.cmake +++ b/cmake/pcl_find_cuda.cmake @@ -12,6 +12,7 @@ if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.11) if(CMAKE_VERSION VERSION_GREATER_EQUAL 3.17) find_package(CUDAToolkit QUIET) + set(CUDA_TOOLKIT_INCLUDE ${CUDAToolkit_INCLUDE_DIRS}) else() set(CUDA_FIND_QUIETLY TRUE) find_package(CUDA 9.0) diff --git a/gpu/features/src/centroid.cu b/gpu/features/src/centroid.cu index 5e73df35d80..8ba0f80eefc 100644 --- a/gpu/features/src/centroid.cu +++ b/gpu/features/src/centroid.cu @@ -36,6 +36,7 @@ #include "internal.hpp" +#include #include #include #include @@ -56,26 +57,26 @@ namespace pcl struct PlusFloat3 { - __device__ __forceinline__ float3 operator()(const float3& e1, const float3& e2) const - { - return make_float3(e1.x + e2.x, e1.y + e2.y, e1.z + e2.z); + __device__ __forceinline__ float3 operator()(const float3& e1, const float3& e2) const + { + return make_float3(e1.x + e2.x, e1.y + e2.y, e1.z + e2.z); } }; - + struct TupleDistCvt { float3 pivot_; TupleDistCvt(const float3& pivot) : pivot_(pivot) {} - __device__ __forceinline__ thrust::tuple operator()(const thrust::tuple& t) const - { - float4 point = t.get<0>(); + __device__ __forceinline__ thrust::tuple operator()(const thrust::tuple& t) const + { + float4 point = thrust::get<0>(t); float dx = pivot_.x - point.x; float dy = pivot_.y - point.y; float dz = pivot_.z - point.z; float dist = sqrt(dx*dx + dy*dy + dz*dz); - return thrust::tuple(dist, t.get<1>()); + return thrust::tuple(dist, thrust::get<1>(t)); } }; @@ -87,7 +88,7 @@ void pcl::device::compute3DCentroid(const DeviceArray& cloud, float3& ce { thrust::device_ptr src_beg((PointT*)cloud.ptr()); thrust::device_ptr src_end = src_beg + cloud.size(); - + centroid = transform_reduce(src_beg, src_beg, PointT2float3(), make_float3(0.f, 0.f, 0.f), PlusFloat3()); centroid *= 1.f/cloud.size(); } @@ -99,13 +100,13 @@ void pcl::device::compute3DCentroid(const DeviceArray& cloud, const Indi compute3DCentroid(cloud, centroid); else { - thrust::device_ptr src_beg((PointT*)cloud.ptr()); + thrust::device_ptr src_beg((PointT*)cloud.ptr()); thrust::device_ptr map_beg((int*)indices.ptr()); thrust::device_ptr map_end = map_beg + indices.size(); centroid = transform_reduce(make_permutation_iterator(src_beg, map_beg), - make_permutation_iterator(src_beg, map_end), + make_permutation_iterator(src_beg, map_end), PointT2float3(), make_float3(0.f, 0.f, 0.f), PlusFloat3()); centroid *= 1.f/indices.size(); @@ -114,7 +115,7 @@ void pcl::device::compute3DCentroid(const DeviceArray& cloud, const Indi template float3 pcl::device::getMaxDistance(const DeviceArray& cloud, const float3& pivot) -{ +{ thrust::device_ptr src_beg((PointT*)cloud.ptr()); thrust::device_ptr src_end = src_beg + cloud.size(); @@ -123,14 +124,14 @@ float3 pcl::device::getMaxDistance(const DeviceArray& cloud, const float thrust::tuple init(0.f, 0); thrust::maximum> op; - + thrust::tuple res = transform_reduce( make_zip_iterator(make_tuple( src_beg, cf )), make_zip_iterator(make_tuple( src_beg, ce )), TupleDistCvt(pivot), init, op); - float4 point = src_beg[res.get<1>()]; + float4 point = src_beg[thrust::get<1>(res)]; return make_float3(point.x, point.y, point.z); } @@ -138,11 +139,11 @@ float3 pcl::device::getMaxDistance(const DeviceArray& cloud, const float template float3 pcl::device::getMaxDistance(const DeviceArray& cloud, const Indices& indices, const float3& pivot) -{ +{ if (indices.empty()) return getMaxDistance(cloud, pivot); - thrust::device_ptr src_beg((PointT*)cloud.ptr()); + thrust::device_ptr src_beg((PointT*)cloud.ptr()); thrust::device_ptr map_beg((int*)indices.ptr()); thrust::device_ptr map_end = map_beg + indices.size(); @@ -151,13 +152,13 @@ float3 pcl::device::getMaxDistance(const DeviceArray& cloud, const Indic thrust::tuple init(0.f, 0); thrust::maximum> op; - + thrust::tuple res = transform_reduce( make_zip_iterator(make_tuple( make_permutation_iterator(src_beg, map_beg), cf )), make_zip_iterator(make_tuple( make_permutation_iterator(src_beg, map_end), ce )), TupleDistCvt(pivot), init, op); - float4 point = src_beg[map_beg[res.get<1>()]]; + float4 point = src_beg[map_beg[thrust::get<1>(res)]]; return make_float3(point.x, point.y, point.z); } diff --git a/gpu/octree/src/cuda/octree_builder.cu b/gpu/octree/src/cuda/octree_builder.cu index 9616143695c..7ca1110e363 100644 --- a/gpu/octree/src/cuda/octree_builder.cu +++ b/gpu/octree/src/cuda/octree_builder.cu @@ -43,6 +43,7 @@ #include "utils/scan_block.hpp" #include "utils/morton.hpp" +#include #include #include #include @@ -51,7 +52,7 @@ using namespace pcl::gpu; -namespace pcl +namespace pcl { namespace device { @@ -64,21 +65,21 @@ namespace pcl result.x = fmin(e1.x, e2.x); result.y = fmin(e1.y, e2.y); result.z = fmin(e1.z, e2.z); - return result; - } + return result; + } }; template struct SelectMaxPoint { - __host__ __device__ __forceinline__ PointType operator()(const PointType& e1, const PointType& e2) const - { + __host__ __device__ __forceinline__ PointType operator()(const PointType& e1, const PointType& e2) const + { PointType result; result.x = fmax(e1.x, e2.x); result.y = fmax(e1.y, e2.y); result.z = fmax(e1.z, e2.z); - return result; - } + return result; + } }; @@ -88,9 +89,9 @@ namespace pcl __device__ __forceinline__ thrust::tuple operator()(const PointType& arg) const { thrust::tuple res; - res.get<0>() = arg.x; - res.get<1>() = arg.y; - res.get<2>() = arg.z; + thrust::get<0>(res) = arg.x; + thrust::get<1>(res) = arg.y; + thrust::get<2>(res) = arg.z; return res; } }; @@ -102,8 +103,8 @@ namespace pcl { const static int max_points_per_leaf = 96; - enum - { + enum + { GRID_SIZE = 1, CTA_SIZE = 1024-32, STRIDE = CTA_SIZE, @@ -116,7 +117,7 @@ namespace pcl __shared__ int tasks_beg; __shared__ int tasks_end; __shared__ int total_new; - __shared__ volatile int offsets[CTA_SIZE]; + __shared__ volatile int offsets[CTA_SIZE]; struct SingleStepBuild { @@ -127,14 +128,14 @@ namespace pcl static __device__ __forceinline__ int divUp(int total, int grain) { return (total + grain - 1) / grain; }; __device__ __forceinline__ int FindCells(int task, int level, int cell_begs[], char cell_code[]) const - { + { int cell_count = 0; int beg = octree.begs[task]; - int end = octree.ends[task]; + int end = octree.ends[task]; if (end - beg < max_points_per_leaf) - { + { //cell_count == 0; } else @@ -142,13 +143,13 @@ namespace pcl int cur_code = Morton::extractLevelCode(codes[beg], level); cell_begs[cell_count] = beg; - cell_code[cell_count] = cur_code; - ++cell_count; + cell_code[cell_count] = cur_code; + ++cell_count; int last_code = Morton::extractLevelCode(codes[end - 1], level); if (last_code == cur_code) { - cell_begs[cell_count] = end; + cell_begs[cell_count] = end; } else { @@ -162,7 +163,7 @@ namespace pcl } int morton_code = Morton::shiftLevelCode(search_code, level); - int pos = lower_bound(codes + beg, codes + end, morton_code, CompareByLevelCode(level)) - codes; + int pos = lower_bound(codes + beg, codes + end, morton_code, CompareByLevelCode(level)) - codes; if (pos == end) { @@ -175,7 +176,7 @@ namespace pcl cell_code[cell_count] = cur_code; ++cell_count; beg = pos; - } + } } } return cell_count; @@ -183,7 +184,7 @@ namespace pcl __device__ __forceinline__ void operator()() const - { + { //32 is a performance penalty step for search static_assert((max_points_per_leaf % 32) == 0, "max_points_per_leaf must be a multiple of 32"); @@ -196,7 +197,7 @@ namespace pcl octree. ends[0] = points_number; octree.parent[0] = -1; - //init shared + //init shared nodes_num = 1; tasks_beg = 0; tasks_end = 1; @@ -211,8 +212,8 @@ namespace pcl __syncthreads(); while (tasks_beg < tasks_end && level < Morton::levels) - { - int task_count = tasks_end - tasks_beg; + { + int task_count = tasks_end - tasks_beg; int iters = divUp(task_count, CTA_SIZE); int task = tasks_beg + threadIdx.x; @@ -220,14 +221,14 @@ namespace pcl //__syncthreads(); // extra?? for(int it = 0; it < iters; ++it, task += STRIDE) - { + { int cell_count = (task < tasks_end) ? FindCells(task, level, cell_begs, cell_code) : 0; - + offsets[threadIdx.x] = cell_count; __syncthreads(); scan_block(offsets); - + //__syncthreads(); //because sync is inside the scan above if (task < tasks_end) @@ -255,24 +256,24 @@ namespace pcl __syncthreads(); if (threadIdx.x == CTA_SIZE - 1) - { + { total_new += cell_count + offsets[threadIdx.x]; nodes_num += cell_count + offsets[threadIdx.x]; - } - __syncthreads(); + } + __syncthreads(); } /* for(int it = 0; it < iters; ++it, task += STRIDE) */ //__syncthreads(); //extra ?? if (threadIdx.x == CTA_SIZE - 1) - { + { tasks_beg = tasks_end; - tasks_end += total_new; + tasks_end += total_new; total_new = 0; } ++level; - __syncthreads(); + __syncthreads(); } if (threadIdx.x == CTA_SIZE - 1) @@ -285,7 +286,7 @@ namespace pcl } void pcl::device::OctreeImpl::build() -{ +{ using namespace pcl::device; host_octree.downloaded = false; @@ -293,7 +294,7 @@ void pcl::device::OctreeImpl::build() //allocatations { - //ScopeTimer timer("new_allocs"); + //ScopeTimer timer("new_allocs"); //+1 codes * points_num * sizeof(int) //+1 indices * points_num * sizeof(int) //+1 octreeGlobal.nodes * points_num * sizeof(int) @@ -306,22 +307,22 @@ void pcl::device::OctreeImpl::build() //+3 points_sorted * points_num * sizeof(float) //== - // 10 rows + // 10 rows - //left - //octreeGlobal.nodes_num * 1 * sizeof(int) + //left + //octreeGlobal.nodes_num * 1 * sizeof(int) //== - // 3 * sizeof(int) => +1 row + // 3 * sizeof(int) => +1 row const int transaction_size = 128 / sizeof(int); int cols = std::max(points_num, transaction_size * 4); int rows = 10 + 1; // = 13 - + storage.create(rows, cols); - + codes = DeviceArray(storage.ptr(0), points_num); indices = DeviceArray(storage.ptr(1), points_num); - + octreeGlobal.nodes = storage.ptr(2); octreeGlobal.codes = storage.ptr(3); octreeGlobal.begs = storage.ptr(4); @@ -332,10 +333,10 @@ void pcl::device::OctreeImpl::build() points_sorted = DeviceArray2D(3, points_num, storage.ptr(8), storage.step()); } - + { - //ScopeTimer timer("reduce-morton-sort-permutations"); - + //ScopeTimer timer("reduce-morton-sort-permutations"); + thrust::device_ptr beg(points.ptr()); thrust::device_ptr end = beg + points.size(); @@ -345,49 +346,49 @@ void pcl::device::OctreeImpl::build() atmin.x = atmin.y = atmin.z = std::numeric_limits::lowest(); atmax.w = atmin.w = 0; - //ScopeTimer timer("reduce"); + //ScopeTimer timer("reduce"); PointType minp = thrust::reduce(beg, end, atmax, SelectMinPoint()); PointType maxp = thrust::reduce(beg, end, atmin, SelectMaxPoint()); octreeGlobal.minp = make_float3(minp.x, minp.y, minp.z); octreeGlobal.maxp = make_float3(maxp.x, maxp.y, maxp.z); } - + thrust::device_ptr codes_beg(codes.ptr()); thrust::device_ptr codes_end = codes_beg + codes.size(); { - //ScopeTimer timer("morton"); + //ScopeTimer timer("morton"); thrust::transform(beg, end, codes_beg, CalcMorton(octreeGlobal.minp, octreeGlobal.maxp)); } thrust::device_ptr indices_beg(indices.ptr()); thrust::device_ptr indices_end = indices_beg + indices.size(); { - //ScopeTimer timer("sort"); + //ScopeTimer timer("sort"); thrust::sequence(indices_beg, indices_end); - thrust::sort_by_key(codes_beg, codes_end, indices_beg ); + thrust::sort_by_key(codes_beg, codes_end, indices_beg ); } { - ////ScopeTimer timer("perm"); + ////ScopeTimer timer("perm"); //thrust::copy(make_permutation_iterator(beg, indices_beg), - // make_permutation_iterator(end, indices_end), device_ptr(points_sorted.ptr())); + // make_permutation_iterator(end, indices_end), device_ptr(points_sorted.ptr())); + - } { thrust::device_ptr xs(points_sorted.ptr(0)); thrust::device_ptr ys(points_sorted.ptr(1)); thrust::device_ptr zs(points_sorted.ptr(2)); - //ScopeTimer timer("perm2"); + //ScopeTimer timer("perm2"); thrust::transform(make_permutation_iterator(beg, indices_beg), - make_permutation_iterator(end, indices_end), + make_permutation_iterator(end, indices_end), make_zip_iterator(make_tuple(xs, ys, zs)), PointType_to_tuple()); - + } } - + SingleStepBuild ssb; ssb.octree = octreeGlobal; ssb.codes = codes; diff --git a/gpu/octree/src/utils/approx_nearest_utils.hpp b/gpu/octree/src/utils/approx_nearest_utils.hpp index 247eda0dc9b..9bec17e74d6 100644 --- a/gpu/octree/src/utils/approx_nearest_utils.hpp +++ b/gpu/octree/src/utils/approx_nearest_utils.hpp @@ -12,6 +12,7 @@ #include "morton.hpp" #include +#include #include #include #include diff --git a/gpu/surface/src/cuda/convex_hull.cu b/gpu/surface/src/cuda/convex_hull.cu index c1f20234eba..98e89cd703d 100644 --- a/gpu/surface/src/cuda/convex_hull.cu +++ b/gpu/surface/src/cuda/convex_hull.cu @@ -61,89 +61,89 @@ namespace pcl { namespace device - { + { template struct IndOp { __device__ __forceinline__ thrust::tuple operator()(const thrust::tuple& e1, const thrust::tuple& e2) const - { + { thrust::tuple res; - + if (use_max) - res.get<0>() = fmax(e1.get<0>(), e2.get<0>()); + thrust::get<0>(res) = fmax(thrust::get<0>(e1), thrust::get<0>(e2)); else - res.get<0>() = fmin(e1.get<0>(), e2.get<0>()); + thrust::get<0>(res) = fmin(thrust::get<0>(e1), thrust::get<0>(e2)); - res.get<1>() = (res.get<0>() == e1.get<0>()) ? e1.get<1>() : e2.get<1>(); - return res; - } + thrust::get<1>(res) = (thrust::get<0>(res) == thrust::get<0>(e1)) ? thrust::get<1>(e1) : thrust::get<1>(e2); + return res; + } }; struct X - { - __device__ __forceinline__ - thrust::tuple + { + __device__ __forceinline__ + thrust::tuple operator()(const thrust::tuple& in) const { - return thrust::tuple(in.get<0>().x, in.get<1>()); + return thrust::tuple(thrust::get<0>(in).x, thrust::get<1>(in)); } }; struct Y - { + { __device__ __forceinline__ float operator()(const PointType& in) const { return in.y; } }; struct Z - { + { __device__ __forceinline__ float operator()(const PointType& in) const { return in.z; } }; - + struct LineDist { float3 x1, x2; LineDist(const PointType& p1, const PointType& p2) : x1(tr(p1)), x2(tr(p2)) {} - + __device__ __forceinline__ thrust::tuple operator()(const thrust::tuple& in) const - { - float3 x0 = tr(in.get<0>()); + { + float3 x0 = tr(thrust::get<0>(in)); - float dist = norm(cross(x0 - x1, x0 - x2))/norm(x1 - x2); - return thrust::tuple(dist, in.get<1>()); - } + float dist = norm(cross(x0 - x1, x0 - x2))/norm(x1 - x2); + return thrust::tuple(dist, thrust::get<1>(in)); + } }; struct PlaneDist - { + { float3 x1, n; PlaneDist(const PointType& p1, const PointType& p2, const PointType& p3) : x1(tr(p1)) { float3 x2 = tr(p2), x3 = tr(p3); n = normalized(cross(x2 - x1, x3 - x1)); } - + __device__ __forceinline__ thrust::tuple operator()(const thrust::tuple& in) const { - float3 x0 = tr(in.get<0>()); + float3 x0 = tr(thrust::get<0>(in)); float dist = std::abs(dot(n, x0 - x1)); - return thrust::tuple(dist, in.get<1>()); + return thrust::tuple(dist, thrust::get<1>(in)); } }; - + template int transform_reduce_index(It beg, It end, Unary unop, Init init, Binary binary) { thrust::counting_iterator cbeg(0); thrust::counting_iterator cend = cbeg + thrust::distance(beg, end); - - thrust::tuple t = transform_reduce( - make_zip_iterator(thrust::make_tuple(beg, cbeg)), - make_zip_iterator(thrust::make_tuple(end, cend)), + + thrust::tuple t = transform_reduce( + make_zip_iterator(thrust::make_tuple(beg, cbeg)), + make_zip_iterator(thrust::make_tuple(end, cend)), unop, init, binary); - - return t.get<1>(); + + return thrust::get<1>(t); } template @@ -158,35 +158,35 @@ namespace pcl { thrust::tuple max_tuple(std::numeric_limits::min(), 0); return transform_reduce_index(beg, end, unop, max_tuple, IndOp()); - } + } } } pcl::device::PointStream::PointStream(const Cloud& cloud_) : cloud(cloud_) -{ +{ cloud_size = cloud.size(); facets_dists.create(cloud_size); perm.create(cloud_size); - thrust::device_ptr pbeg(perm.ptr()); + thrust::device_ptr pbeg(perm.ptr()); thrust::sequence(pbeg, pbeg + cloud_size); } void pcl::device::PointStream::computeInitalSimplex() { - thrust::device_ptr beg(cloud.ptr()); + thrust::device_ptr beg(cloud.ptr()); thrust::device_ptr end = beg + cloud_size; - + int minx = transform_reduce_min_index(beg, end, X()); int maxx = transform_reduce_max_index(beg, end, X()); PointType p1 = *(beg + minx); PointType p2 = *(beg + maxx); - + int maxl = transform_reduce_max_index(beg, end, LineDist(p1, p2)); PointType p3 = *(beg + maxl); - + int maxp = transform_reduce_max_index(beg, end, PlaneDist(p1, p2, p3)); PointType p4 = *(beg + maxp); @@ -194,12 +194,12 @@ void pcl::device::PointStream::computeInitalSimplex() simplex.x1 = tr(p1); simplex.x2 = tr(p2); simplex.x3 = tr(p3); simplex.x4 = tr(p4); simplex.i1 = minx; simplex.i2 = maxx; simplex.i3 = maxl; simplex.i4 = maxp; - float maxy = transform_reduce(beg, end, Y(), std::numeric_limits::min(), thrust::maximum()); - float miny = transform_reduce(beg, end, Y(), std::numeric_limits::max(), thrust::minimum()); + float maxy = transform_reduce(beg, end, Y(), std::numeric_limits::min(), thrust::maximum()); + float miny = transform_reduce(beg, end, Y(), std::numeric_limits::max(), thrust::minimum()); + + float maxz = transform_reduce(beg, end, Z(), std::numeric_limits::min(), thrust::maximum()); + float minz = transform_reduce(beg, end, Z(), std::numeric_limits::max(), thrust::minimum()); - float maxz = transform_reduce(beg, end, Z(), std::numeric_limits::min(), thrust::maximum()); - float minz = transform_reduce(beg, end, Z(), std::numeric_limits::max(), thrust::minimum()); - float dx = (p2.x - p1.x); float dy = (maxy - miny); float dz = (maxz - minz); @@ -209,7 +209,7 @@ void pcl::device::PointStream::computeInitalSimplex() simplex.p1 = compute_plane(simplex.x4, simplex.x2, simplex.x3, simplex.x1); simplex.p2 = compute_plane(simplex.x3, simplex.x1, simplex.x4, simplex.x2); simplex.p3 = compute_plane(simplex.x2, simplex.x1, simplex.x4, simplex.x3); - simplex.p4 = compute_plane(simplex.x1, simplex.x2, simplex.x3, simplex.x4); + simplex.p4 = compute_plane(simplex.x1, simplex.x2, simplex.x3, simplex.x4); } namespace pcl @@ -217,7 +217,7 @@ namespace pcl namespace device { __global__ void init_fs(int i1, int i2, int i3, int i4, PtrStep verts_inds) - { + { *(int4*)verts_inds.ptr(0) = make_int4(i2, i1, i1, i1); *(int4*)verts_inds.ptr(1) = make_int4(i3, i3, i2, i2); *(int4*)verts_inds.ptr(2) = make_int4(i4, i4, i4, i3); @@ -227,10 +227,10 @@ namespace pcl } void pcl::device::FacetStream::setInitialFacets(const InitalSimplex& s) -{ - init_fs<<<1, 1>>>(s.i1, s.i2, s.i3, s.i4, verts_inds); +{ + init_fs<<<1, 1>>>(s.i1, s.i2, s.i3, s.i4, verts_inds); cudaSafeCall( cudaGetLastError() ); - cudaSafeCall( cudaDeviceSynchronize() ); + cudaSafeCall( cudaDeviceSynchronize() ); facet_count = 4; } @@ -245,20 +245,20 @@ namespace pcl { float diag; float4 pl1, pl2, pl3, pl4; - - InitalClassify(const float4& p1, const float4& p2, const float4& p3, const float4& p4, float diagonal) + + InitalClassify(const float4& p1, const float4& p2, const float4& p3, const float4& p4, float diagonal) : diag(diagonal), pl1(p1), pl2(p2), pl3(p3), pl4(p4) - { + { pl1 *= compue_inv_normal_norm(pl1); pl2 *= compue_inv_normal_norm(pl2); pl3 *= compue_inv_normal_norm(pl3); pl4 *= compue_inv_normal_norm(pl4); } - + __device__ __forceinline__ - std::uint64_t + std::uint64_t operator()(const PointType& p) const - { + { float4 x = p; x.w = 1; @@ -270,7 +270,7 @@ namespace pcl float dists[] = { d0, d1, d2, d3 }; int negs_inds[4]; int neg_count = 0; - + int idx = std::numeric_limits::max(); float dist = 0; @@ -283,7 +283,7 @@ namespace pcl { int i1 = negs_inds[1]; int i2 = negs_inds[2]; - + int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1; negs_inds[1] = ir; --neg_count; @@ -293,10 +293,10 @@ namespace pcl { int i1 = negs_inds[0]; int i2 = negs_inds[1]; - + int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1; negs_inds[0] = ir; - --neg_count; + --neg_count; } if (neg_count == 1) @@ -311,28 +311,28 @@ namespace pcl std::uint64_t res = idx; res <<= 32; return res + *reinterpret_cast(&dist); - } - }; + } + }; - __global__ void initalClassifyKernel(const InitalClassify ic, const PointType* points, int cloud_size, std::uint64_t* output) - { + __global__ void initalClassifyKernel(const InitalClassify ic, const PointType* points, int cloud_size, std::uint64_t* output) + { int index = threadIdx.x + blockIdx.x * blockDim.x; - if (index < cloud_size) - output[index] = ic(points[index]); + if (index < cloud_size) + output[index] = ic(points[index]); } } } void pcl::device::PointStream::initalClassify() -{ +{ //thrust::device_ptr beg(cloud.ptr()); //thrust::device_ptr end = beg + cloud_size; thrust::device_ptr out(facets_dists.ptr()); - + InitalClassify ic(simplex.p1, simplex.p2, simplex.p3, simplex.p4, cloud_diag); //thrust::transform(beg, end, out, ic); - + //printFuncAttrib(initalClassifyKernel); initalClassifyKernel<<>>(ic, cloud, cloud_size, facets_dists); @@ -350,9 +350,9 @@ namespace pcl { namespace device { - __device__ int new_cloud_size; + __device__ int new_cloud_size; struct SearchFacetHeads - { + { std::uint64_t *facets_dists; int cloud_size; int facet_count; @@ -361,25 +361,25 @@ namespace pcl mutable int* head_points; //bool logger; - + __device__ __forceinline__ void operator()(int facet) const - { + { const std::uint64_t* b = facets_dists; const std::uint64_t* e = b + cloud_size; bool last_thread = facet == facet_count; - int search_value = !last_thread ? facet : std::numeric_limits::max(); - int index = lower_bound(b, e, search_value, LessThanByFacet()) - b; - + int search_value = !last_thread ? facet : std::numeric_limits::max(); + int index = lower_bound(b, e, search_value, LessThanByFacet()) - b; + if (last_thread) new_cloud_size = index; else { bool not_found = index == cloud_size || (facet != (facets_dists[index] >> 32)); - head_points[facet] = not_found ? -1 : perm[index]; + head_points[facet] = not_found ? -1 : perm[index]; } } }; @@ -403,18 +403,18 @@ int pcl::device::PointStream::searchFacetHeads(std::size_t facet_count, DeviceAr sfh.facet_count = (int)facet_count; sfh.perm = perm; sfh.points = cloud.ptr(); - sfh.head_points = head_points; - + sfh.head_points = head_points; + //thrust::counting_iterator b(0); - //thrust::counting_iterator e = b + facet_count + 1; + //thrust::counting_iterator e = b + facet_count + 1; //thrust::for_each(b, e, sfh); searchFacetHeadsKernel<<>>(sfh); cudaSafeCall( cudaGetLastError() ); - cudaSafeCall( cudaDeviceSynchronize() ); + cudaSafeCall( cudaDeviceSynchronize() ); int new_size; - cudaSafeCall( cudaMemcpyFromSymbol( (void*)&new_size, pcl::device::new_cloud_size, sizeof(new_size)) ); + cudaSafeCall( cudaMemcpyFromSymbol( (void*)&new_size, pcl::device::new_cloud_size, sizeof(new_size)) ); return new_size; } @@ -434,7 +434,7 @@ namespace pcl struct Compaction { - enum + enum { CTA_SIZE = 256, @@ -443,18 +443,18 @@ namespace pcl int* head_points_in; PtrStep verts_inds_in; - + int *scan_buffer; int facet_count; mutable int* head_points_out; mutable PtrStep verts_inds_out; - + mutable PtrStep empty_facets; mutable int *empty_count; - + __device__ __forceinline__ void operator()() const { @@ -473,16 +473,16 @@ namespace pcl int offset = scan_buffer[idx]; head_points_out[offset] = head_idx; - + verts_inds_out.ptr(0)[offset] = verts_inds_in.ptr(0)[idx]; verts_inds_out.ptr(1)[offset] = verts_inds_in.ptr(1)[idx]; verts_inds_out.ptr(2)[offset] = verts_inds_in.ptr(2)[idx]; - - + + } - else - empty = 1; + else + empty = 1; } int total = __popc (__ballot_sync (__activemask (), empty)); @@ -498,7 +498,7 @@ namespace pcl if (laneid == 0) { int old = atomicAdd(empty_count, total); - wapr_buffer[warpid] = old; + wapr_buffer[warpid] = old; } int old = wapr_buffer[warpid]; @@ -506,11 +506,11 @@ namespace pcl { empty_facets.ptr(0)[old + offset] = verts_inds_in.ptr(0)[idx]; empty_facets.ptr(1)[old + offset] = verts_inds_in.ptr(1)[idx]; - empty_facets.ptr(2)[old + offset] = verts_inds_in.ptr(2)[idx]; + empty_facets.ptr(2)[old + offset] = verts_inds_in.ptr(2)[idx]; int a1 = verts_inds_in.ptr(0)[idx], a2 = verts_inds_in.ptr(1)[idx], a3 = verts_inds_in.ptr(2)[idx]; } - } + } } }; @@ -521,19 +521,19 @@ namespace pcl void pcl::device::FacetStream::compactFacets() { - int old_empty_count; - empty_count.download(&old_empty_count); + int old_empty_count; + empty_count.download(&old_empty_count); thrust::device_ptr b(head_points.ptr()); thrust::device_ptr e = b + facet_count; thrust::device_ptr o(scan_buffer.ptr()); - - thrust::transform_exclusive_scan(b, e, o, NotMinus1(), 0, thrust::plus()); - + + thrust::transform_exclusive_scan(b, e, o, NotMinus1(), 0, thrust::plus()); + Compaction c; c.verts_inds_in = verts_inds; - c.head_points_in = head_points; + c.head_points_in = head_points; c.scan_buffer = scan_buffer; c.facet_count = facet_count; @@ -543,20 +543,20 @@ void pcl::device::FacetStream::compactFacets() c.empty_facets = empty_facets; c.empty_count = empty_count; - + int block = Compaction::CTA_SIZE; int grid = divUp(facet_count, block); - compactionKernel<<>>(c); + compactionKernel<<>>(c); cudaSafeCall( cudaGetLastError() ); cudaSafeCall( cudaDeviceSynchronize() ); - + verts_inds.swap(verts_inds2); head_points.swap(head_points2); - int new_empty_count; - empty_count.download(&new_empty_count); - + int new_empty_count; + empty_count.download(&new_empty_count); + facet_count -= new_empty_count - old_empty_count; } @@ -583,11 +583,11 @@ namespace pcl int facet_count; - __device__ __forceinline__ + __device__ __forceinline__ void operator()(int point_idx) const { int perm_index = perm[point_idx]; - + int facet = facets_dists[point_idx] >> 32; facet = scan_buffer[facet]; @@ -596,10 +596,10 @@ namespace pcl if (hi == perm_index) { std::uint64_t res = std::numeric_limits::max(); - res <<= 32; + res <<= 32; facets_dists[point_idx] = res; } - else + else { int i1 = verts_inds.ptr(0)[facet]; @@ -610,16 +610,16 @@ namespace pcl float3 v1 = tr( points[ i1 ] ); float3 v2 = tr( points[ i2 ] ); float3 v3 = tr( points[ i3 ] ); - + float4 p0 = compute_plane(hp, v1, v2, /*opposite*/v3); // j float4 p1 = compute_plane(hp, v2, v3, /*opposite*/v1); // facet_count + j - float4 p2 = compute_plane(hp, v3, v1, /*opposite*/v2); // facet_count + j*2 + float4 p2 = compute_plane(hp, v3, v1, /*opposite*/v2); // facet_count + j*2 p0 *= compue_inv_normal_norm(p0); p1 *= compue_inv_normal_norm(p1); p2 *= compue_inv_normal_norm(p2); - + float4 p = points[perm_index]; p.w = 1; @@ -640,12 +640,12 @@ namespace pcl for(int i = 0; i < 3; ++i) if (dists[i] < 0) negs_inds[neg_count++] = i; - + if (neg_count == 3) { int i1 = negs_inds[1]; int i2 = negs_inds[2]; - + int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1; negs_inds[1] = ir; --neg_count; @@ -655,10 +655,10 @@ namespace pcl { int i1 = negs_inds[0]; int i2 = negs_inds[1]; - + int ir = std::abs(dists[i1]) < std::abs(dists[i2]) ? i2 : i1; negs_inds[0] = ir; - --neg_count; + --neg_count; } if (neg_count == 1) @@ -670,16 +670,16 @@ namespace pcl // if (neg_count == 0) // new_idx = std::numeric_limits::max() ==>> internal point - + std::uint64_t res = new_idx; res <<= 32; res += *reinterpret_cast(&dist); facets_dists[point_idx] = res; - } /* if (hi == perm_index) */ + } /* if (hi == perm_index) */ } - }; + }; __global__ void classifyKernel(const Classify c, int cloud_size) { @@ -692,7 +692,7 @@ namespace pcl } void pcl::device::PointStream::classify(FacetStream& fs) -{ +{ Classify c; c.facets_dists = facets_dists; @@ -706,16 +706,16 @@ void pcl::device::PointStream::classify(FacetStream& fs) c.diag = cloud_diag; c.facet_count = fs.facet_count; - //thrust::counting_iterator b(0); + //thrust::counting_iterator b(0); //thrust::for_each(b, b + cloud_size, c); classifyKernel<<>>(c, cloud_size); cudaSafeCall( cudaGetLastError() ); cudaSafeCall( cudaDeviceSynchronize() ); - + thrust::device_ptr beg(facets_dists.ptr()); thrust::device_ptr end = beg + cloud_size; - + thrust::device_ptr pbeg(perm.ptr()); thrust::sort_by_key(beg, end, pbeg); } @@ -731,14 +731,14 @@ namespace pcl mutable PtrStep verts_inds; - __device__ __forceinline__ + __device__ __forceinline__ void operator()(int facet) const { int hi = head_points[facet]; int i1 = verts_inds.ptr(0)[facet]; int i2 = verts_inds.ptr(1)[facet]; int i3 = verts_inds.ptr(2)[facet]; - + make_facet(hi, i1, i2, facet); make_facet(hi, i2, i3, facet + facet_count); make_facet(hi, i3, i1, facet + facet_count * 2); @@ -757,8 +757,8 @@ namespace pcl { int facet = threadIdx.x + blockIdx.x * blockDim.x; - if (facet < sf.facet_count) - sf(facet); + if (facet < sf.facet_count) + sf(facet); } } } @@ -769,9 +769,9 @@ void pcl::device::FacetStream::splitFacets() sf.head_points = head_points; sf.verts_inds = verts_inds; sf.facet_count = facet_count; - - //thrust::counting_iterator b(0); + + //thrust::counting_iterator b(0); //thrust::for_each(b, b + facet_count, sf); splitFacetsKernel<<>>(sf); @@ -786,8 +786,8 @@ size_t pcl::device::remove_duplicates(DeviceArray& indeces) thrust::device_ptr beg(indeces.ptr()); thrust::device_ptr end = beg + indeces.size(); - thrust::sort(beg, end); - return (std::size_t)(thrust::unique(beg, end) - beg); + thrust::sort(beg, end); + return (std::size_t)(thrust::unique(beg, end) - beg); } @@ -810,15 +810,15 @@ void pcl::device::pack_hull(const DeviceArray& points, const DeviceAr { output.create(indeces.size()); - //thrust::device_ptr in(points.ptr()); - + //thrust::device_ptr in(points.ptr()); + //thrust::device_ptr mb(indeces.ptr()); //thrust::device_ptr me = mb + indeces.size(); - //thrust::device_ptr out(output.ptr()); + //thrust::device_ptr out(output.ptr()); //thrust::gather(mb, me, in, out); - + gatherKernel<<>>(indeces, points, output); cudaSafeCall( cudaGetLastError() ); cudaSafeCall( cudaDeviceSynchronize() ); From dc1ac5061c83191fb489e9f65d761bd840fdb08d Mon Sep 17 00:00:00 2001 From: = <=> Date: Thu, 14 Mar 2024 14:12:44 +0000 Subject: [PATCH 216/288] Its not necessary and was only used for some gpu applications. CUDA_TOOLKIT_INCLUDE is used in PCL_CUDA_ADD_EXECUTABLE/LIBRARY. --- cmake/pcl_find_cuda.cmake | 9 +-------- gpu/kinfu/CMakeLists.txt | 2 +- gpu/kinfu_large_scale/CMakeLists.txt | 2 +- gpu/people/CMakeLists.txt | 2 +- 4 files changed, 4 insertions(+), 11 deletions(-) diff --git a/cmake/pcl_find_cuda.cmake b/cmake/pcl_find_cuda.cmake index 466d033feac..7897ee9d58b 100644 --- a/cmake/pcl_find_cuda.cmake +++ b/cmake/pcl_find_cuda.cmake @@ -65,20 +65,13 @@ if(CUDA_FOUND) cmake_policy(SET CMP0104 NEW) set(CMAKE_CUDA_ARCHITECTURES ${CUDA_ARCH_BIN}) message(STATUS "CMAKE_CUDA_ARCHITECTURES: ${CMAKE_CUDA_ARCHITECTURES}") - - #Add empty project as its not required with newer CMake - add_library(pcl_cuda INTERFACE) else() # Generate SASS set(CMAKE_CUDA_ARCHITECTURES ${CUDA_ARCH_BIN}) # Generate PTX for last architecture list(GET CUDA_ARCH_BIN -1 ver) set(CMAKE_CUDA_FLAGS "${CMAKE_CUDA_FLAGS} -gencode arch=compute_${ver},code=compute_${ver}") - message(STATUS "CMAKE_CUDA_FLAGS: ${CMAKE_CUDA_FLAGS}") - - add_library(pcl_cuda INTERFACE) - target_include_directories(pcl_cuda INTERFACE ${CUDA_TOOLKIT_INCLUDE}) - + message(STATUS "CMAKE_CUDA_FLAGS: ${CMAKE_CUDA_FLAGS}") endif () else() message(STATUS "CUDA was not found.") diff --git a/gpu/kinfu/CMakeLists.txt b/gpu/kinfu/CMakeLists.txt index fbbd294fdbc..723604a7557 100644 --- a/gpu/kinfu/CMakeLists.txt +++ b/gpu/kinfu/CMakeLists.txt @@ -29,7 +29,7 @@ set(LIB_NAME "pcl_${SUBSYS_NAME}") include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${cuda}) -target_link_libraries(${LIB_NAME} pcl_cuda pcl_gpu_containers) +target_link_libraries(${LIB_NAME} pcl_gpu_containers) target_compile_options(${LIB_NAME} PRIVATE $<$:--ftz=true;--prec-div=false;--prec-sqrt=false>) diff --git a/gpu/kinfu_large_scale/CMakeLists.txt b/gpu/kinfu_large_scale/CMakeLists.txt index a5d4bac8fb5..e712a365daa 100644 --- a/gpu/kinfu_large_scale/CMakeLists.txt +++ b/gpu/kinfu_large_scale/CMakeLists.txt @@ -33,7 +33,7 @@ include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURC PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${cuda}) -target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_io pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree pcl_octree pcl_filters) +target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree pcl_octree pcl_filters) target_compile_options(${LIB_NAME} PRIVATE $<$:--ftz=true;--prec-div=false;--prec-sqrt=false>) diff --git a/gpu/people/CMakeLists.txt b/gpu/people/CMakeLists.txt index ebcb5fd875b..dcc2040f4eb 100644 --- a/gpu/people/CMakeLists.txt +++ b/gpu/people/CMakeLists.txt @@ -56,7 +56,7 @@ include_directories( set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${hdrs} ${srcs_cuda}) -target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers ${CUDA_CUDART_LIBRARY} ${CUDA_npp_LIBRARY}) +target_link_libraries(${LIB_NAME} pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers ${CUDA_CUDART_LIBRARY} ${CUDA_npp_LIBRARY}) if(UNIX OR APPLE) target_compile_options(${LIB_NAME} INTERFACE $<$:"-Xcompiler=-fPIC">) From d88afe0888562f97b7a9e5396fa2479412dc5174 Mon Sep 17 00:00:00 2001 From: ryosga Date: Thu, 21 Mar 2024 15:12:21 +0800 Subject: [PATCH 217/288] fixed setShapeRenderingProperties(PCL_VISUALIZER_FONT_SIZE), was not working It always returns false. Because vtkTextActor is not a subclass of vtkActor, the actor is just empty. --- visualization/src/pcl_visualizer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index fe1b15fabc1..5f073646ac1 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -1760,7 +1760,7 @@ pcl::visualization::PCLVisualizer::setShapeRenderingProperties ( } // Get the actor pointer vtkActor* actor = vtkActor::SafeDownCast (am_it->second); - if (!actor) + if (!actor && property != PCL_VISUALIZER_FONT_SIZE) // vtkTextActor is not a subclass of vtkActor return (false); switch (property) From ad2bf688b2d036fe703cd16ea6d574e453e101b2 Mon Sep 17 00:00:00 2001 From: steple Date: Fri, 22 Mar 2024 05:43:10 -0700 Subject: [PATCH 218/288] fix container overflow read (#5980) * fix container overflow read nearestKSearch might reduce the size of nn_dists. * address review feedback * switch to std::size_t --- .../pcl/filters/impl/statistical_outlier_removal.hpp | 8 ++++---- filters/src/statistical_outlier_removal.cpp | 10 +++++----- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp b/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp index 0e9359f0bad..3b81df8b3fb 100644 --- a/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp +++ b/filters/include/pcl/filters/impl/statistical_outlier_removal.hpp @@ -93,11 +93,11 @@ pcl::StatisticalOutlierRemoval::applyFilterIndices (Indices &indices) continue; } - // Calculate the mean distance to its neighbors + // Calculate the mean distance to its neighbors. double dist_sum = 0.0; - for (int k = 1; k < searcher_k; ++k) // k = 0 is the query point - dist_sum += sqrt (nn_dists[k]); - distances[iii] = static_cast (dist_sum / mean_k_); + for (std::size_t k = 1; k < nn_dists.size(); ++k) // k = 0 is the query point + dist_sum += sqrt(nn_dists[k]); + distances[iii] = static_cast(dist_sum / (nn_dists.size() - 1)); valid_distances++; } diff --git a/filters/src/statistical_outlier_removal.cpp b/filters/src/statistical_outlier_removal.cpp index 3690d86c3fa..a72ff3fdd6d 100644 --- a/filters/src/statistical_outlier_removal.cpp +++ b/filters/src/statistical_outlier_removal.cpp @@ -227,11 +227,11 @@ pcl::StatisticalOutlierRemoval::generateStatistics (double& continue; } - // Minimum distance (if mean_k_ == 2) or mean distance - double dist_sum = 0; - for (int j = 1; j < mean_k_; ++j) - dist_sum += sqrt (nn_dists[j]); - distances[cp] = static_cast (dist_sum / (mean_k_ - 1)); + // Calculate the mean distance to its neighbors. + double dist_sum = 0.0; + for (std::size_t k = 1; k < nn_dists.size(); ++k) // k = 0 is the query point + dist_sum += sqrt(nn_dists[k]); + distances[cp] = static_cast(dist_sum / (nn_dists.size() - 1)); valid_distances++; } From 7ac73de81df0ad5e31fd467db758bdeab5505ca8 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Mon, 25 Mar 2024 10:10:35 +0100 Subject: [PATCH 219/288] Add `pcl::PointXYZLNormal` to GP3 PCL_INSTANTIATE --- surface/src/gp3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/surface/src/gp3.cpp b/surface/src/gp3.cpp index 362d0ba8445..e099ff3f604 100644 --- a/surface/src/gp3.cpp +++ b/surface/src/gp3.cpp @@ -41,5 +41,5 @@ #include // Instantiations of specific point types -PCL_INSTANTIATE(GreedyProjectionTriangulation, (pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)) +PCL_INSTANTIATE(GreedyProjectionTriangulation, (pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal)) From 7f07c87204820def85e12ce68663384406e9aa9b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?D=C5=BEenan=20Zuki=C4=87?= Date: Tue, 26 Mar 2024 09:48:51 -0400 Subject: [PATCH 220/288] fix pcl::squaredEuclideanDistance already defined in grabcut_2d.cpp.obj Detailed error message: FAILED: bin/pcl_grabcut_2d.exe C:\WINDOWS\system32\cmd.exe /C "cd . && "C:\Program Files\CMake\bin\cmake.exe" -E vs_link_exe --intdir=apps\CMakeFiles\pcl_grabcut_2d.dir --rc=C:\PROGRA~2\WI3CF2~1\10\bin\100226~1.0\x64\rc.exe --mt=C:\PROGRA~2\WI3CF2~1\10\bin\100226~1.0\x64\mt.exe --manifests -- C:\PROGRA~1\MIB055~1\2022\COMMUN~1\VC\Tools\MSVC\1439~1.335\bin\Hostx64\x64\link.exe @CMakeFiles\pcl_grabcut_2d.rsp /out:bin\pcl_grabcut_2d.exe /implib:lib\pcl_grabcut_2d.lib /pdb:bin\pcl_grabcut_2d.pdb /version:0.0 /machine:x64 /nologo /DEBUG /INCREMENTAL:NO /OPT:REF /OPT:ICF /subsystem:console && cd ." LINK: command "C:\PROGRA~1\MIB055~1\2022\COMMUN~1\VC\Tools\MSVC\1439~1.335\bin\Hostx64\x64\link.exe @CMakeFiles\pcl_grabcut_2d.rsp /out:bin\pcl_grabcut_2d.exe /implib:lib\pcl_grabcut_2d.lib /pdb:bin\pcl_grabcut_2d.pdb /version:0.0 /machine:x64 /nologo /DEBUG /INCREMENTAL:NO /OPT:REF /OPT:ICF /subsystem:console /MANIFEST:EMBED,ID=1" failed (exit code 1169) with the following output: pcl_segmentation.lib(grabcut_segmentation.cpp.obj) : error LNK2005: "float __cdecl pcl::squaredEuclideanDistance(struct pcl::segmentation::grabcut::Color const &,struct pcl::segmentation::grabcut::Color const &)" (??$squaredEuclideanDistance@UColor@grabcut@segmentation@pcl@@U1234@@pcl@@YAMAEBUColor@grabcut@segmentation@0@0@Z) already defined in grabcut_2d.cpp.obj bin\pcl_grabcut_2d.exe : fatal error LNK1169: one or more multiply defined symbols found --- .../include/pcl/segmentation/impl/grabcut_segmentation.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/segmentation/include/pcl/segmentation/impl/grabcut_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/grabcut_segmentation.hpp index 2ef5fc27b16..5143080b6de 100644 --- a/segmentation/include/pcl/segmentation/impl/grabcut_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/grabcut_segmentation.hpp @@ -48,8 +48,8 @@ namespace pcl { template <> -float squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1, - const pcl::segmentation::grabcut::Color &c2) +inline float squaredEuclideanDistance (const pcl::segmentation::grabcut::Color &c1, + const pcl::segmentation::grabcut::Color &c2) { return ((c1.r-c2.r)*(c1.r-c2.r)+(c1.g-c2.g)*(c1.g-c2.g)+(c1.b-c2.b)*(c1.b-c2.b)); } From 0579359df1c014964a05b13a3b45191625a09a70 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 26 Mar 2024 20:10:08 +0100 Subject: [PATCH 221/288] gpu_kinfu_large_scale: fix bad dependency on vtk.pc vtk.pc does not exist, so vtk should not appear in PCL_MAKE_PKGCONFIG as an external dependency --- gpu/kinfu_large_scale/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gpu/kinfu_large_scale/CMakeLists.txt b/gpu/kinfu_large_scale/CMakeLists.txt index a5d4bac8fb5..d65a18d59be 100644 --- a/gpu/kinfu_large_scale/CMakeLists.txt +++ b/gpu/kinfu_large_scale/CMakeLists.txt @@ -37,7 +37,7 @@ target_link_libraries(${LIB_NAME} pcl_cuda pcl_common pcl_io pcl_gpu_utils pcl_g target_compile_options(${LIB_NAME} PRIVATE $<$:--ftz=true;--prec-div=false;--prec-sqrt=false>) -PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS ${EXT_DEPS}) +PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} EXT_DEPS "") # Install include files PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_PATH}" ${incs}) From 99ea62c614051ed9eb1ded818eb94894ae416356 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 27 Mar 2024 11:51:43 +0100 Subject: [PATCH 222/288] OBJReader: fix possible out-of-bounds access Fixes https://github.com/PointCloudLibrary/pcl/issues/5987 --- io/src/obj_io.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 108481a69bc..19d454e120b 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -215,8 +215,8 @@ pcl::MTLReader::read (const std::string& mtl_file_path) // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments - if (st[0] == "#") + // Ignore comments and lines with only whitespace + if (st.empty() || st[0] == "#") continue; if (st[0] == "newmtl") @@ -573,8 +573,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments - if (st[0] == "#") + // Ignore comments and lines with only whitespace + if (st.empty() || st[0] == "#") continue; // Vertex @@ -711,8 +711,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments - if (st[0] == "#") + // Ignore comments and lines with only whitespace + if (st.empty() || st[0] == "#") continue; // Vertex if (st[0] == "v") @@ -904,8 +904,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments - if (st[0] == "#") + // Ignore comments and lines with only whitespace + if (st.empty() || st[0] == "#") continue; // Vertex From 9e408d507dd6d8358b53471fdbd067cf600feccd Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 27 Mar 2024 14:16:21 +0100 Subject: [PATCH 223/288] Fix ubuntu-variety CI and update compilers Add quotation marks around args to fix the failing CI. Also add new compiler versions (gcc-14 and clang-18) --- .ci/azure-pipelines/ubuntu-variety.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.ci/azure-pipelines/ubuntu-variety.yaml b/.ci/azure-pipelines/ubuntu-variety.yaml index 24f34dbe349..de119edea90 100644 --- a/.ci/azure-pipelines/ubuntu-variety.yaml +++ b/.ci/azure-pipelines/ubuntu-variety.yaml @@ -32,11 +32,11 @@ jobs: POSSIBLE_VTK_VERSION=("9") \ POSSIBLE_CMAKE_CXX_STANDARD=("14" "17" "20") \ POSSIBLE_CMAKE_BUILD_TYPE=("None" "Debug" "Release" "RelWithDebInfo" "MinSizeRel") \ - POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang libomp-dev" "clang-13 libomp-13-dev" "clang-14 libomp-14-dev" "clang-15 libomp-15-dev" "clang-16 libomp-16-dev" "clang-17 libomp-17-dev") \ - POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "clang" "clang-13" "clang-14" "clang-15" "clang-16" "clang-17") \ - POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "clang++" "clang++-13" "clang++-14" "clang++-15" "clang++-16" "clang++-17") \ + POSSIBLE_COMPILER_PACKAGE=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "g++-14" "clang libomp-dev" "clang-14 libomp-14-dev" "clang-15 libomp-15-dev" "clang-16 libomp-16-dev" "clang-17 libomp-17-dev" "clang-18 libomp-18-dev") \ + POSSIBLE_CMAKE_C_COMPILER=("gcc" "gcc-10" "gcc-11" "gcc-12" "gcc-13" "gcc-14" "clang" "clang-14" "clang-15" "clang-16" "clang-17" "clang-18") \ + POSSIBLE_CMAKE_CXX_COMPILER=("g++" "g++-10" "g++-11" "g++-12" "g++-13" "g++-14" "clang++" "clang++-14" "clang++-15" "clang++-16" "clang++-17" "clang++-18") \ CHOSEN_COMPILER=$[RANDOM%${#POSSIBLE_COMPILER_PACKAGE[@]}] \ - dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]} --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \ + dockerBuildArgs="--build-arg VTK_VERSION=${POSSIBLE_VTK_VERSION[$[RANDOM%${#POSSIBLE_VTK_VERSION[@]}]]} --build-arg CMAKE_CXX_STANDARD=${POSSIBLE_CMAKE_CXX_STANDARD[$[RANDOM%${#POSSIBLE_CMAKE_CXX_STANDARD[@]}]]} --build-arg CMAKE_BUILD_TYPE=${POSSIBLE_CMAKE_BUILD_TYPE[$[RANDOM%${#POSSIBLE_CMAKE_BUILD_TYPE[@]}]]} --build-arg COMPILER_PACKAGE=\"${POSSIBLE_COMPILER_PACKAGE[$CHOSEN_COMPILER]}\" --build-arg CMAKE_C_COMPILER=${POSSIBLE_CMAKE_C_COMPILER[$CHOSEN_COMPILER]} --build-arg CMAKE_CXX_COMPILER=${POSSIBLE_CMAKE_CXX_COMPILER[$CHOSEN_COMPILER]}" ; \ echo "##vso[task.setvariable variable=dockerBuildArgs]$dockerBuildArgs" displayName: "Prepare docker build arguments" - task: Docker@2 From 045abc3b8b973cf18ff1dae650b0d26adde309b4 Mon Sep 17 00:00:00 2001 From: Wang Kai <53281385+kai-waang@users.noreply.github.com> Date: Tue, 2 Apr 2024 16:07:03 +0800 Subject: [PATCH 224/288] [filters] fixing ignored `pcl::Indices` in `VoxelGrid` of `PCLPointCloud2` (#5979) * [filters] fixing #5880 * adding back the original `getMinMax3D` functions * [test] adding indices test in `VoxelGrid` tests * fixing build using copied cloud in tests * Delete check if cloud is dense --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- filters/include/pcl/filters/voxel_grid.h | 43 +++- filters/src/voxel_grid.cpp | 270 ++++++++++++++++++----- test/filters/test_filters.cpp | 31 ++- 3 files changed, 284 insertions(+), 60 deletions(-) diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 24615c43e7f..9ecce2bb285 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -44,17 +44,30 @@ namespace pcl { + /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. + * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset + * \param[in] x_idx the index of the X channel + * \param[in] y_idx the index of the Y channel + * \param[in] z_idx the index of the Z channel + * \param[out] min_pt the minimum data point + * \param[out] max_pt the maximum data point + */ + PCL_EXPORTS void + getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset + * \param[in] indices the point cloud indices that need to be considered * \param[in] x_idx the index of the X channel * \param[in] y_idx the index of the Y channel * \param[in] z_idx the index of the Z channel * \param[out] min_pt the minimum data point * \param[out] max_pt the maximum data point - */ + */ PCL_EXPORTS void - getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, - Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); + getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt); /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. * \note Performs internal data filtering as well. @@ -69,9 +82,29 @@ namespace pcl * \param[out] max_pt the maximum data point * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be * considered, \b true otherwise. - */ + */ PCL_EXPORTS void getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false); + + /** \brief Obtain the maximum and minimum points in 3D from a given point cloud. + * \note Performs internal data filtering as well. + * \param[in] cloud the pointer to a pcl::PCLPointCloud2 dataset + * \param[in] indices the point cloud indices that need to be considered + * \param[in] x_idx the index of the X channel + * \param[in] y_idx the index of the Y channel + * \param[in] z_idx the index of the Z channel + * \param[in] distance_field_name the name of the dimension to filter data along to + * \param[in] min_distance the minimum acceptable value in \a distance_field_name data + * \param[in] max_distance the maximum acceptable value in \a distance_field_name data + * \param[out] min_pt the minimum data point + * \param[out] max_pt the maximum data point + * \param[in] limit_negative \b false if data \b inside of the [min_distance; max_distance] interval should be + * considered, \b true otherwise. + */ + PCL_EXPORTS void + getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const Indices &indices, int x_idx, int y_idx, int z_idx, const std::string &distance_field_name, float min_distance, float max_distance, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative = false); @@ -515,7 +548,7 @@ namespace pcl VoxelGrid () : leaf_size_ (Eigen::Vector4f::Zero ()), inverse_leaf_size_ (Eigen::Array4f::Zero ()), - + min_b_ (Eigen::Vector4i::Zero ()), max_b_ (Eigen::Vector4i::Zero ()), div_b_ (Eigen::Vector4i::Zero ()), diff --git a/filters/src/voxel_grid.cpp b/filters/src/voxel_grid.cpp index 2a3ab968bfd..de56caa46a9 100644 --- a/filters/src/voxel_grid.cpp +++ b/filters/src/voxel_grid.cpp @@ -49,7 +49,7 @@ using Array4size_t = Eigen::Array; /////////////////////////////////////////////////////////////////////////////////////////// void pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, - Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) { // @todo fix this if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 || @@ -76,8 +76,8 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float)); memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float)); // Check if the point is invalid - if (!std::isfinite (pt[0]) || - !std::isfinite (pt[1]) || + if (!std::isfinite (pt[0]) || + !std::isfinite (pt[1]) || !std::isfinite (pt[2])) { xyz_offset += cloud->point_step; @@ -91,11 +91,66 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx max_pt = max_p; } +/////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) +{ + if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 || + cloud->fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 || + cloud->fields[z_idx].datatype != pcl::PCLPointField::FLOAT32) + { + PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n"); + return; + } + + Eigen::Array4f min_p, max_p; + min_p.setConstant (std::numeric_limits::max()); + max_p.setConstant (std::numeric_limits::lowest()); + + Eigen::Array4f pt = Eigen::Array4f::Zero (); + Array4size_t xyz_offset (cloud->fields[x_idx].offset, cloud->fields[y_idx].offset, cloud->fields[z_idx].offset, 0); + + if(cloud->is_dense) // no need to check validity of points + { + for (const auto& index : indices) + { + // Unoptimized memcpys: assume fields x, y, z are in random order + memcpy(&pt[0],&cloud->data[xyz_offset[0] + cloud->point_step * index],sizeof(float)); + memcpy(&pt[1],&cloud->data[xyz_offset[1] + cloud->point_step * index],sizeof(float)); + memcpy(&pt[2],&cloud->data[xyz_offset[2] + cloud->point_step * index],sizeof(float)); + min_p = (min_p.min)(pt); + max_p = (max_p.max)(pt); + } + } + else + { + for (const auto& index : indices) + { + // Unoptimized memcpys: assume fields x, y, z are in random order + memcpy(&pt[0],&cloud->data[xyz_offset[0] + cloud->point_step * index],sizeof(float)); + memcpy(&pt[1],&cloud->data[xyz_offset[1] + cloud->point_step * index],sizeof(float)); + memcpy(&pt[2],&cloud->data[xyz_offset[2] + cloud->point_step * index],sizeof(float)); + // Check if the point is invalid + if (!std::isfinite(pt[0]) || + !std::isfinite(pt[1]) || + !std::isfinite(pt[2])) + { + continue; + } + min_p = (min_p.min)(pt); + max_p = (max_p.max)(pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + /////////////////////////////////////////////////////////////////////////////////////////// void pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx, int z_idx, - const std::string &distance_field_name, float min_distance, float max_distance, - Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative) + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative) { // @todo fix this if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 || @@ -124,9 +179,9 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx Eigen::Array4f pt = Eigen::Array4f::Zero (); Array4size_t xyz_offset (cloud->fields[x_idx].offset, - cloud->fields[y_idx].offset, - cloud->fields[z_idx].offset, - 0); + cloud->fields[y_idx].offset, + cloud->fields[z_idx].offset, + 0); float distance_value = 0; for (std::size_t cp = 0; cp < nr_points; ++cp) { @@ -159,8 +214,8 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx memcpy (&pt[1], &cloud->data[xyz_offset[1]], sizeof (float)); memcpy (&pt[2], &cloud->data[xyz_offset[2]], sizeof (float)); // Check if the point is invalid - if (!std::isfinite (pt[0]) || - !std::isfinite (pt[1]) || + if (!std::isfinite (pt[0]) || + !std::isfinite (pt[1]) || !std::isfinite (pt[2])) { xyz_offset += cloud->point_step; @@ -174,6 +229,124 @@ pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, int x_idx, int y_idx max_pt = max_p; } +/////////////////////////////////////////////////////////////////////////////////////////// +void +pcl::getMinMax3D (const pcl::PCLPointCloud2ConstPtr &cloud, const pcl::Indices &indices, int x_idx, int y_idx, int z_idx, + const std::string &distance_field_name, float min_distance, float max_distance, + Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, bool limit_negative) +{ + // @todo fix this + if (cloud->fields[x_idx].datatype != pcl::PCLPointField::FLOAT32 || + cloud->fields[y_idx].datatype != pcl::PCLPointField::FLOAT32 || + cloud->fields[z_idx].datatype != pcl::PCLPointField::FLOAT32) + { + PCL_ERROR ("[pcl::getMinMax3D] XYZ dimensions are not float type!\n"); + return; + } + + Eigen::Array4f min_p, max_p; + min_p.setConstant (std::numeric_limits::max()); + max_p.setConstant (std::numeric_limits::lowest()); + + // Get the distance field index + int distance_idx = pcl::getFieldIndex (*cloud, distance_field_name); + + // @todo fix this + if (cloud->fields[distance_idx].datatype != pcl::PCLPointField::FLOAT32) + { + PCL_ERROR ("[pcl::getMinMax3D] Filtering dimensions is not float type!\n"); + return; + } + + Eigen::Array4f pt = Eigen::Array4f::Zero (); + Array4size_t xyz_offset (cloud->fields[x_idx].offset, + cloud->fields[y_idx].offset, + cloud->fields[z_idx].offset, + 0); + float distance_value = 0; + if(cloud->is_dense) + { + for (const auto& index : indices) { + std::size_t point_offset = index * cloud->point_step; + + // Get the distance value + memcpy(&distance_value, + &cloud->data[point_offset + cloud->fields[distance_idx].offset], + sizeof(float)); + + if (limit_negative) { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) { + continue; + } + } + else { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) { + continue; + } + } + + // Unoptimized memcpys: assume fields x, y, z are in random order + memcpy(&pt[0], + &cloud->data[xyz_offset[0] + index * cloud->point_step], + sizeof(float)); + memcpy(&pt[1], + &cloud->data[xyz_offset[1] + index * cloud->point_step], + sizeof(float)); + memcpy(&pt[2], + &cloud->data[xyz_offset[2] + index * cloud->point_step], + sizeof(float)); + min_p = (min_p.min)(pt); + max_p = (max_p.max)(pt); + } + } + else + { + for (const auto& index : indices) + { + std::size_t point_offset = index * cloud->point_step; + + // Get the distance value + memcpy(&distance_value,&cloud->data[point_offset + cloud->fields[distance_idx].offset],sizeof(float)); + + if (limit_negative) + { + // Use a threshold for cutting out points which inside the interval + if ((distance_value < max_distance) && (distance_value > min_distance)) + { + continue; + } + } + else + { + // Use a threshold for cutting out points which are too close/far away + if ((distance_value > max_distance) || (distance_value < min_distance)) + { + continue; + } + } + + // Unoptimized memcpys: assume fields x, y, z are in random order + memcpy(&pt[0],&cloud->data[xyz_offset[0] + index * cloud->point_step],sizeof(float)); + memcpy(&pt[1],&cloud->data[xyz_offset[1] + index * cloud->point_step],sizeof(float)); + memcpy(&pt[2],&cloud->data[xyz_offset[2] + index * cloud->point_step],sizeof(float)); + // Check if the point is invalid + if (!std::isfinite(pt[0]) + || !std::isfinite(pt[1]) + || !std::isfinite(pt[2])) + { + continue; + } + min_p = (min_p.min)(pt); + max_p = (max_p.max)(pt); + } + } + min_pt = min_p; + max_pt = max_p; +} + + /////////////////////////////////////////////////////////////////////////////////////////// void pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) @@ -186,7 +359,6 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) output.data.clear (); return; } - std::size_t nr_points = input_->width * input_->height; // Copy the header (and thus the frame_id) + allocate enough space for points output.height = 1; // downsampling breaks the organized structure @@ -217,11 +389,11 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) Eigen::Vector4f min_p, max_p; // Get the minimum and maximum dimensions if (!filter_field_name_.empty ()) // If we don't want to process the entire cloud... - getMinMax3D (input_, x_idx_, y_idx_, z_idx_, filter_field_name_, - static_cast (filter_limit_min_), + getMinMax3D (input_, *indices_, x_idx_, y_idx_, z_idx_, filter_field_name_, + static_cast (filter_limit_min_), static_cast (filter_limit_max_), min_p, max_p, filter_limit_negative_); else - getMinMax3D (input_, x_idx_, y_idx_, z_idx_, min_p, max_p); + getMinMax3D (input_, *indices_, x_idx_, y_idx_, z_idx_, min_p, max_p); // Check that the leaf size is not too small, given the size of the data std::int64_t dx = static_cast((max_p[0] - min_p[0]) * inverse_leaf_size_[0])+1; @@ -249,7 +421,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) div_b_[3] = 0; std::vector index_vector; - index_vector.reserve (nr_points); + index_vector.reserve (indices_->size()); // Create the first xyz_offset, and set up the division multiplier Array4size_t xyz_offset (input_->fields[x_idx_].offset, @@ -265,8 +437,8 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) if (downsample_all_data_) { centroid_size = static_cast (input_->fields.size ()); - - // ---[ RGB special case + + // ---[ RGB special case // if the data contains "rgba" or "rgb", add an extra field for r/g/b in centroid for (int d = 0; d < centroid_size; ++d) { @@ -278,7 +450,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) } } } - + // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... if (!filter_field_name_.empty ()) { @@ -298,9 +470,9 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) // with calculated idx. Points with the same idx value will contribute to the // same point of resulting CloudPoint float distance_value = 0; - for (std::size_t cp = 0; cp < nr_points; ++cp) + for (const auto &index : *indices_) { - std::size_t point_offset = cp * input_->point_step; + std::size_t point_offset = index * input_->point_step; // Get the distance value memcpy (&distance_value, &input_->data[point_offset + input_->fields[distance_idx].offset], sizeof (float)); @@ -309,7 +481,6 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) // Use a threshold for cutting out points which inside the interval if (distance_value < filter_limit_max_ && distance_value > filter_limit_min_) { - xyz_offset += input_->point_step; continue; } } @@ -318,22 +489,20 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) // Use a threshold for cutting out points which are too close/far away if (distance_value > filter_limit_max_ || distance_value < filter_limit_min_) { - xyz_offset += input_->point_step; continue; } } // Unoptimized memcpys: assume fields x, y, z are in random order - memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float)); - memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float)); - memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float)); + memcpy (&pt[0], &input_->data[xyz_offset[0] + index * input_->point_step], sizeof (float)); + memcpy (&pt[1], &input_->data[xyz_offset[1] + index * input_->point_step], sizeof (float)); + memcpy (&pt[2], &input_->data[xyz_offset[2] + index * input_->point_step], sizeof (float)); // Check if the point is invalid - if (!std::isfinite (pt[0]) || - !std::isfinite (pt[1]) || + if (!std::isfinite (pt[0]) || + !std::isfinite (pt[1]) || !std::isfinite (pt[2])) { - xyz_offset += input_->point_step; continue; } @@ -342,28 +511,26 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) int ijk2 = static_cast (std::floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]); // Compute the centroid leaf index int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; - index_vector.emplace_back(idx, static_cast (cp)); + index_vector.emplace_back(idx, static_cast (index)); - xyz_offset += input_->point_step; } } // No distance filtering, process all data else { // First pass: go over all points and insert them into the right leaf - for (std::size_t cp = 0; cp < nr_points; ++cp) + for (const auto &index : *indices_) { // Unoptimized memcpys: assume fields x, y, z are in random order - memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof (float)); - memcpy (&pt[1], &input_->data[xyz_offset[1]], sizeof (float)); - memcpy (&pt[2], &input_->data[xyz_offset[2]], sizeof (float)); + memcpy (&pt[0], &input_->data[xyz_offset[0] + index * input_->point_step], sizeof (float)); + memcpy (&pt[1], &input_->data[xyz_offset[1] + index * input_->point_step], sizeof (float)); + memcpy (&pt[2], &input_->data[xyz_offset[2] + index * input_->point_step], sizeof (float)); // Check if the point is invalid - if (!std::isfinite (pt[0]) || - !std::isfinite (pt[1]) || + if (!std::isfinite (pt[0]) || + !std::isfinite (pt[1]) || !std::isfinite (pt[2])) { - xyz_offset += input_->point_step; continue; } @@ -372,8 +539,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) int ijk2 = static_cast (std::floor (pt[2] * inverse_leaf_size_[2]) - min_b_[2]); // Compute the centroid leaf index int idx = ijk0 * divb_mul_[0] + ijk1 * divb_mul_[1] + ijk2 * divb_mul_[2]; - index_vector.emplace_back(idx, static_cast (cp)); - xyz_offset += input_->point_step; + index_vector.emplace_back(idx, static_cast (index)); } } @@ -392,10 +558,10 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) std::vector > first_and_last_indices_vector; // Worst case size first_and_last_indices_vector.reserve (index_vector.size ()); - while (index < index_vector.size ()) + while (index < index_vector.size ()) { std::size_t i = index + 1; - while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) + while (i < index_vector.size () && index_vector[i].idx == index_vector[index].idx) ++i; if ((i - index) >= min_points_per_voxel_) { @@ -410,7 +576,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) output.row_step = output.point_step * output.width; output.data.resize (output.width * output.point_step); - if (save_leaf_layout_) + if (save_leaf_layout_) { try { @@ -421,21 +587,21 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) for (std::uint32_t i = 0; i < reinit_size; i++) { leaf_layout_[i] = -1; - } - leaf_layout_.resize (new_layout_size, -1); + } + leaf_layout_.resize (new_layout_size, -1); } catch (std::bad_alloc&) { - throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", - "voxel_grid.cpp", "applyFilter"); + throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", + "voxel_grid.cpp", "applyFilter"); } catch (std::length_error&) { - throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", - "voxel_grid.cpp", "applyFilter"); + throw PCLException("VoxelGrid bin size is too low; impossible to allocate memory for layout", + "voxel_grid.cpp", "applyFilter"); } } - + // If we downsample each field, the {x,y,z}_idx_ offsets should correspond in input_ and output if (downsample_all_data_) xyz_offset = Array4size_t (output.fields[x_idx_].offset, @@ -506,7 +672,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) centroid += temporary; } centroid /= static_cast (last_index - first_index); - + std::size_t point_offset = index * output.point_step; // Copy all the fields for (std::size_t d = 0; d < output.fields.size (); ++d) @@ -514,14 +680,14 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) // ---[ RGB special case // full extra r/g/b centroid field - if (rgba_index >= 0) + if (rgba_index >= 0) { float r = centroid[centroid_size-4], g = centroid[centroid_size-3], b = centroid[centroid_size-2], a = centroid[centroid_size-1]; int rgb = (static_cast (a) << 24) | (static_cast (r) << 16) | (static_cast (g) << 8) | static_cast (b); memcpy (&output.data[point_offset + output.fields[rgba_index].offset], &rgb, sizeof (float)); } } - + ++index; } } diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index 15e678ab062..ca342b57e78 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -638,6 +638,19 @@ TEST (VoxelGrid, Filters) EXPECT_LE (std::abs (output[neighbors.at (0)].y - output[centroidIdx].y), 0.02); EXPECT_LE ( output[neighbors.at (0)].z - output[centroidIdx].z, 0.02 * 2); + // indices must be handled correctly + auto indices = grid.getIndices(); // original cloud indices + auto cloud_copied = std::make_shared>(); + *cloud_copied = *cloud; + for (int i = 0; i < 100; i++) { + cloud_copied->emplace_back(100 + i, 100 + i, 100 + i); + } + grid.setInputCloud(cloud_copied); + grid.setIndices(indices); + grid.filter(output); + + EXPECT_EQ(output.size(), 100); // additional points should be ignored + // Test the pcl::PCLPointCloud2 method VoxelGrid grid2; @@ -719,6 +732,18 @@ TEST (VoxelGrid, Filters) EXPECT_LE (std::abs (output[neighbors2.at (0)].x - output[centroidIdx2].x), 0.02); EXPECT_LE (std::abs (output[neighbors2.at (0)].y - output[centroidIdx2].y), 0.02); EXPECT_LE (output[neighbors2.at (0)].z - output[centroidIdx2].z, 0.02 * 2); + + // indices must be handled correctly + auto indices2 = grid2.getIndices(); // original cloud indices + auto cloud_blob2 = std::make_shared(); + toPCLPointCloud2(*cloud_copied, *cloud_blob2); + + grid2.setInputCloud(cloud_blob2); + grid2.setIndices(indices2); + grid2.filter(output_blob); + + fromPCLPointCloud2(output_blob, output); + EXPECT_EQ(output.size(), 100); // additional points should be ignored } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -1353,7 +1378,7 @@ TEST (VoxelGridMinPoints, Filters) // Verify 2 clusters (0.11 and 0.31) passed threshold and verify their location and color EXPECT_EQ (outputMin4.size (), 2); - // Offset noise applied by offsets vec are 1e-3 magnitude, so check within 1e-2 + // Offset noise applied by offsets vec are 1e-3 magnitude, so check within 1e-2 EXPECT_NEAR (outputMin4[0].x, input->at(1).x, 1e-2); EXPECT_NEAR (outputMin4[0].y, input->at(1).y, 1e-2); EXPECT_NEAR (outputMin4[0].z, input->at(1).z, 1e-2); @@ -2052,7 +2077,7 @@ TEST (FrustumCulling, Filters) Eigen::Matrix4f cam2robot; cam2robot << 0, 0, 1, 0, 0, -1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1; - // Cut out object based on ROI + // Cut out object based on ROI fc.setInputCloud (model); fc.setNegative (false); fc.setVerticalFOV (43); @@ -2063,7 +2088,7 @@ TEST (FrustumCulling, Filters) fc.setCameraPose (cam2robot); fc.filter (*output); // Should extract milk cartoon with 13541 points - EXPECT_EQ (output->size (), 13541); + EXPECT_EQ (output->size (), 13541); removed = fc.getRemovedIndices (); EXPECT_EQ (removed->size (), model->size () - output->size ()); From 2f0018f6a73b876b5020833bb898bc56d3b6cc9b Mon Sep 17 00:00:00 2001 From: ryosga Date: Tue, 2 Apr 2024 20:23:53 +0800 Subject: [PATCH 225/288] fix addPolygon and addLine return value error The return value is reversed. --- .../include/pcl/visualization/impl/pcl_visualizer.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index 6c0f42a5f54..244af25d69f 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -482,7 +482,7 @@ pcl::visualization::PCLVisualizer::addPolygon ( const typename pcl::PointCloud::ConstPtr &cloud, const std::string &id, int viewport) { - return (!addPolygon (cloud, 0.5, 0.5, 0.5, id, viewport)); + return (addPolygon (cloud, 0.5, 0.5, 0.5, id, viewport)); } //////////////////////////////////////////////////////////////////////////////////////////// @@ -603,7 +603,7 @@ pcl::visualization::PCLVisualizer::addArrow (const P1 &pt1, const P2 &pt2, template bool pcl::visualization::PCLVisualizer::addLine (const P1 &pt1, const P2 &pt2, const std::string &id, int viewport) { - return (!addLine (pt1, pt2, 0.5, 0.5, 0.5, id, viewport)); + return (addLine (pt1, pt2, 0.5, 0.5, 0.5, id, viewport)); } //////////////////////////////////////////////////////////////////////////////////////////// From cc9bcfcdde078dec86c137b99057e63c7adea44d Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 2 Apr 2024 18:28:09 +0200 Subject: [PATCH 226/288] Only skip first result of radiusSearch if results are sorted The same was done for `extractEuclideanClusters` years ago: https://github.com/PointCloudLibrary/pcl/pull/109 For ConditionalEuclideanClustering, I tested whether it is faster to require sorted results (and skip first entry), or not (and iterate over all results). The second option is much faster (took roughly 2/3 of the time of the first option in my test) --- features/include/pcl/features/impl/cvfh.hpp | 5 +++-- features/include/pcl/features/impl/our_cvfh.hpp | 4 +++- kdtree/include/pcl/kdtree/kdtree.h | 9 +++++++++ recognition/include/pcl/recognition/impl/hv/hv_go.hpp | 4 +++- segmentation/include/pcl/segmentation/extract_clusters.h | 8 ++++++-- .../impl/conditional_euclidean_clustering.hpp | 8 +++++--- .../pcl/segmentation/impl/extract_labeled_clusters.hpp | 5 +++-- .../pcl/segmentation/impl/seeded_hue_segmentation.hpp | 8 ++++++-- 8 files changed, 38 insertions(+), 13 deletions(-) diff --git a/features/include/pcl/features/impl/cvfh.hpp b/features/include/pcl/features/impl/cvfh.hpp index d5df1e6551b..de4fbc17eb3 100644 --- a/features/include/pcl/features/impl/cvfh.hpp +++ b/features/include/pcl/features/impl/cvfh.hpp @@ -96,6 +96,8 @@ pcl::CVFHEstimation::extractEuclideanClustersSmoot static_cast(normals.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -124,8 +126,7 @@ pcl::CVFHEstimation::extractEuclideanClustersSmoot continue; } - // skip index 0, since nn_indices[0] == idx, worth it? - for (std::size_t j = 1; j < nn_indices.size (); ++j) + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; diff --git a/features/include/pcl/features/impl/our_cvfh.hpp b/features/include/pcl/features/impl/our_cvfh.hpp index 34caf74c615..b0f0bc01a2e 100644 --- a/features/include/pcl/features/impl/our_cvfh.hpp +++ b/features/include/pcl/features/impl/our_cvfh.hpp @@ -97,6 +97,8 @@ pcl::OURCVFHEstimation::extractEuclideanClustersSm static_cast(normals.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -124,7 +126,7 @@ pcl::OURCVFHEstimation::extractEuclideanClustersSm continue; } - for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; diff --git a/kdtree/include/pcl/kdtree/kdtree.h b/kdtree/include/pcl/kdtree/kdtree.h index fd5e357fb09..5638c76e3e6 100644 --- a/kdtree/include/pcl/kdtree/kdtree.h +++ b/kdtree/include/pcl/kdtree/kdtree.h @@ -332,6 +332,15 @@ namespace pcl return (min_pts_); } + /** \brief Gets whether the results should be sorted (ascending in the distance) or not + * Otherwise the results may be returned in any order. + */ + inline bool + getSortedResults () const + { + return (sorted_); + } + protected: /** \brief The input point cloud dataset containing the points we need to use. */ PointCloudConstPtr input_; diff --git a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp index e4d6ceee372..3db2df822db 100644 --- a/recognition/include/pcl/recognition/impl/hv/hv_go.hpp +++ b/recognition/include/pcl/recognition/impl/hv/hv_go.hpp @@ -61,6 +61,8 @@ inline void extractEuclideanClustersSmooth(const typename pcl::PointCloudgetSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -96,7 +98,7 @@ inline void extractEuclideanClustersSmooth(const typename pcl::PointCloud(normals.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster) // Create a bool vector of processed point indices, and initialize it to false @@ -151,7 +153,7 @@ namespace pcl continue; } - for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; @@ -243,6 +245,8 @@ namespace pcl static_cast(normals.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; const double cos_eps_angle = std::cos (eps_angle); // compute this once instead of acos many times (faster) // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -270,7 +274,7 @@ namespace pcl continue; } - for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; diff --git a/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp b/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp index 93230268017..5eef5e59919 100644 --- a/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp +++ b/segmentation/include/pcl/segmentation/impl/conditional_euclidean_clustering.hpp @@ -60,11 +60,13 @@ pcl::ConditionalEuclideanClustering::segment (pcl::IndicesClusters &clus if (!searcher_) { if (input_->isOrganized ()) - searcher_.reset (new pcl::search::OrganizedNeighbor ()); + searcher_.reset (new pcl::search::OrganizedNeighbor (false)); // not requiring sorted results is much faster else - searcher_.reset (new pcl::search::KdTree ()); + searcher_.reset (new pcl::search::KdTree (false)); // not requiring sorted results is much faster } searcher_->setInputCloud (input_, indices_); + // If searcher_ gives sorted results, we can skip the first one because it is the query point itself + const int nn_start_idx = searcher_->getSortedResults () ? 1 : 0; // Temp variables used by search class Indices nn_indices; @@ -100,7 +102,7 @@ pcl::ConditionalEuclideanClustering::segment (pcl::IndicesClusters &clus } // Process the neighbors - for (int nii = 1; nii < static_cast (nn_indices.size ()); ++nii) // nii = neighbor indices iterator + for (int nii = nn_start_idx; nii < static_cast (nn_indices.size ()); ++nii) // nii = neighbor indices iterator { // Has this point been processed before? if (nn_indices[nii] == UNAVAILABLE || processed[nn_indices[nii]]) diff --git a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp index 1f6ea1d88d1..37ed0d69435 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_labeled_clusters.hpp @@ -57,6 +57,8 @@ pcl::extractLabeledEuclideanClusters( cloud.size()); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed(cloud.size(), false); @@ -88,8 +90,7 @@ pcl::extractLabeledEuclideanClusters( continue; } - for (std::size_t j = 1; j < nn_indices.size(); - ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size(); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; diff --git a/segmentation/include/pcl/segmentation/impl/seeded_hue_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/seeded_hue_segmentation.hpp index 3976c143e2d..1c79547d966 100644 --- a/segmentation/include/pcl/segmentation/impl/seeded_hue_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/seeded_hue_segmentation.hpp @@ -61,6 +61,8 @@ pcl::seededHueSegmentation (const PointCloud &cloud, static_cast(cloud.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -96,7 +98,7 @@ pcl::seededHueSegmentation (const PointCloud &cloud, continue; } - for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; @@ -139,6 +141,8 @@ pcl::seededHueSegmentation (const PointCloud &cloud, static_cast(cloud.size())); return; } + // If tree gives sorted results, we can skip the first one because it is the query point itself + const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0; // Create a bool vector of processed point indices, and initialize it to false std::vector processed (cloud.size (), false); @@ -173,7 +177,7 @@ pcl::seededHueSegmentation (const PointCloud &cloud, sq_idx++; continue; } - for (std::size_t j = 1; j < nn_indices.size (); ++j) // nn_indices[0] should be sq_idx + for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j) { if (processed[nn_indices[j]]) // Has this point been processed before ? continue; From 969a4376cf005e92eb569324c281c619f78d6eeb Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 9 Apr 2024 21:00:36 +0200 Subject: [PATCH 227/288] Fix minor issues in tests --- test/filters/test_filters.cpp | 2 +- test/geometry/test_mesh_common_functions.h | 1 + test/io/test_io.cpp | 1 + 3 files changed, 3 insertions(+), 1 deletion(-) diff --git a/test/filters/test_filters.cpp b/test/filters/test_filters.cpp index ca342b57e78..be9837475bb 100644 --- a/test/filters/test_filters.cpp +++ b/test/filters/test_filters.cpp @@ -2491,7 +2491,7 @@ TEST (VoxelGridOcclusionEstimation, Filters) auto input_cloud = pcl::make_shared>(); input_cloud->emplace_back(0.0, 0.0, 0.0); input_cloud->emplace_back(9.9, 9.9, 9.9); // we want a nice bounding box from (0, 0, 0) to (10, 10, 10) - input_cloud->sensor_origin_ << -0.1, 0.5, 0.5; // just outside the bounding box. Most rays will enter at voxel (0, 0, 0) + input_cloud->sensor_origin_ << -0.1f, 0.5f, 0.5f, 0.0f; // just outside the bounding box. Most rays will enter at voxel (0, 0, 0) pcl::VoxelGridOcclusionEstimation vg; vg.setInputCloud (input_cloud); vg.setLeafSize (1.0, 1.0, 1.0); diff --git a/test/geometry/test_mesh_common_functions.h b/test/geometry/test_mesh_common_functions.h index 5f3d42f5f2b..0579b99e63d 100644 --- a/test/geometry/test_mesh_common_functions.h +++ b/test/geometry/test_mesh_common_functions.h @@ -40,6 +40,7 @@ #pragma once +#include // for setw #include #include diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index 53438b2e92f..be2f83c07af 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -49,6 +49,7 @@ #include #include #include +#include // for setprecision #include #include From 027db4f9987cb1f1382225fe4d933cc8ee316730 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 14 Apr 2024 10:20:15 +0200 Subject: [PATCH 228/288] Add option to choose boost filesystem over std filesystem Currently, std filesystem is chosen if it is available (if compiled as C++17 or higher). However, it might be good to have the option to choose boost filesystem over std filesystem, even if the latter is available, in case there is some problem with std filesystem. --- common/include/pcl/common/pcl_filesystem.h | 4 +++- io/src/pcd_io.cpp | 4 ++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/common/include/pcl/common/pcl_filesystem.h b/common/include/pcl/common/pcl_filesystem.h index 06b062be676..90e4fa22e6a 100644 --- a/common/include/pcl/common/pcl_filesystem.h +++ b/common/include/pcl/common/pcl_filesystem.h @@ -38,10 +38,12 @@ #pragma once -#if (__cplusplus >= 201703L) +#if (__cplusplus >= 201703L) && !defined(PCL_PREFER_BOOST_FILESYSTEM) +#define PCL_USING_STD_FILESYSTEM #include namespace pcl_fs = std::filesystem; #else +#define PCL_USING_BOOST_FILESYSTEM #include namespace pcl_fs = boost::filesystem; #endif diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 767f65e7d4b..a7fc6860767 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -71,7 +71,7 @@ pcl::PCDWriter::setLockingPermissions (const std::string &file_name, try { -#if (__cplusplus >= 201703L) +#ifdef PCL_USING_STD_FILESYSTEM pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::add); #else pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::add_perms | pcl_fs::set_gid_on_exe); @@ -95,7 +95,7 @@ pcl::PCDWriter::resetLockingPermissions (const std::string &file_name, #ifndef NO_MANDATORY_LOCKING try { -#if (__cplusplus >= 201703L) +#ifdef PCL_USING_STD_FILESYSTEM pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::perms::set_gid, pcl_fs::perm_options::remove); #else pcl_fs::permissions (pcl_fs::path (file_name), pcl_fs::remove_perms | pcl_fs::set_gid_on_exe); From abeac82f815dd8fe19bf8101d93824f482266525 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Tue, 16 Apr 2024 11:16:24 +0200 Subject: [PATCH 229/288] Remove global includes and use target include for all "common" modules. --- 2d/CMakeLists.txt | 2 -- cmake/pcl_targets.cmake | 10 ++++++++++ common/CMakeLists.txt | 5 ----- features/CMakeLists.txt | 2 -- filters/CMakeLists.txt | 1 - geometry/CMakeLists.txt | 2 -- io/CMakeLists.txt | 3 --- kdtree/CMakeLists.txt | 1 - keypoints/CMakeLists.txt | 1 - ml/CMakeLists.txt | 1 - octree/CMakeLists.txt | 1 - outofcore/CMakeLists.txt | 1 - people/CMakeLists.txt | 2 -- recognition/CMakeLists.txt | 1 - registration/CMakeLists.txt | 1 - sample_consensus/CMakeLists.txt | 1 - search/CMakeLists.txt | 1 - segmentation/CMakeLists.txt | 1 - simulation/CMakeLists.txt | 2 -- stereo/CMakeLists.txt | 1 - surface/CMakeLists.txt | 6 ------ test/CMakeLists.txt | 3 +-- test/io/CMakeLists.txt | 1 - test/outofcore/CMakeLists.txt | 1 - test/people/CMakeLists.txt | 1 - tracking/CMakeLists.txt | 1 - visualization/CMakeLists.txt | 8 -------- 27 files changed, 11 insertions(+), 50 deletions(-) diff --git a/2d/CMakeLists.txt b/2d/CMakeLists.txt index e706ca4e7a6..457aae7dbcf 100644 --- a/2d/CMakeLists.txt +++ b/2d/CMakeLists.txt @@ -29,8 +29,6 @@ set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/morphology.hpp" ) -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY) diff --git a/cmake/pcl_targets.cmake b/cmake/pcl_targets.cmake index 2da076c23c5..f3ca56d1c54 100644 --- a/cmake/pcl_targets.cmake +++ b/cmake/pcl_targets.cmake @@ -196,6 +196,11 @@ function(PCL_ADD_LIBRARY _name) PCL_ADD_VERSION_INFO(${_name}) target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES}) + target_include_directories(${_name} PUBLIC + $ + $ + ) + target_link_libraries(${_name} Threads::Threads) if(TARGET OpenMP::OpenMP_CXX) target_link_libraries(${_name} OpenMP::OpenMP_CXX) @@ -257,6 +262,11 @@ function(PCL_CUDA_ADD_LIBRARY _name) target_compile_options(${_name} PRIVATE $<$: ${GEN_CODE} --expt-relaxed-constexpr>) + target_include_directories(${_name} PUBLIC + $ + $ + ) + target_include_directories(${_name} PRIVATE ${CUDA_TOOLKIT_INCLUDE}) if(MSVC) diff --git a/common/CMakeLists.txt b/common/CMakeLists.txt index fd449f2eff6..103cdd5b0b4 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -174,11 +174,6 @@ set(kissfft_srcs set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${kissfft_srcs} ${incs} ${common_incs} ${impl_incs} ${tools_incs} ${kissfft_incs} ${common_incs_impl} ${range_image_incs} ${range_image_incs_impl}) -target_include_directories(${LIB_NAME} PUBLIC - $ - $ -) - target_link_libraries(${LIB_NAME} Boost::boost Eigen3::Eigen) if(MSVC AND NOT (MSVC_VERSION LESS 1915)) diff --git a/features/CMakeLists.txt b/features/CMakeLists.txt index cdf17fdef29..2b280563372 100644 --- a/features/CMakeLists.txt +++ b/features/CMakeLists.txt @@ -11,8 +11,6 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - set(incs "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/eigen.h" diff --git a/filters/CMakeLists.txt b/filters/CMakeLists.txt index a485505b5ab..eb49b3f37d4 100644 --- a/filters/CMakeLists.txt +++ b/filters/CMakeLists.txt @@ -131,7 +131,6 @@ 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_common pcl_sample_consensus pcl_search pcl_kdtree pcl_octree) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/geometry/CMakeLists.txt b/geometry/CMakeLists.txt index 0ec3e6fe5b0..2e0a9ee58b8 100644 --- a/geometry/CMakeLists.txt +++ b/geometry/CMakeLists.txt @@ -37,10 +37,8 @@ set(impl_incs set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") add_library(${LIB_NAME} INTERFACE) -target_include_directories(${LIB_NAME} INTERFACE "${CMAKE_CURRENT_SOURCE_DIR}/include") target_link_libraries(${LIB_NAME} INTERFACE Boost::boost pcl_common) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY) diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index 470796f9a1c..d02a25bb88a 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -209,7 +209,6 @@ if(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") target_link_libraries(pcl_io_ply pcl_common Boost::boost) set(srcs @@ -340,8 +339,6 @@ add_definitions(${VTK_DEFINES}) PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${compression_incs} ${impl_incs} ${OPENNI_INCLUDES} ${OPENNI2_INCLUDES}) -target_include_directories(${LIB_NAME} PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") - target_link_libraries("${LIB_NAME}" Boost::boost Boost::iostreams pcl_common pcl_io_ply) if(TARGET Boost::filesystem) target_link_libraries("${LIB_NAME}" Boost::filesystem) diff --git a/kdtree/CMakeLists.txt b/kdtree/CMakeLists.txt index e015aa3178f..9487af14e4a 100644 --- a/kdtree/CMakeLists.txt +++ b/kdtree/CMakeLists.txt @@ -27,7 +27,6 @@ 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_common FLANN::FLANN) set(EXT_DEPS flann) diff --git a/keypoints/CMakeLists.txt b/keypoints/CMakeLists.txt index de9189a7b47..1964878c82e 100644 --- a/keypoints/CMakeLists.txt +++ b/keypoints/CMakeLists.txt @@ -58,7 +58,6 @@ 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_features pcl_filters) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/ml/CMakeLists.txt b/ml/CMakeLists.txt index a67a5835b8a..7c4c112acf1 100644 --- a/ml/CMakeLists.txt +++ b/ml/CMakeLists.txt @@ -74,7 +74,6 @@ set(srcs ) 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}) SET_TARGET_PROPERTIES("${LIB_NAME}" PROPERTIES LINKER_LANGUAGE CXX) target_link_libraries("${LIB_NAME}" pcl_common) diff --git a/octree/CMakeLists.txt b/octree/CMakeLists.txt index 5f5a431e928..2270690adc5 100644 --- a/octree/CMakeLists.txt +++ b/octree/CMakeLists.txt @@ -50,7 +50,6 @@ set(impl_incs set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs}) target_link_libraries("${LIB_NAME}" pcl_common) -target_include_directories(${LIB_NAME} PUBLIC "${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) # Install include files diff --git a/outofcore/CMakeLists.txt b/outofcore/CMakeLists.txt index dd2a7d8a9c5..eb71895d7c0 100644 --- a/outofcore/CMakeLists.txt +++ b/outofcore/CMakeLists.txt @@ -67,7 +67,6 @@ set(visualization_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} ${visualization_incs}) #PCL_ADD_SSE_FLAGS("${LIB_NAME}") target_link_libraries("${LIB_NAME}" pcl_common pcl_visualization ${Boost_SYSTEM_LIBRARY}) diff --git a/people/CMakeLists.txt b/people/CMakeLists.txt index d49ebf2947e..f2b11e838e6 100644 --- a/people/CMakeLists.txt +++ b/people/CMakeLists.txt @@ -33,8 +33,6 @@ set(srcs ) 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_common pcl_filters pcl_kdtree pcl_sample_consensus pcl_segmentation pcl_visualization) diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 2cda7232be4..ac88a58cbe4 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -158,7 +158,6 @@ else() endif() 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} ${face_detection_incs} ${ransac_based_incs} ${ransac_based_impl_incs} ${hv_incs} ${hv_impl_incs} ${cg_incs} ${cg_impl_incs} ${metslib_incs}) target_link_libraries("${LIB_NAME}" pcl_common pcl_kdtree pcl_octree pcl_search pcl_features pcl_registration pcl_sample_consensus pcl_filters pcl_ml pcl_io) diff --git a/registration/CMakeLists.txt b/registration/CMakeLists.txt index bc8ae11a9f2..cb7bc435e63 100644 --- a/registration/CMakeLists.txt +++ b/registration/CMakeLists.txt @@ -172,7 +172,6 @@ set(srcs ) 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_kdtree pcl_search pcl_sample_consensus pcl_features pcl_filters) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/sample_consensus/CMakeLists.txt b/sample_consensus/CMakeLists.txt index 65652158927..4ce23771bdd 100644 --- a/sample_consensus/CMakeLists.txt +++ b/sample_consensus/CMakeLists.txt @@ -90,7 +90,6 @@ 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_common) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/search/CMakeLists.txt b/search/CMakeLists.txt index e0296cd8e95..d8422ab9e54 100644 --- a/search/CMakeLists.txt +++ b/search/CMakeLists.txt @@ -38,7 +38,6 @@ 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_common FLANN::FLANN pcl_octree pcl_kdtree) list(APPEND EXT_DEPS flann) diff --git a/segmentation/CMakeLists.txt b/segmentation/CMakeLists.txt index cb31b7bf16c..85b3f64be55 100644 --- a/segmentation/CMakeLists.txt +++ b/segmentation/CMakeLists.txt @@ -98,7 +98,6 @@ 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_search pcl_sample_consensus pcl_filters pcl_ml pcl_features) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/simulation/CMakeLists.txt b/simulation/CMakeLists.txt index 1002f5d339f..0591f09f70c 100644 --- a/simulation/CMakeLists.txt +++ b/simulation/CMakeLists.txt @@ -30,8 +30,6 @@ set(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}) target_link_libraries("${LIB_NAME}" pcl_common pcl_io diff --git a/stereo/CMakeLists.txt b/stereo/CMakeLists.txt index 5d980a327a3..566a06f5248 100644 --- a/stereo/CMakeLists.txt +++ b/stereo/CMakeLists.txt @@ -32,7 +32,6 @@ set(srcs ) 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_common) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index 4536cbbe1eb..8f0760a84ab 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -174,11 +174,6 @@ set(impl_incs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") - -include_directories( - "${CMAKE_CURRENT_SOURCE_DIR}/include" - "${CMAKE_CURRENT_SOURCE_DIR}" -) PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${VTK_SMOOTHING_INCLUDES} ${POISSON_INCLUDES} ${OPENNURBS_INCLUDES} ${ON_NURBS_INCLUDES}) target_link_libraries("${LIB_NAME}" pcl_common pcl_search pcl_kdtree pcl_octree ${ON_NURBS_LIBRARIES}) @@ -191,7 +186,6 @@ if(VTK_FOUND) VTK::FiltersModeling VTK::FiltersCore) else() - include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) link_directories(${VTK_LIBRARY_DIRS}) target_link_libraries("${LIB_NAME}" vtkCommonCore diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 5a489065e58..c47ba3b837d 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(GTestSource REQUIRED) include_directories(SYSTEM ${GTEST_INCLUDE_DIRS} ${GTEST_SRC_DIR}) add_library(pcl_gtest STATIC ${GTEST_SRC_DIR}/src/gtest-all.cc) +target_include_directories(pcl_gtest PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/include) enable_testing() @@ -41,8 +42,6 @@ add_custom_target(tests "${CMAKE_CTEST_COMMAND}" ${PCL_CTEST_ARGUMENTS} -V -T Te set_target_properties(tests PROPERTIES FOLDER "Tests") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - add_subdirectory(2d) add_subdirectory(common) add_subdirectory(features) diff --git a/test/io/CMakeLists.txt b/test/io/CMakeLists.txt index 16546ecb189..3b0f90546ea 100644 --- a/test/io/CMakeLists.txt +++ b/test/io/CMakeLists.txt @@ -41,7 +41,6 @@ PCL_ADD_TEST(io_ply_io test_ply_io # Uses VTK readers to verify if(VTK_FOUND AND NOT ANDROID) - include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) PCL_ADD_TEST (io_ply_mesh_io test_ply_mesh_io FILES test_ply_mesh_io.cpp LINK_WITH pcl_gtest pcl_io diff --git a/test/outofcore/CMakeLists.txt b/test/outofcore/CMakeLists.txt index 7a6cb9323e4..7ce9303bcd2 100644 --- a/test/outofcore/CMakeLists.txt +++ b/test/outofcore/CMakeLists.txt @@ -10,7 +10,6 @@ if(NOT build) return() endif() -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) PCL_ADD_TEST (outofcore_test test_outofcore FILES test_outofcore.cpp LINK_WITH pcl_gtest pcl_common pcl_io pcl_filters pcl_outofcore pcl_visualization) diff --git a/test/people/CMakeLists.txt b/test/people/CMakeLists.txt index 6c3840df5c0..d920a36bf47 100644 --- a/test/people/CMakeLists.txt +++ b/test/people/CMakeLists.txt @@ -10,7 +10,6 @@ if(NOT build) return() endif() -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) PCL_ADD_TEST(a_people_detection_test test_people_detection FILES test_people_groundBasedPeopleDetectionApp.cpp LINK_WITH pcl_gtest pcl_common pcl_io pcl_kdtree pcl_search pcl_features pcl_sample_consensus pcl_filters pcl_segmentation pcl_people diff --git a/tracking/CMakeLists.txt b/tracking/CMakeLists.txt index 78109d9724d..cd1fb8777a8 100644 --- a/tracking/CMakeLists.txt +++ b/tracking/CMakeLists.txt @@ -51,7 +51,6 @@ 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_common pcl_kdtree pcl_search pcl_filters pcl_octree) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index a629b4cc897..8446cb4f31d 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -11,9 +11,6 @@ if(ANDROID) endif() if(OPENGL_FOUND) - if(OPENGL_INCLUDE_DIR) - include_directories(SYSTEM "${OPENGL_INCLUDE_DIR}") - endif() if(OPENGL_DEFINITIONS) add_definitions("${OPENGL_DEFINITIONS}") endif() @@ -138,11 +135,6 @@ endif() set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${common_incs} ${impl_incs} ${common_impl_incs} ${vtk_incs}) -target_include_directories(${LIB_NAME} PUBLIC - $ - $ -) - # apple workaround (continued) if(APPLE) target_link_libraries("${LIB_NAME}" "-framework Cocoa") From 7234ee75fce64bd15376c696d46a70594fc826f2 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 18 Apr 2024 13:49:53 +0200 Subject: [PATCH 230/288] Enable compatibility with Boost 1.85.0 --- cmake/Modules/AdditionalBoostVersions.cmake | 1 + outofcore/include/pcl/outofcore/octree_base.h | 1 + outofcore/include/pcl/outofcore/octree_base_node.h | 1 + .../recognition/face_detection/face_detector_data_provider.h | 2 +- test/outofcore/test_outofcore.cpp | 1 + 5 files changed, 5 insertions(+), 1 deletion(-) diff --git a/cmake/Modules/AdditionalBoostVersions.cmake b/cmake/Modules/AdditionalBoostVersions.cmake index a4698e0061a..0a06d08d0eb 100644 --- a/cmake/Modules/AdditionalBoostVersions.cmake +++ b/cmake/Modules/AdditionalBoostVersions.cmake @@ -1,5 +1,6 @@ set(Boost_ADDITIONAL_VERSIONS + "1.85.0" "1.85" "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" diff --git a/outofcore/include/pcl/outofcore/octree_base.h b/outofcore/include/pcl/outofcore/octree_base.h index 45959b95236..1a7c8778c10 100644 --- a/outofcore/include/pcl/outofcore/octree_base.h +++ b/outofcore/include/pcl/outofcore/octree_base.h @@ -63,6 +63,7 @@ #include #include +#include namespace pcl { diff --git a/outofcore/include/pcl/outofcore/octree_base_node.h b/outofcore/include/pcl/outofcore/octree_base_node.h index 7085d530227..dba76d4f04f 100644 --- a/outofcore/include/pcl/outofcore/octree_base_node.h +++ b/outofcore/include/pcl/outofcore/octree_base_node.h @@ -42,6 +42,7 @@ #include #include #include +#include #include #include diff --git a/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h b/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h index 7b4a929df52..be3b86aecc1 100644 --- a/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h +++ b/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h @@ -12,7 +12,7 @@ #include #include -#include +#include #include #include diff --git a/test/outofcore/test_outofcore.cpp b/test/outofcore/test_outofcore.cpp index cb5cfff4aca..3f658bf86ea 100644 --- a/test/outofcore/test_outofcore.cpp +++ b/test/outofcore/test_outofcore.cpp @@ -44,6 +44,7 @@ #include +#include #include #include #include From 208c74f74fadf51aedbb04803295d792c876b09b Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Fri, 19 Apr 2024 16:07:40 +0200 Subject: [PATCH 231/288] Revert "Update system wide include for metslib." This reverts commit b881de693ec19b34a549be5078c57f6a3caff196. --- CMakeLists.txt | 5 +++++ recognition/CMakeLists.txt | 7 ------- recognition/include/pcl/recognition/hv/hv_go.h | 3 +-- 3 files changed, 6 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index cee13e6a8e6..705ade21b65 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -354,7 +354,12 @@ if(PKG_CONFIG_FOUND) pkg_check_modules(METSLIB metslib) if(METSLIB_FOUND) set(HAVE_METSLIB ON) + include_directories(SYSTEM ${METSLIB_INCLUDE_DIRS}) + else() + include_directories(SYSTEM "${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/") endif() +else() + include_directories(SYSTEM ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/) endif() # LibPNG diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 2cda7232be4..168297cd0e7 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -161,13 +161,6 @@ 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} ${face_detection_incs} ${ransac_based_incs} ${ransac_based_impl_incs} ${hv_incs} ${hv_impl_incs} ${cg_incs} ${cg_impl_incs} ${metslib_incs}) target_link_libraries("${LIB_NAME}" pcl_common pcl_kdtree pcl_octree pcl_search pcl_features pcl_registration pcl_sample_consensus pcl_filters pcl_ml pcl_io) - -if(HAVE_METSLIB) - target_include_directories(${LIB_NAME} SYSTEM PUBLIC ${METSLIB_INCLUDE_DIRS}) -else() - target_include_directories(${LIB_NAME} SYSTEM PUBLIC ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/) -endif() - PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) # Install include files PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) diff --git a/recognition/include/pcl/recognition/hv/hv_go.h b/recognition/include/pcl/recognition/hv/hv_go.h index 3a5e575ec4e..e4bbf1b9201 100644 --- a/recognition/include/pcl/recognition/hv/hv_go.h +++ b/recognition/include/pcl/recognition/hv/hv_go.h @@ -19,10 +19,9 @@ #include #include +#include #include -#include // Either include 3.party in pcl/recognition/3rdparty or system installed metslib - #include namespace pcl From b75637d2d0c7bd33251f5e441bb0d4047c49440b Mon Sep 17 00:00:00 2001 From: Johan Mattsson <39247600+mjunix@users.noreply.github.com> Date: Sun, 21 Apr 2024 11:24:30 +0200 Subject: [PATCH 232/288] Fix potential index out of bounds --- io/src/image_grabber.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/io/src/image_grabber.cpp b/io/src/image_grabber.cpp index 2ce2e3dfa47..780b9fa5255 100644 --- a/io/src/image_grabber.cpp +++ b/io/src/image_grabber.cpp @@ -612,7 +612,7 @@ pcl::ImageGrabberBase::ImageGrabberImpl::getCloudPCLZF (std::size_t idx, double &cx, double &cy) const { - if (idx > depth_pclzf_files_.size ()) + if (idx >= depth_pclzf_files_.size ()) { return (false); } From cdc0a4288de16055e872d7f60958fcecb3be1d27 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 21 Apr 2024 15:57:51 +0200 Subject: [PATCH 233/288] Add CMake option --- cmake/pcl_options.cmake | 3 +++ common/include/pcl/common/pcl_filesystem.h | 2 ++ pcl_config.h.in | 2 ++ 3 files changed, 7 insertions(+) diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index 7955f1171e0..1911fdf8a82 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -45,6 +45,9 @@ set(PCL_QHULL_REQUIRED_TYPE "DONTCARE" CACHE STRING "Select build type to use ST set_property(CACHE PCL_QHULL_REQUIRED_TYPE PROPERTY STRINGS DONTCARE SHARED STATIC) mark_as_advanced(PCL_QHULL_REQUIRED_TYPE) +option(PCL_PREFER_BOOST_FILESYSTEM "Prefer boost::filesystem over std::filesystem (if compiled as C++17 or higher, std::filesystem is chosen by default)" OFF) +mark_as_advanced(PCL_PREFER_BOOST_FILESYSTEM) + # Precompile for a minimal set of point types instead of all. option(PCL_ONLY_CORE_POINT_TYPES "Compile explicitly only for a small subset of point types (e.g., pcl::PointXYZ instead of PCL_XYZ_POINT_TYPES)." OFF) mark_as_advanced(PCL_ONLY_CORE_POINT_TYPES) diff --git a/common/include/pcl/common/pcl_filesystem.h b/common/include/pcl/common/pcl_filesystem.h index 90e4fa22e6a..eb6c4140353 100644 --- a/common/include/pcl/common/pcl_filesystem.h +++ b/common/include/pcl/common/pcl_filesystem.h @@ -38,6 +38,8 @@ #pragma once +#include // for PCL_PREFER_BOOST_FILESYSTEM + #if (__cplusplus >= 201703L) && !defined(PCL_PREFER_BOOST_FILESYSTEM) #define PCL_USING_STD_FILESYSTEM #include diff --git a/pcl_config.h.in b/pcl_config.h.in index 5f96e2faeaa..1a7f843f49a 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -54,6 +54,8 @@ #cmakedefine HAVE_ZLIB +#cmakedefine PCL_PREFER_BOOST_FILESYSTEM + /* Precompile for a minimal set of point types instead of all. */ #cmakedefine PCL_ONLY_CORE_POINT_TYPES From 6be79ec6ec2d7fe429a7f9e9f2fd13efd452ed75 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 21 Apr 2024 16:20:13 +0200 Subject: [PATCH 234/288] Fix ABI compatibility problems for 1.14.1 release Partially revert https://github.com/PointCloudLibrary/pcl/pull/5974 and https://github.com/PointCloudLibrary/pcl/pull/5988 and https://github.com/PointCloudLibrary/pcl/pull/5907 After the 1.14.1 release, we can re-apply these changes. The ABI checker reported: `The parameter file_name became passed in r12 register instead of r13. Applications will read the wrong memory block instead of the parameter value.` and `The parameter cloud_tgt_demean became passed in r12 register instead of r13.` These changes are not super important, so I think it doesn't hurt to temporarily revert them to achieve 100% ABI compatibility between 1.14.0 and 1.14.1. --- io/src/obj_io.cpp | 4 ++-- io/src/pcd_io.cpp | 8 +------- .../registration/impl/transformation_estimation_svd.hpp | 2 +- 3 files changed, 4 insertions(+), 10 deletions(-) diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 19d454e120b..e00ab14409a 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -711,8 +711,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments and lines with only whitespace - if (st.empty() || st[0] == "#") + // Ignore comments + if (st[0] == "#") continue; // Vertex if (st[0] == "v") diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 767f65e7d4b..e2333786d7b 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -677,13 +677,7 @@ pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, pcl::console::TicToc tt; tt.tic (); - if (file_name.empty ()) - { - PCL_ERROR ("[pcl::PCDReader::read] No file name given!\n"); - return (-1); - } - - if (!pcl_fs::exists (file_name)) + if (file_name.empty () || !pcl_fs::exists (file_name)) { PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ()); return (-1); diff --git a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp index 8ebb59b5770..7b2e22f5205 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp @@ -211,7 +211,7 @@ TransformationEstimationSVD:: Eigen::Matrix R = v * u.transpose(); // Return the correct transformation - transformation_matrix.template topLeftCorner<3, 3>() = R; + transformation_matrix.topLeftCorner(3, 3) = R; const Eigen::Matrix Rc(R * centroid_src.template head<3>()); transformation_matrix.template block<3, 1>(0, 3) = centroid_tgt.template head<3>() - Rc; From 56487fd023f453ceb0b8b47ded2bae17218e6385 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 22 Apr 2024 12:59:52 +0200 Subject: [PATCH 235/288] Support header only libraries like 2d and geometry. --- 2d/CMakeLists.txt | 1 + cmake/pcl_targets.cmake | 61 ++++++++++++++++++++++++----------------- geometry/CMakeLists.txt | 3 +- 3 files changed, 38 insertions(+), 27 deletions(-) diff --git a/2d/CMakeLists.txt b/2d/CMakeLists.txt index 457aae7dbcf..f2656b2f475 100644 --- a/2d/CMakeLists.txt +++ b/2d/CMakeLists.txt @@ -30,6 +30,7 @@ set(impl_incs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") +PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME}) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY) #Install include files diff --git a/cmake/pcl_targets.cmake b/cmake/pcl_targets.cmake index f3ca56d1c54..c8cdbcb1c76 100644 --- a/cmake/pcl_targets.cmake +++ b/cmake/pcl_targets.cmake @@ -192,38 +192,49 @@ function(PCL_ADD_LIBRARY _name) message(FATAL_ERROR "PCL_ADD_LIBRARY requires parameter COMPONENT.") endif() - add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES}) - PCL_ADD_VERSION_INFO(${_name}) - target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES}) + if(NOT ARGS_SOURCES) + add_library(${_name} INTERFACE) + + target_include_directories(${_name} INTERFACE + $ + $ + ) - target_include_directories(${_name} PUBLIC - $ - $ - ) + else() + add_library(${_name} ${PCL_LIB_TYPE} ${ARGS_SOURCES}) + PCL_ADD_VERSION_INFO(${_name}) + target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES}) + + target_include_directories(${_name} PUBLIC + $ + $ + ) + + target_link_libraries(${_name} Threads::Threads) + if(TARGET OpenMP::OpenMP_CXX) + target_link_libraries(${_name} OpenMP::OpenMP_CXX) + endif() - target_link_libraries(${_name} Threads::Threads) - if(TARGET OpenMP::OpenMP_CXX) - target_link_libraries(${_name} OpenMP::OpenMP_CXX) - endif() + if((UNIX AND NOT ANDROID) OR MINGW) + target_link_libraries(${_name} m ${ATOMIC_LIBRARY}) + endif() - if((UNIX AND NOT ANDROID) OR MINGW) - target_link_libraries(${_name} m ${ATOMIC_LIBRARY}) - endif() + if(MINGW) + target_link_libraries(${_name} gomp) + endif() - if(MINGW) - target_link_libraries(${_name} gomp) - endif() + if(MSVC) + target_link_libraries(${_name} delayimp.lib) # because delay load is enabled for openmp.dll + endif() + + set_target_properties(${_name} PROPERTIES + VERSION ${PCL_VERSION} + SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR} + DEFINE_SYMBOL "PCLAPI_EXPORTS") - if(MSVC) - target_link_libraries(${_name} delayimp.lib) # because delay load is enabled for openmp.dll + set_target_properties(${_name} PROPERTIES FOLDER "Libraries") endif() - set_target_properties(${_name} PROPERTIES - VERSION ${PCL_VERSION} - SOVERSION ${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR} - DEFINE_SYMBOL "PCLAPI_EXPORTS") - set_target_properties(${_name} PROPERTIES FOLDER "Libraries") - install(TARGETS ${_name} RUNTIME DESTINATION ${BIN_INSTALL_DIR} COMPONENT pcl_${ARGS_COMPONENT} LIBRARY DESTINATION ${LIB_INSTALL_DIR} COMPONENT pcl_${ARGS_COMPONENT} diff --git a/geometry/CMakeLists.txt b/geometry/CMakeLists.txt index 2e0a9ee58b8..54929f709b9 100644 --- a/geometry/CMakeLists.txt +++ b/geometry/CMakeLists.txt @@ -37,8 +37,7 @@ set(impl_incs set(LIB_NAME "pcl_${SUBSYS_NAME}") - -add_library(${LIB_NAME} INTERFACE) +PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME}) target_link_libraries(${LIB_NAME} INTERFACE Boost::boost pcl_common) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS} HEADER_ONLY) From ce2ca5c987f4dd866978d3d900e79bf2c5798316 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Tue, 23 Apr 2024 19:35:42 +0200 Subject: [PATCH 236/288] Add changelog for 1.14.1 --- CHANGES.md | 75 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 75 insertions(+) diff --git a/CHANGES.md b/CHANGES.md index 1faa1b86236..78e8e29e8a7 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -1,5 +1,80 @@ # ChangeList +## = 1.14.1 (01 May 2024) = + +### Notable changes + +**New features** *added to PCL* + +* **[cmake]** Make Boost filesystem optional for C++17 [[#5937](https://github.com/PointCloudLibrary/pcl/pull/5937)] +* **[common]** Enhance toPCLPointCloud2 to remove padding on request [[#5913](https://github.com/PointCloudLibrary/pcl/pull/5913)] +* **[io]** Enable writing data in binary PLY format to std::ostream [[#5975](https://github.com/PointCloudLibrary/pcl/pull/5975)] + +### Changes grouped by module + +#### CMake: + +* Switch latest Ubuntu CI to C++17 [[#5931](https://github.com/PointCloudLibrary/pcl/pull/5931)] +* **[new feature]** Make Boost filesystem optional for C++17 [[#5937](https://github.com/PointCloudLibrary/pcl/pull/5937)] +* Add OpenGL_GLU as external dependency. [[#5963](https://github.com/PointCloudLibrary/pcl/pull/5963)] +* Preparation for default hidden visibility on gcc [[#5970](https://github.com/PointCloudLibrary/pcl/pull/5970)] +* Cmake cuda find_package cuda is deprecated. [[#5953](https://github.com/PointCloudLibrary/pcl/pull/5953)] +* fix build with CUDA [[#5976](https://github.com/PointCloudLibrary/pcl/pull/5976)] +* Enable compatibility with Boost 1.85.0 [[#6014](https://github.com/PointCloudLibrary/pcl/pull/6014)] + +#### libpcl_common: + +* Rename variables with reserved names (PointXYZLAB) [[#5951](https://github.com/PointCloudLibrary/pcl/pull/5951)] +* **[new feature]** Enhance toPCLPointCloud2 to remove padding on request [[#5913](https://github.com/PointCloudLibrary/pcl/pull/5913)] +* Fix behaviour of eigen33 function if smallest eigenvalue is not unique [[#5956](https://github.com/PointCloudLibrary/pcl/pull/5956)] +* Add option to choose boost filesystem over std filesystem [[#6005](https://github.com/PointCloudLibrary/pcl/pull/6005)] + +#### libpcl_filters: + +* Fix Bug in NormalSpaceSampling::findBin() [[#5936](https://github.com/PointCloudLibrary/pcl/pull/5936)] +* VoxelGridOcclusionEstimation should always round down to go from coordinates to voxel indices. [[#5942](https://github.com/PointCloudLibrary/pcl/pull/5942)] +* StatisticalOutlierRemoval: fix potential container overflow read [[#5980](https://github.com/PointCloudLibrary/pcl/pull/5980)] +* fixing ignored `pcl::Indices` in `VoxelGrid` of `PCLPointCloud2` [[#5979](https://github.com/PointCloudLibrary/pcl/pull/5979)] + +#### libpcl_gpu: + +* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)] + +#### libpcl_io: + +* Real Sense 2 grabber stream fix [[#5912](https://github.com/PointCloudLibrary/pcl/pull/5912)] +* Improve documentation in vtk_lib_io [[#5955](https://github.com/PointCloudLibrary/pcl/pull/5955)] +* Add special implementation for raw_fallocate for OpenBSD [[#5957](https://github.com/PointCloudLibrary/pcl/pull/5957)] +* Fix missing include in ply_parser.h (#5962) [[#5964](https://github.com/PointCloudLibrary/pcl/pull/5964)] +* **[new feature]** Enable writing data in binary PLY format to std::ostream [[#5975](https://github.com/PointCloudLibrary/pcl/pull/5975)] +* OBJReader: fix possible out-of-bounds access [[#5988](https://github.com/PointCloudLibrary/pcl/pull/5988)] +* ImageGrabber: Fix potential index out of bounds [[#6016](https://github.com/PointCloudLibrary/pcl/pull/6016)] + +#### libpcl_registration: + +* NDT: allow access to target cloud distribution [[#5969](https://github.com/PointCloudLibrary/pcl/pull/5969)] +* Optimize Eigen block operations [[#5974](https://github.com/PointCloudLibrary/pcl/pull/5974)] + +#### libpcl_sample_consensus: + +* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)] + +#### libpcl_surface: + +* Add `pcl::PointXYZLNormal` to GP3 PCL_INSTANTIATE (#5981) [[#5983](https://github.com/PointCloudLibrary/pcl/pull/5983)] + +#### libpcl_visualization: + +* Add missing PCL_EXPORTS (economical_download, optimizeModelCoefficients, vtkRenderWindowInteractorFixNew) [[#5926](https://github.com/PointCloudLibrary/pcl/pull/5926)] +* Add missing pragma once in qvtk_compatibility.h [[#5943](https://github.com/PointCloudLibrary/pcl/pull/5943)] +* fixed setShapeRenderingProperties(PCL_VISUALIZER_FONT_SIZE) [[#5993](https://github.com/PointCloudLibrary/pcl/pull/5993)] +* fix addPolygon and addLine return value error [[#5996](https://github.com/PointCloudLibrary/pcl/pull/5996)] + +#### CI: + +* Switch latest Ubuntu CI to C++17 [[#5931](https://github.com/PointCloudLibrary/pcl/pull/5931)] +* Fix ubuntu-variety CI and update compilers [[#5990](https://github.com/PointCloudLibrary/pcl/pull/5990)] + ## = 1.14.0 (03 January 2024) = ### Notable changes From b380e214de525bca85193ff14cdae70fda36afa1 Mon Sep 17 00:00:00 2001 From: qipaifeiying <1752669709@qq.com> Date: Mon, 29 Apr 2024 17:32:32 +0800 Subject: [PATCH 237/288] Add to convolution_3d.h and add to convolution_3d.hpp --- filters/include/pcl/filters/convolution_3d.h | 1 + filters/include/pcl/filters/impl/convolution_3d.hpp | 1 + 2 files changed, 2 insertions(+) diff --git a/filters/include/pcl/filters/convolution_3d.h b/filters/include/pcl/filters/convolution_3d.h index bb701725713..ee03fdad0cf 100644 --- a/filters/include/pcl/filters/convolution_3d.h +++ b/filters/include/pcl/filters/convolution_3d.h @@ -41,6 +41,7 @@ #include #include +#include namespace pcl { diff --git a/filters/include/pcl/filters/impl/convolution_3d.hpp b/filters/include/pcl/filters/impl/convolution_3d.hpp index f3901fca524..ba5feca8ad0 100644 --- a/filters/include/pcl/filters/impl/convolution_3d.hpp +++ b/filters/include/pcl/filters/impl/convolution_3d.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include From 037ca5a09ba1ea19e5afeb5e809374f437a80ea7 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 3 May 2024 14:13:48 +0200 Subject: [PATCH 238/288] Bump version to 1.14.1 --- CHANGES.md | 2 +- CMakeLists.txt | 2 +- README.md | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGES.md b/CHANGES.md index 78e8e29e8a7..6e63b224879 100644 --- a/CHANGES.md +++ b/CHANGES.md @@ -1,6 +1,6 @@ # ChangeList -## = 1.14.1 (01 May 2024) = +## = 1.14.1 (03 May 2024) = ### Notable changes diff --git a/CMakeLists.txt b/CMakeLists.txt index 705ade21b65..41fb8120dcf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.14.0.99) +project(PCL VERSION 1.14.1) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) diff --git a/README.md b/README.md index 08318ebf317..0fca1a92726 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ [![Release][release-image]][releases] [![License][license-image]][license] -[release-image]: https://img.shields.io/badge/release-1.14.0-green.svg?style=flat +[release-image]: https://img.shields.io/badge/release-1.14.1-green.svg?style=flat [releases]: https://github.com/PointCloudLibrary/pcl/releases [license-image]: https://img.shields.io/badge/license-BSD-green.svg?style=flat From 089b17632f8edcce6ee981917478335262394674 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 3 May 2024 17:40:01 +0200 Subject: [PATCH 239/288] Bump version to 1.14.1.99 post release --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 41fb8120dcf..1741d73e20e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -23,7 +23,7 @@ if("${CMAKE_BUILD_TYPE}" STREQUAL "") set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "build type default to RelWithDebInfo, set to Release to improve performance" FORCE) endif() -project(PCL VERSION 1.14.1) +project(PCL VERSION 1.14.1.99) string(TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) if(MSVC AND ("${MSVC_VERSION}" LESS 1910)) From 38ab31e7ae74cdae58b5861ac1cdd40cd48986c8 Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Sat, 4 May 2024 12:14:43 +0200 Subject: [PATCH 240/288] Revert "Fix ABI compatibility problems for 1.14.1 release" --- io/src/obj_io.cpp | 4 ++-- io/src/pcd_io.cpp | 8 +++++++- .../registration/impl/transformation_estimation_svd.hpp | 2 +- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index e00ab14409a..19d454e120b 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -711,8 +711,8 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, // Tokenize the line pcl::split (st, line, "\t\r "); - // Ignore comments - if (st[0] == "#") + // Ignore comments and lines with only whitespace + if (st.empty() || st[0] == "#") continue; // Vertex if (st[0] == "v") diff --git a/io/src/pcd_io.cpp b/io/src/pcd_io.cpp index 0bb600a58a5..a7fc6860767 100644 --- a/io/src/pcd_io.cpp +++ b/io/src/pcd_io.cpp @@ -677,7 +677,13 @@ pcl::PCDReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, pcl::console::TicToc tt; tt.tic (); - if (file_name.empty () || !pcl_fs::exists (file_name)) + if (file_name.empty ()) + { + PCL_ERROR ("[pcl::PCDReader::read] No file name given!\n"); + return (-1); + } + + if (!pcl_fs::exists (file_name)) { PCL_ERROR ("[pcl::PCDReader::read] Could not find file '%s'.\n", file_name.c_str ()); return (-1); diff --git a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp index 7b2e22f5205..8ebb59b5770 100644 --- a/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp +++ b/registration/include/pcl/registration/impl/transformation_estimation_svd.hpp @@ -211,7 +211,7 @@ TransformationEstimationSVD:: Eigen::Matrix R = v * u.transpose(); // Return the correct transformation - transformation_matrix.topLeftCorner(3, 3) = R; + transformation_matrix.template topLeftCorner<3, 3>() = R; const Eigen::Matrix Rc(R * centroid_src.template head<3>()); transformation_matrix.template block<3, 1>(0, 3) = centroid_tgt.template head<3>() - Rc; From 9b041a0f319802132ae3e759b9ff7a364e4b6abe Mon Sep 17 00:00:00 2001 From: Kino Date: Sun, 5 May 2024 16:24:25 +0800 Subject: [PATCH 241/288] C++17 filesystem for recognition module (#5935) * C++17 filesystem for recognition module * Replace with pcl_filesystem.h --- .../face_detection/face_detector_data_provider.h | 12 +++++------- .../face_detection/face_detector_data_provider.cpp | 2 +- 2 files changed, 6 insertions(+), 8 deletions(-) diff --git a/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h b/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h index be3b86aecc1..6bf66dc9abe 100644 --- a/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h +++ b/recognition/include/pcl/recognition/face_detection/face_detector_data_provider.h @@ -7,19 +7,17 @@ #pragma once +#include #include #include #include #include -#include #include #include -namespace bf = boost::filesystem; - namespace pcl { namespace face_detection @@ -35,15 +33,15 @@ namespace pcl int patches_per_image_; int min_images_per_bin_; - void getFilesInDirectory(bf::path & dir, std::string & rel_path_so_far, std::vector & relative_paths, std::string & ext) + void getFilesInDirectory(pcl_fs::path & dir, std::string & rel_path_so_far, std::vector & relative_paths, std::string & ext) { - for (const auto& dir_entry : bf::directory_iterator(dir)) + for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) { //check if its a directory, then get models in it - if (bf::is_directory (dir_entry)) + if (pcl_fs::is_directory (dir_entry)) { std::string so_far = rel_path_so_far + (dir_entry.path ().filename ()).string () + "/"; - bf::path curr_path = dir_entry.path (); + pcl_fs::path curr_path = dir_entry.path (); getFilesInDirectory (curr_path, so_far, relative_paths, ext); } else { diff --git a/recognition/src/face_detection/face_detector_data_provider.cpp b/recognition/src/face_detection/face_detector_data_provider.cpp index f2b7ab62520..c6baab4b911 100644 --- a/recognition/src/face_detection/face_detector_data_provider.cpp +++ b/recognition/src/face_detection/face_detector_data_provider.cpp @@ -50,7 +50,7 @@ void pcl::face_detection::FaceDetectorDataProvider files; getFilesInDirectory (dir, start, files, ext); From eb76a6ea5f6b292e9c2bacb48e9ebdc382f4aebb Mon Sep 17 00:00:00 2001 From: Haidar Obeid <110574820+ufrhaidar@users.noreply.github.com> Date: Sun, 5 May 2024 18:26:58 +1000 Subject: [PATCH 242/288] UniformSampling Filter | add a minimum number of points required for a voxel option (#5968) * add a minimum number of points required for a voxel option * fix documentation and variable type * resize output --- .../include/pcl/filters/impl/uniform_sampling.hpp | 13 ++++++++++--- filters/include/pcl/filters/uniform_sampling.h | 15 +++++++++++++++ 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/filters/include/pcl/filters/impl/uniform_sampling.hpp b/filters/include/pcl/filters/impl/uniform_sampling.hpp index a46902c4704..f9ceb77563a 100644 --- a/filters/include/pcl/filters/impl/uniform_sampling.hpp +++ b/filters/include/pcl/filters/impl/uniform_sampling.hpp @@ -104,6 +104,10 @@ pcl::UniformSampling::applyFilter (PointCloud &output) // Compute the leaf index int idx = (ijk - min_b_).dot (divb_mul_); Leaf& leaf = leaves_[idx]; + + // Increment the count of points in this voxel + ++leaf.count; + // First time we initialize the index if (leaf.idx == -1) { @@ -134,11 +138,14 @@ pcl::UniformSampling::applyFilter (PointCloud &output) // Second pass: go over all leaves and copy data output.resize (leaves_.size ()); - int cp = 0; + std::size_t cp = 0; for (const auto& leaf : leaves_) - output[cp++] = (*input_)[leaf.second.idx]; - output.width = output.size (); + { + if (leaf.second.count >= min_points_per_voxel_) + output[cp++] = (*input_)[leaf.second.idx]; + } + output.resize (cp); } #define PCL_INSTANTIATE_UniformSampling(T) template class PCL_EXPORTS pcl::UniformSampling; diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index 39d0815d32a..42f5febd804 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -108,12 +108,24 @@ namespace pcl search_radius_ = radius; } + /** \brief Set the minimum number of points required for a voxel to be used. + * \param[in] min_points_per_voxel the minimum number of points for required for a voxel to be used + */ + inline void + setMinimumPointsNumberPerVoxel (unsigned int min_points_per_voxel) { min_points_per_voxel_ = min_points_per_voxel; } + + /** \brief Return the minimum number of points required for a voxel to be used. + */ + inline unsigned int + getMinimumPointsNumberPerVoxel () const { return min_points_per_voxel_; } + protected: /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */ struct Leaf { Leaf () = default; int idx{-1}; + unsigned int count{0}; }; /** \brief The 3D grid leaves. */ @@ -131,6 +143,9 @@ namespace pcl /** \brief The nearest neighbors search radius for each point. */ double search_radius_{0.0}; + /** \brief Minimum number of points per voxel. */ + unsigned int min_points_per_voxel_{0}; + /** \brief Downsample a Point Cloud using a voxelized grid approach * \param[out] output the resultant point cloud message */ From 91bc0fdb713a9b55f4c1e24a535d374b663cf614 Mon Sep 17 00:00:00 2001 From: koide3 <31344317+koide3@users.noreply.github.com> Date: Sun, 5 May 2024 17:32:44 +0900 Subject: [PATCH 243/288] [registration] Add OMP based Multi-threading to IterativeClosestPoint (#4520) * Make ICP multi-threaded * Use unsigned int for num_threads_ * Keep correspondences ordered with inplace_merge * Apply clang-format to correspondence_estimation.(h|hpp) and icp.h * Use move and emplace_back * remove unnecessary include * Resolve omp build errors on gcc (Class members cannot be shared variables) * Wrap omp_get_thread_num() in ifdef _OPENMP * Formatting * Remove std::move per clang-tidy suggestion * Fix typo --------- Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- .../registration/correspondence_estimation.h | 22 ++++ registration/include/pcl/registration/icp.h | 10 ++ .../impl/correspondence_estimation.hpp | 100 +++++++++++++++--- 3 files changed, 120 insertions(+), 12 deletions(-) diff --git a/registration/include/pcl/registration/correspondence_estimation.h b/registration/include/pcl/registration/correspondence_estimation.h index bb1db6aab3a..d8c66b050fd 100644 --- a/registration/include/pcl/registration/correspondence_estimation.h +++ b/registration/include/pcl/registration/correspondence_estimation.h @@ -137,6 +137,23 @@ class CorrespondenceEstimationBase : public PCLBase { return (target_); } + /** \brief Set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to + * automatic) + */ + void + setNumberOfThreads(unsigned int nr_threads) + { +#ifdef _OPENMP + num_threads_ = nr_threads != 0 ? nr_threads : omp_get_num_procs(); +#else + if (nr_threads != 1) { + PCL_WARN("OpenMP is not available. Keeping number of threads unchanged at 1\n"); + } + num_threads_ = 1; +#endif + } + /** \brief See if this rejector requires source normals */ virtual bool requiresSourceNormals() const @@ -362,6 +379,8 @@ class CorrespondenceEstimationBase : public PCLBase { /** \brief A flag which, if set, means the tree operating on the source cloud * will never be recomputed*/ bool force_no_recompute_reciprocal_{false}; + + unsigned int num_threads_{1}; }; /** \brief @b CorrespondenceEstimation represents the base class for @@ -479,6 +498,9 @@ class CorrespondenceEstimation Ptr copy(new CorrespondenceEstimation(*this)); return (copy); } + +protected: + using CorrespondenceEstimationBase::num_threads_; }; } // namespace registration } // namespace pcl diff --git a/registration/include/pcl/registration/icp.h b/registration/include/pcl/registration/icp.h index 8127b10d029..dbba310952a 100644 --- a/registration/include/pcl/registration/icp.h +++ b/registration/include/pcl/registration/icp.h @@ -261,6 +261,16 @@ class IterativeClosestPoint : public RegistrationsetNumberOfThreads(nr_threads); + } + protected: /** \brief Apply a rigid transform to a given dataset. Here we check whether * the dataset has surface normals in addition to XYZ, and rotate normals as well. diff --git a/registration/include/pcl/registration/impl/correspondence_estimation.hpp b/registration/include/pcl/registration/impl/correspondence_estimation.hpp index 50eb5b0fc66..e21b1ffdd95 100644 --- a/registration/include/pcl/registration/impl/correspondence_estimation.hpp +++ b/registration/include/pcl/registration/impl/correspondence_estimation.hpp @@ -153,12 +153,18 @@ CorrespondenceEstimation::determineCorresponde pcl::Indices index(1); std::vector distance(1); - pcl::Correspondence corr; - unsigned int nr_valid_correspondences = 0; + std::vector per_thread_correspondences(num_threads_); + for (auto& corrs : per_thread_correspondences) { + corrs.reserve(2 * indices_->size() / num_threads_); + } double max_dist_sqr = max_distance * max_distance; +#pragma omp parallel for default(none) \ + shared(max_dist_sqr, per_thread_correspondences) firstprivate(index, distance) \ + num_threads(num_threads_) // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { + for (int i = 0; i < static_cast(indices_->size()); i++) { + const auto& idx = (*indices_)[i]; // Check if the template types are the same. If true, avoid a copy. // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT // macro! @@ -167,13 +173,44 @@ CorrespondenceEstimation::determineCorresponde if (distance[0] > max_dist_sqr) continue; + pcl::Correspondence corr; corr.index_query = idx; corr.index_match = index[0]; corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; + +#ifdef _OPENMP + const int thread_num = omp_get_thread_num(); +#else + const int thread_num = 0; +#endif + + per_thread_correspondences[thread_num].emplace_back(corr); } - correspondences.resize(nr_valid_correspondences); + if (num_threads_ == 1) { + correspondences = std::move(per_thread_correspondences.front()); + } + else { + const unsigned int nr_correspondences = std::accumulate( + per_thread_correspondences.begin(), + per_thread_correspondences.end(), + static_cast(0), + [](const auto sum, const auto& corr) { return sum + corr.size(); }); + correspondences.resize(nr_correspondences); + + // Merge per-thread correspondences while keeping them ordered + auto insert_loc = correspondences.begin(); + for (const auto& corrs : per_thread_correspondences) { + const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc); + std::inplace_merge(correspondences.begin(), + insert_loc, + insert_loc + corrs.size(), + [](const auto& lhs, const auto& rhs) { + return lhs.index_query < rhs.index_query; + }); + insert_loc = new_insert_loc; + } + } deinitCompute(); } @@ -197,12 +234,18 @@ CorrespondenceEstimation:: std::vector distance(1); pcl::Indices index_reciprocal(1); std::vector distance_reciprocal(1); - pcl::Correspondence corr; - unsigned int nr_valid_correspondences = 0; - int target_idx = 0; + std::vector per_thread_correspondences(num_threads_); + for (auto& corrs : per_thread_correspondences) { + corrs.reserve(2 * indices_->size() / num_threads_); + } +#pragma omp parallel for default(none) \ + shared(max_dist_sqr, per_thread_correspondences) \ + firstprivate(index, distance, index_reciprocal, distance_reciprocal) \ + num_threads(num_threads_) // Iterate over the input set of source indices - for (const auto& idx : (*indices_)) { + for (int i = 0; i < static_cast(indices_->size()); i++) { + const auto& idx = (*indices_)[i]; // Check if the template types are the same. If true, avoid a copy. // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT // macro! @@ -213,7 +256,7 @@ CorrespondenceEstimation:: if (distance[0] > max_dist_sqr) continue; - target_idx = index[0]; + const auto target_idx = index[0]; const auto& pt_tgt = detail::pointCopyOrRef(target_, target_idx); @@ -221,12 +264,45 @@ CorrespondenceEstimation:: if (distance_reciprocal[0] > max_dist_sqr || idx != index_reciprocal[0]) continue; + pcl::Correspondence corr; corr.index_query = idx; corr.index_match = index[0]; corr.distance = distance[0]; - correspondences[nr_valid_correspondences++] = corr; + +#ifdef _OPENMP + const int thread_num = omp_get_thread_num(); +#else + const int thread_num = 0; +#endif + + per_thread_correspondences[thread_num].emplace_back(corr); + } + + if (num_threads_ == 1) { + correspondences = std::move(per_thread_correspondences.front()); + } + else { + const unsigned int nr_correspondences = std::accumulate( + per_thread_correspondences.begin(), + per_thread_correspondences.end(), + static_cast(0), + [](const auto sum, const auto& corr) { return sum + corr.size(); }); + correspondences.resize(nr_correspondences); + + // Merge per-thread correspondences while keeping them ordered + auto insert_loc = correspondences.begin(); + for (const auto& corrs : per_thread_correspondences) { + const auto new_insert_loc = std::move(corrs.begin(), corrs.end(), insert_loc); + std::inplace_merge(correspondences.begin(), + insert_loc, + insert_loc + corrs.size(), + [](const auto& lhs, const auto& rhs) { + return lhs.index_query < rhs.index_query; + }); + insert_loc = new_insert_loc; + } } - correspondences.resize(nr_valid_correspondences); + deinitCompute(); } From 014bf309ec6134787d20f7c9393ea899676dcd60 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Sun, 5 May 2024 16:01:26 +0200 Subject: [PATCH 244/288] Updated 23.04 to 24.04 for docker images. (#6028) * Updated 23.04 to 24.04. --- .ci/azure-pipelines/env.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index a6559a22301..60d24e9eb73 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -46,16 +46,16 @@ jobs: UBUNTU_VERSION: 20.04 VTK_VERSION: 7 TAG: 20.04 - # Test the latest LTS version of Ubuntu Ubuntu 22.04: UBUNTU_VERSION: 22.04 VTK_VERSION: 9 TAG: 22.04 - Ubuntu 23.04: - UBUNTU_VERSION: 23.04 + # Test the latest LTS version of Ubuntu + Ubuntu 24.04: + UBUNTU_VERSION: 24.04 USE_LATEST_CMAKE: true VTK_VERSION: 9 - TAG: 23.04 + TAG: 24.04 steps: - script: | dockerBuildArgs="" ; \ From da1cce4dad390be16be488da911494a02eee31ba Mon Sep 17 00:00:00 2001 From: Kino Date: Wed, 8 May 2024 16:24:28 +0800 Subject: [PATCH 245/288] Remove deprecated readdir_r (#6035) * Remove deprecated readdir_r * Resolve Review --- .../src/3rdparty/opennurbs/opennurbs_archive.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp b/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp index f4da1709a32..eb74cfd4262 100644 --- a/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp +++ b/surface/src/3rdparty/opennurbs/opennurbs_archive.cpp @@ -15318,15 +15318,21 @@ const wchar_t* ON_FileIterator::NextFile() for(;;) { current_file_attributes = 0; + /* + from readdir man page: + If the end of the directory stream is reached, + NULL is returned and errno is not changed. If an error occurs, + NULL is returned and errno is set appropriately. + */ struct dirent* dp = 0; - int readdir_errno = readdir_r(m_dir, &m_dirent, &dp); - if ( 0 != readdir_errno ) - break; + dp = readdir(m_dir); if ( 0 == dp ) break; - if ( 0 == m_dirent.d_name[0] ) + if ( 0 == dp->d_name[0] ) break; + m_dirent = *dp; + if ( IsDotOrDotDotDir(m_dirent.d_name) ) continue; From 00331db9af1e4bd25fdd39f3d72d5065b7e95304 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 8 May 2024 13:24:20 +0200 Subject: [PATCH 246/288] Update windows docker boost and cmake (#6033) * Only install boost-filesystem and boost-iostreams and their dependencies instead of all of boost. * Remove unncessary continouation line. * Added more required boost modules. * Boost-format used in example_iccp_segmentation. --- .dev/docker/windows/Dockerfile | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index ae6fc94be86..04aa5daf816 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -30,15 +30,14 @@ RUN wget $Env:CHANNEL_BASE_URL/vs_buildtools.exe -OutFile 'C:\TEMP\vs_buildtools "C:\TEMP\VisualStudio.chman", ` "--add", ` "Microsoft.VisualStudio.Workload.VCTools", ` - "Microsoft.Net.Component.4.8.SDK", ` + "Microsoft.Net.Component.4.8.SDK", ` "Microsoft.VisualStudio.Component.VC.ATLMFC", ` "--includeRecommended" ` -Wait -PassThru; ` del c:\temp\vs_buildtools.exe; -# VCPKG requires update if Cmake version is > 3.20.5 see: https://github.com/microsoft/vcpkg-tool/pull/107 RUN iex ((New-Object System.Net.WebClient).DownloadString('https://chocolatey.org/install.ps1')); ` - choco install cmake --version=3.20.5 --installargs 'ADD_CMAKE_TO_PATH=System' -y --no-progress; ` + choco install cmake --installargs 'ADD_CMAKE_TO_PATH=System' -y --no-progress; ` choco install git -y --no-progress RUN git clone https://github.com/microsoft/vcpkg.git; cd vcpkg; git checkout $Env:VCPKGCOMMIT; @@ -46,7 +45,8 @@ RUN git clone https://github.com/microsoft/vcpkg.git; cd vcpkg; git checkout $En # 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 benchmark openni2 --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; ` +RUN cd .\vcpkg; ` + .\bootstrap-vcpkg.bat; ` + .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 ` + --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; From 0f3da4c3068f17fc7b1ed578a695381ff38790a4 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Wed, 8 May 2024 15:03:03 +0200 Subject: [PATCH 247/288] Remove broken support for external metslib. --- CMakeLists.txt | 13 ------------- recognition/CMakeLists.txt | 31 ++++++++++++------------------- 2 files changed, 12 insertions(+), 32 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1741d73e20e..a4d575a0261 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -349,19 +349,6 @@ PCL_ADD_GRABBER_DEPENDENCY("DSSDK" "DepthSense SDK support") PCL_ADD_GRABBER_DEPENDENCY("RSSDK" "RealSense SDK support") PCL_ADD_GRABBER_DEPENDENCY("RSSDK2" "RealSense SDK 2.0 (librealsense) support") -# metslib -if(PKG_CONFIG_FOUND) - pkg_check_modules(METSLIB metslib) - if(METSLIB_FOUND) - set(HAVE_METSLIB ON) - include_directories(SYSTEM ${METSLIB_INCLUDE_DIRS}) - else() - include_directories(SYSTEM "${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/") - endif() -else() - include_directories(SYSTEM ${PCL_SOURCE_DIR}/recognition/include/pcl/recognition/3rdparty/) -endif() - # LibPNG option(WITH_PNG "PNG file support" TRUE) if(WITH_PNG) diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 6f1ad46a9a3..6bb94c62853 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -141,21 +141,17 @@ set(srcs src/implicit_shape_model.cpp ) -if(HAVE_METSLIB) - set(metslib_incs "") -else() - set(metslib_incs - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/abstract-search.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/local-search.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/mets.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/metslib_config.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/model.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/observer.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/simulated-annealing.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/tabu-search.hh" - "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/termination-criteria.hh" - ) -endif() +set(metslib_incs + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/abstract-search.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/local-search.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/mets.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/metslib_config.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/model.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/observer.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/simulated-annealing.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/tabu-search.hh" + "include/pcl/${SUBSYS_NAME}/3rdparty/metslib/termination-criteria.hh" +) set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${face_detection_incs} ${ransac_based_incs} ${ransac_based_impl_incs} ${hv_incs} ${hv_impl_incs} ${cg_incs} ${cg_impl_incs} ${metslib_incs}) @@ -174,7 +170,4 @@ PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/hv" ${hv_impl_incs}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/cg" ${cg_impl_incs}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/linemod" ${LINEMOD_INCLUDES}) PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl/linemod" ${LINEMOD_IMPLS}) - -if(NOT HAVE_METSLIB) - PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/3rdparty/metslib" ${metslib_incs}) -endif() +PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/3rdparty/metslib" ${metslib_incs}) From 366b85535099ea9fab19f108b4e7236a48de8a75 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 10 May 2024 10:31:57 +0200 Subject: [PATCH 248/288] Fix issue 6024 --- filters/include/pcl/filters/impl/bilateral.hpp | 12 ++++++++---- .../pcl/filters/impl/sampling_surface_normal.hpp | 12 ++++++++++++ .../pcl/visualization/impl/pcl_visualizer.hpp | 5 ++++- 3 files changed, 24 insertions(+), 5 deletions(-) diff --git a/filters/include/pcl/filters/impl/bilateral.hpp b/filters/include/pcl/filters/impl/bilateral.hpp index 2c707d38fbb..3a3a403d4ef 100644 --- a/filters/include/pcl/filters/impl/bilateral.hpp +++ b/filters/include/pcl/filters/impl/bilateral.hpp @@ -43,6 +43,7 @@ #include #include // for OrganizedNeighbor #include // for KdTree +#include // for isXYZFinite ////////////////////////////////////////////////////////////////////////////////////////////// template double @@ -101,11 +102,14 @@ pcl::BilateralFilter::applyFilter (PointCloud &output) // For all the indices given (equal to the entire cloud if none given) for (const auto& idx : (*indices_)) { - // Perform a radius search to find the nearest neighbors - tree_->radiusSearch (idx, sigma_s_ * 2, k_indices, k_distances); + if (input_->is_dense || pcl::isXYZFinite((*input_)[idx])) + { + // Perform a radius search to find the nearest neighbors + tree_->radiusSearch (idx, sigma_s_ * 2, k_indices, k_distances); - // Overwrite the intensity value with the computed average - output[idx].intensity = static_cast (computePointWeight (idx, k_indices, k_distances)); + // Overwrite the intensity value with the computed average + output[idx].intensity = static_cast (computePointWeight (idx, k_indices, k_distances)); + } } } diff --git a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp index a711bf8cba0..3a2959b015c 100644 --- a/filters/include/pcl/filters/impl/sampling_surface_normal.hpp +++ b/filters/include/pcl/filters/impl/sampling_surface_normal.hpp @@ -48,6 +48,18 @@ template void pcl::SamplingSurfaceNormal::applyFilter (PointCloud &output) { + if (ratio_ <= 0.0f) + { + PCL_ERROR("[SamplingSurfaceNormal::applyFilter] Parameter 'ratio' must be larger than zero!\n"); + output.clear(); + return; + } + if (sample_ < 5) + { + PCL_ERROR("[SamplingSurfaceNormal::applyFilter] Parameter 'sample' must be at least 5!\n"); + output.clear(); + return; + } Indices indices; std::size_t npts = input_->size (); for (std::size_t i = 0; i < npts; i++) diff --git a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp index 244af25d69f..08c81f08e23 100644 --- a/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp +++ b/visualization/include/pcl/visualization/impl/pcl_visualizer.hpp @@ -924,13 +924,15 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( lines->InsertCellPoint (2 * cell_count + 1); cell_count ++; } + nr_normals = cell_count; } else { nr_normals = (cloud->size () - 1) / level + 1 ; pts = new float[2 * nr_normals * 3]; - for (vtkIdType i = 0, j = 0; (j < nr_normals) && (i < static_cast(cloud->size())); i += level) + vtkIdType j = 0; + for (vtkIdType i = 0; (j < nr_normals) && (i < static_cast(cloud->size())); i += level) { if (!pcl::isFinite((*cloud)[i]) || !pcl::isNormalFinite((*normals)[i])) continue; @@ -951,6 +953,7 @@ pcl::visualization::PCLVisualizer::addPointCloudNormals ( lines->InsertCellPoint (2 * j + 1); ++j; } + nr_normals = j; } data->SetArray (&pts[0], 2 * nr_normals * 3, 0, vtkFloatArray::VTK_DATA_ARRAY_DELETE); From bf0965b9aa8303709c8d8ef2ffcc00f9f8cb6598 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sun, 12 May 2024 17:04:32 +0200 Subject: [PATCH 249/288] Faster octree nearestKSearch Inspired by the logic in organized.h: always keep `point_candidates` sorted, inserting new entries at the correct places. This avoids repeated calls to std::sort and having more than `k` entries in `point_candidates`. Benchmarks: NormalEstimation with octree: | NormalEstimation | Old | New | |-------------------|-----------|------------| | k=50, cloud=milk | 2607 ms | 1842 ms | | k=50, cloud=mug | 2043 ms | 1505 ms | | k=100, cloud=milk | 5650 ms | 3075 ms | | k=100, cloud=mug | 3824 ms | 2436 ms | Calling nearestKSearch on every (valid) point of a cloud: | Search | Old | New | |--------------|-----------|------------| | k=1, cloud1 | 818 ms | 509 ms | | k=1, cloud2 | 791 ms | 613 ms | | k=1, cloud3 | 773 ms | 744 ms | | k=5, cloud1 | 914 ms | 637 ms | | k=5, cloud2 | 950 ms | 780 ms | | k=5, cloud3 | 1083 ms | 1033 ms | --- .../include/pcl/octree/impl/octree_search.hpp | 30 +++++++++++-------- 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/octree/include/pcl/octree/impl/octree_search.hpp b/octree/include/pcl/octree/impl/octree_search.hpp index b0b5b54baa3..723fa4a58b5 100644 --- a/octree/include/pcl/octree/impl/octree_search.hpp +++ b/octree/include/pcl/octree/impl/octree_search.hpp @@ -97,6 +97,7 @@ OctreePointCloudSearch::nearestKSearch prioPointQueueEntry point_entry; std::vector point_candidates; + point_candidates.reserve(k); OctreeKey key; key.x = key.y = key.z = 0; @@ -305,21 +306,26 @@ OctreePointCloudSearch:: // calculate point distance to search point float squared_dist = pointSquaredDist(candidate_point, point); - // check if a closer match is found - if (squared_dist < smallest_squared_dist) { - prioPointQueueEntry point_entry; - - point_entry.point_distance_ = squared_dist; - point_entry.point_idx_ = point_index; - point_candidates.push_back(point_entry); + const auto insert_into_queue = [&] { + point_candidates.emplace( + std::upper_bound(point_candidates.begin(), + point_candidates.end(), + squared_dist, + [](float dist, const prioPointQueueEntry& ent) { + return dist < ent.point_distance_; + }), + point_index, + squared_dist); + }; + if (point_candidates.size() < K) { + insert_into_queue(); + } + else if (point_candidates.back().point_distance_ > squared_dist) { + point_candidates.pop_back(); + insert_into_queue(); } } - std::sort(point_candidates.begin(), point_candidates.end()); - - if (point_candidates.size() > K) - point_candidates.resize(K); - if (point_candidates.size() == K) smallest_squared_dist = point_candidates.back().point_distance_; } From 3ae4df5ede96d08408b500ee83d551151dd2a3da Mon Sep 17 00:00:00 2001 From: Shayril Date: Thu, 16 May 2024 03:27:23 +0800 Subject: [PATCH 250/288] Remove Deprecated Code for 1.15.0 release Signed-off-by: Shayril --- apps/in_hand_scanner/CMakeLists.txt | 2 - .../include/pcl/apps/in_hand_scanner/boost.h | 48 ------------- .../include/pcl/apps/in_hand_scanner/eigen.h | 49 ------------- common/CMakeLists.txt | 3 - common/include/pcl/common/boost.h | 53 --------------- common/include/pcl/make_shared.h | 42 ------------ common/include/pcl/point_traits.h | 43 ------------ features/CMakeLists.txt | 2 - features/include/pcl/features/boost.h | 46 ------------- features/include/pcl/features/eigen.h | 47 ------------- filters/CMakeLists.txt | 1 - filters/include/pcl/filters/boost.h | 54 --------------- geometry/CMakeLists.txt | 1 - geometry/include/pcl/geometry/eigen.h | 49 ------------- .../pcl/gpu/utils/device/static_check.hpp | 68 ------------------- io/CMakeLists.txt | 3 - io/include/pcl/io/boost.h | 66 ------------------ io/include/pcl/io/eigen.h | 45 ------------ io/include/pcl/io/io.h | 43 ------------ keypoints/CMakeLists.txt | 1 - .../include/pcl/keypoints/uniform_sampling.h | 44 ------------ octree/CMakeLists.txt | 1 - octree/include/pcl/octree/boost.h | 48 ------------- recognition/CMakeLists.txt | 17 ----- .../include/pcl/recognition/auxiliary.h | 2 - recognition/include/pcl/recognition/boost.h | 47 ------------- 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 - registration/CMakeLists.txt | 10 --- registration/include/pcl/registration/boost.h | 50 -------------- registration/include/pcl/registration/eigen.h | 50 -------------- .../correspondence_rejection_distance.hpp | 43 ------------ ...rrespondence_rejection_median_distance.hpp | 43 ------------ .../correspondence_rejection_one_to_one.hpp | 43 ------------ ...spondence_rejection_organized_boundary.hpp | 42 ------------ ...orrespondence_rejection_surface_normal.hpp | 42 ------------ .../impl/correspondence_rejection_trimmed.hpp | 43 ------------ .../correspondence_rejection_var_trimmed.hpp | 42 ------------ registration/include/pcl/registration/ndt.h | 18 ----- .../include/pcl/registration/transforms.h | 43 ------------ sample_consensus/CMakeLists.txt | 2 - .../include/pcl/sample_consensus/boost.h | 47 ------------- .../include/pcl/sample_consensus/eigen.h | 47 ------------- segmentation/CMakeLists.txt | 1 - segmentation/include/pcl/segmentation/boost.h | 55 --------------- surface/CMakeLists.txt | 2 - surface/include/pcl/surface/boost.h | 47 ------------- surface/include/pcl/surface/eigen.h | 47 ------------- surface/include/pcl/surface/mls.h | 10 --- tracking/include/pcl/tracking/pyramidal_klt.h | 16 ----- visualization/CMakeLists.txt | 2 - .../include/pcl/visualization/eigen.h | 48 ------------- .../pcl/visualization/pcl_visualizer.h | 5 -- visualization/include/pcl/visualization/vtk.h | 10 --- 67 files changed, 1663 deletions(-) delete mode 100644 apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h delete mode 100644 apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h delete mode 100644 common/include/pcl/common/boost.h delete mode 100644 common/include/pcl/make_shared.h delete mode 100644 common/include/pcl/point_traits.h delete mode 100644 features/include/pcl/features/boost.h delete mode 100644 features/include/pcl/features/eigen.h delete mode 100644 filters/include/pcl/filters/boost.h delete mode 100644 geometry/include/pcl/geometry/eigen.h delete mode 100644 gpu/utils/include/pcl/gpu/utils/device/static_check.hpp delete mode 100644 io/include/pcl/io/boost.h delete mode 100644 io/include/pcl/io/eigen.h delete mode 100644 io/include/pcl/io/io.h delete mode 100644 keypoints/include/pcl/keypoints/uniform_sampling.h delete mode 100644 octree/include/pcl/octree/boost.h delete mode 100644 recognition/include/pcl/recognition/auxiliary.h delete mode 100644 recognition/include/pcl/recognition/boost.h delete mode 100644 recognition/include/pcl/recognition/bvh.h delete mode 100644 recognition/include/pcl/recognition/hypothesis.h delete mode 100644 recognition/include/pcl/recognition/impl/line_rgbd.hpp delete mode 100644 recognition/include/pcl/recognition/impl/simple_octree.hpp delete mode 100644 recognition/include/pcl/recognition/impl/voxel_structure.hpp delete mode 100644 recognition/include/pcl/recognition/line_rgbd.h delete mode 100644 recognition/include/pcl/recognition/model_library.h delete mode 100644 recognition/include/pcl/recognition/obj_rec_ransac.h delete mode 100644 recognition/include/pcl/recognition/orr_graph.h delete mode 100644 recognition/include/pcl/recognition/orr_octree.h delete mode 100644 recognition/include/pcl/recognition/orr_octree_zprojection.h delete mode 100644 recognition/include/pcl/recognition/rigid_transform_space.h delete mode 100644 recognition/include/pcl/recognition/simple_octree.h delete mode 100644 recognition/include/pcl/recognition/trimmed_icp.h delete mode 100644 recognition/include/pcl/recognition/voxel_structure.h delete mode 100644 registration/include/pcl/registration/boost.h delete mode 100644 registration/include/pcl/registration/eigen.h delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp delete mode 100644 registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp delete mode 100644 registration/include/pcl/registration/transforms.h delete mode 100644 sample_consensus/include/pcl/sample_consensus/boost.h delete mode 100644 sample_consensus/include/pcl/sample_consensus/eigen.h delete mode 100644 segmentation/include/pcl/segmentation/boost.h delete mode 100644 surface/include/pcl/surface/boost.h delete mode 100644 surface/include/pcl/surface/eigen.h delete mode 100644 visualization/include/pcl/visualization/eigen.h delete mode 100644 visualization/include/pcl/visualization/vtk.h diff --git a/apps/in_hand_scanner/CMakeLists.txt b/apps/in_hand_scanner/CMakeLists.txt index 97e2c72ee11..753cb3226d7 100644 --- a/apps/in_hand_scanner/CMakeLists.txt +++ b/apps/in_hand_scanner/CMakeLists.txt @@ -19,9 +19,7 @@ pcl_add_doc("${SUBSUBSYS_NAME}") ################################################################################ set(INCS - "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/common_types.h" - "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/icp.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/input_data_processing.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/integration.h" 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 deleted file mode 100644 index f4f535427ba..00000000000 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h +++ /dev/null @@ -1,48 +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. - * - * $Id$ - * - */ - -#pragma once - -#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 deleted file mode 100644 index a4380316268..00000000000 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/eigen.h +++ /dev/null @@ -1,49 +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. - * - * $Id$ - * - */ - -#pragma once - -#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/common/CMakeLists.txt b/common/CMakeLists.txt index 103cdd5b0b4..0a27abc2956 100644 --- a/common/CMakeLists.txt +++ b/common/CMakeLists.txt @@ -59,7 +59,6 @@ set(incs include/pcl/types.h include/pcl/point_cloud.h include/pcl/point_struct_traits.h - include/pcl/point_traits.h include/pcl/type_traits.h include/pcl/point_types_conversion.h include/pcl/point_representation.h @@ -79,11 +78,9 @@ set(incs include/pcl/PointIndices.h include/pcl/register_point_struct.h include/pcl/conversions.h - include/pcl/make_shared.h ) set(common_incs - include/pcl/common/boost.h include/pcl/common/angles.h include/pcl/common/bivariate_polynomial.h include/pcl/common/centroid.h diff --git a/common/include/pcl/common/boost.h b/common/include/pcl/common/boost.h deleted file mode 100644 index 068e48999fd..00000000000 --- a/common/include/pcl/common/boost.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ - -#pragma once - -#ifdef __GNUC__ -#pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -#ifndef Q_MOC_RUN -// Marking all Boost headers as system headers to remove warnings -#include -#include -#include -#include -#include -#endif diff --git a/common/include/pcl/make_shared.h b/common/include/pcl/make_shared.h deleted file mode 100644 index 983a63c9ead..00000000000 --- a/common/include/pcl/make_shared.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2019-, 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 - -PCL_DEPRECATED_HEADER(1, 15, "Use instead.") - -#include - diff --git a/common/include/pcl/point_traits.h b/common/include/pcl/point_traits.h deleted file mode 100644 index 4136fa91cfc..00000000000 --- a/common/include/pcl/point_traits.h +++ /dev/null @@ -1,43 +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 - -PCL_DEPRECATED_HEADER(1, 15, "Use instead.") - -#include diff --git a/features/CMakeLists.txt b/features/CMakeLists.txt index 2b280563372..a70d3a520b7 100644 --- a/features/CMakeLists.txt +++ b/features/CMakeLists.txt @@ -12,8 +12,6 @@ if(NOT build) endif() set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/board.h" "include/pcl/${SUBSYS_NAME}/flare.h" "include/pcl/${SUBSYS_NAME}/brisk_2d.h" diff --git a/features/include/pcl/features/boost.h b/features/include/pcl/features/boost.h deleted file mode 100644 index 4f49824a070..00000000000 --- a/features/include/pcl/features/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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") -#include diff --git a/features/include/pcl/features/eigen.h b/features/include/pcl/features/eigen.h deleted file mode 100644 index 563874881d6..00000000000 --- a/features/include/pcl/features/eigen.h +++ /dev/null @@ -1,47 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") -#include -#include diff --git a/filters/CMakeLists.txt b/filters/CMakeLists.txt index eb49b3f37d4..3fc7c64104e 100644 --- a/filters/CMakeLists.txt +++ b/filters/CMakeLists.txt @@ -49,7 +49,6 @@ set(srcs ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/conditional_removal.h" "include/pcl/${SUBSYS_NAME}/crop_box.h" "include/pcl/${SUBSYS_NAME}/clipper3D.h" diff --git a/filters/include/pcl/filters/boost.h b/filters/include/pcl/filters/boost.h deleted file mode 100644 index 273c1e67729..00000000000 --- a/filters/include/pcl/filters/boost.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $ - * - */ - -#pragma once - -#ifdef __GNUC__ -#pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -// Marking all Boost headers as system headers to remove warnings -#include -#include -#include -#include -#include -#include diff --git a/geometry/CMakeLists.txt b/geometry/CMakeLists.txt index 54929f709b9..4cebf285724 100644 --- a/geometry/CMakeLists.txt +++ b/geometry/CMakeLists.txt @@ -13,7 +13,6 @@ endif() set(incs "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/get_boundary.h" "include/pcl/${SUBSYS_NAME}/line_iterator.h" "include/pcl/${SUBSYS_NAME}/mesh_base.h" diff --git a/geometry/include/pcl/geometry/eigen.h b/geometry/include/pcl/geometry/eigen.h deleted file mode 100644 index 2f250e29e23..00000000000 --- a/geometry/include/pcl/geometry/eigen.h +++ /dev/null @@ -1,49 +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. - * - * $Id$ - * - */ - -#pragma once - -#ifdef __GNUC__ -#pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") - -#include -#include diff --git a/gpu/utils/include/pcl/gpu/utils/device/static_check.hpp b/gpu/utils/include/pcl/gpu/utils/device/static_check.hpp deleted file mode 100644 index fe153cfc4e1..00000000000 --- a/gpu/utils/include/pcl/gpu/utils/device/static_check.hpp +++ /dev/null @@ -1,68 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 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. - * - * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) - */ - -PCL_DEPRECATED_HEADER(1, 15, "pcl::device::Static will be removed at PCL release 1.15"); - -#ifndef PCL_GPU_DEVICE_STATIC_CHECK_HPP_ -#define PCL_GPU_DEVICE_STATIC_CHECK_HPP_ - -#if defined(__CUDACC__) -#define __PCL_GPU_HOST_DEVICE__ __host__ __device__ __forceinline__ -#else -#define __PCL_GPU_HOST_DEVICE__ -#endif - -namespace pcl { -namespace device { -template -struct Static {}; - -template <> -struct [[deprecated("This class will be replaced at PCL release 1.15 by " - "c++11's static_assert instead")]] Static -{ - __PCL_GPU_HOST_DEVICE__ static void check(){}; -}; -} // namespace device - -namespace gpu { -using pcl::device::Static; -} -} // namespace pcl - -#undef __PCL_GPU_HOST_DEVICE__ - -#endif /* PCL_GPU_DEVICE_STATIC_CHECK_HPP_ */ diff --git a/io/CMakeLists.txt b/io/CMakeLists.txt index d02a25bb88a..38bf2b89984 100644 --- a/io/CMakeLists.txt +++ b/io/CMakeLists.txt @@ -255,8 +255,6 @@ if(PCAP_FOUND) endif() set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/debayer.h" "include/pcl/${SUBSYS_NAME}/fotonic_grabber.h" "include/pcl/${SUBSYS_NAME}/file_io.h" @@ -264,7 +262,6 @@ set(incs "include/pcl/${SUBSYS_NAME}/low_level_io.h" "include/pcl/${SUBSYS_NAME}/lzf.h" "include/pcl/${SUBSYS_NAME}/lzf_image_io.h" - "include/pcl/${SUBSYS_NAME}/io.h" "include/pcl/${SUBSYS_NAME}/grabber.h" "include/pcl/${SUBSYS_NAME}/file_grabber.h" "include/pcl/${SUBSYS_NAME}/timestamp.h" diff --git a/io/include/pcl/io/boost.h b/io/include/pcl/io/boost.h deleted file mode 100644 index a0867796df8..00000000000 --- a/io/include/pcl/io/boost.h +++ /dev/null @@ -1,66 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2011-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 -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") -#if defined __GNUC__ -# pragma GCC system_header -#endif -//https://bugreports.qt-project.org/browse/QTBUG-22829 -#ifndef Q_MOC_RUN -#ifndef __CUDACC__ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#define BOOST_PARAMETER_MAX_ARITY 7 -#include -#include -#endif -#include -#include -#endif diff --git a/io/include/pcl/io/eigen.h b/io/include/pcl/io/eigen.h deleted file mode 100644 index 0979ece907e..00000000000 --- a/io/include/pcl/io/eigen.h +++ /dev/null @@ -1,45 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2011-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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") - -#include diff --git a/io/include/pcl/io/io.h b/io/include/pcl/io/io.h deleted file mode 100644 index 62b3289daf4..00000000000 --- a/io/include/pcl/io/io.h +++ /dev/null @@ -1,43 +0,0 @@ -/* - * 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 the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#pragma once -#include // for PCL_DEPRECATED_HEADER -PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/io.h directly.") -#include diff --git a/keypoints/CMakeLists.txt b/keypoints/CMakeLists.txt index 1964878c82e..30419d7c6f4 100644 --- a/keypoints/CMakeLists.txt +++ b/keypoints/CMakeLists.txt @@ -29,7 +29,6 @@ set(incs "include/pcl/${SUBSYS_NAME}/keypoint.h" "include/pcl/${SUBSYS_NAME}/narf_keypoint.h" "include/pcl/${SUBSYS_NAME}/sift_keypoint.h" - "include/pcl/${SUBSYS_NAME}/uniform_sampling.h" "include/pcl/${SUBSYS_NAME}/smoothed_surfaces_keypoint.h" "include/pcl/${SUBSYS_NAME}/agast_2d.h" "include/pcl/${SUBSYS_NAME}/harris_2d.h" diff --git a/keypoints/include/pcl/keypoints/uniform_sampling.h b/keypoints/include/pcl/keypoints/uniform_sampling.h deleted file mode 100644 index 66596274997..00000000000 --- a/keypoints/include/pcl/keypoints/uniform_sampling.h +++ /dev/null @@ -1,44 +0,0 @@ -/* - * 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. - * - * $Id$ - * - */ - -#pragma once - -PCL_DEPRECATED_HEADER(1, 15, "UniformSampling is not a Keypoint anymore, use instead.") - -#include diff --git a/octree/CMakeLists.txt b/octree/CMakeLists.txt index 2270690adc5..43e07b9a53f 100644 --- a/octree/CMakeLists.txt +++ b/octree/CMakeLists.txt @@ -16,7 +16,6 @@ set(srcs ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/octree_base.h" "include/pcl/${SUBSYS_NAME}/octree_container.h" "include/pcl/${SUBSYS_NAME}/octree_impl.h" diff --git a/octree/include/pcl/octree/boost.h b/octree/include/pcl/octree/boost.h deleted file mode 100644 index b3680aab8c7..00000000000 --- a/octree/include/pcl/octree/boost.h +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * - */ - -#pragma once - -#ifdef __GNUC__ -#pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -// Marking all Boost headers as system headers to remove warnings -#include diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index 6f1ad46a9a3..e4f5cdfbe72 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -27,7 +27,6 @@ set(LINEMOD_IMPLS ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/color_gradient_dot_modality.h" "include/pcl/${SUBSYS_NAME}/color_gradient_modality.h" "include/pcl/${SUBSYS_NAME}/color_modality.h" @@ -44,20 +43,7 @@ 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}/line_rgbd.h" "include/pcl/${SUBSYS_NAME}/implicit_shape_model.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 @@ -97,9 +83,6 @@ set(cg_incs ) set(impl_incs - "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 deleted file mode 100644 index 0e364add08e..00000000000 --- a/recognition/include/pcl/recognition/auxiliary.h +++ /dev/null @@ -1,2 +0,0 @@ -#include -PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/recognition/include/pcl/recognition/boost.h b/recognition/include/pcl/recognition/boost.h deleted file mode 100644 index 44e705be245..00000000000 --- a/recognition/include/pcl/recognition/boost.h +++ /dev/null @@ -1,47 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -#include diff --git a/recognition/include/pcl/recognition/bvh.h b/recognition/include/pcl/recognition/bvh.h deleted file mode 100644 index 12374a202c6..00000000000 --- a/recognition/include/pcl/recognition/bvh.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index ad8f5b642df..00000000000 --- a/recognition/include/pcl/recognition/hypothesis.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 53d67119496..00000000000 --- a/recognition/include/pcl/recognition/impl/line_rgbd.hpp +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 0c8c0ccb3d0..00000000000 --- a/recognition/include/pcl/recognition/impl/simple_octree.hpp +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 44697e8e358..00000000000 --- a/recognition/include/pcl/recognition/impl/voxel_structure.hpp +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 5d526ad3984..00000000000 --- a/recognition/include/pcl/recognition/line_rgbd.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 4b4ee3345bd..00000000000 --- a/recognition/include/pcl/recognition/model_library.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 52b96362eb5..00000000000 --- a/recognition/include/pcl/recognition/obj_rec_ransac.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index a43e35c9558..00000000000 --- a/recognition/include/pcl/recognition/orr_graph.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index b0f43fc2f27..00000000000 --- a/recognition/include/pcl/recognition/orr_octree.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 536f8a53f49..00000000000 --- a/recognition/include/pcl/recognition/orr_octree_zprojection.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index 2cc30436bad..00000000000 --- a/recognition/include/pcl/recognition/rigid_transform_space.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index aa47e0d885d..00000000000 --- a/recognition/include/pcl/recognition/simple_octree.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index cabf17ba777..00000000000 --- a/recognition/include/pcl/recognition/trimmed_icp.h +++ /dev/null @@ -1,2 +0,0 @@ -#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 deleted file mode 100644 index a78e541ca7d..00000000000 --- a/recognition/include/pcl/recognition/voxel_structure.h +++ /dev/null @@ -1,2 +0,0 @@ -#include -PCL_DEPRECATED_HEADER(1, 15, "Please use instead") diff --git a/registration/CMakeLists.txt b/registration/CMakeLists.txt index cb7bc435e63..ab15ffc2cc2 100644 --- a/registration/CMakeLists.txt +++ b/registration/CMakeLists.txt @@ -12,8 +12,6 @@ if(NOT build) endif() set(incs - "include/pcl/${SUBSYS_NAME}/eigen.h" - "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/boost_graph.h" "include/pcl/${SUBSYS_NAME}/convergence_criteria.h" "include/pcl/${SUBSYS_NAME}/default_convergence_criteria.h" @@ -51,7 +49,6 @@ set(incs "include/pcl/${SUBSYS_NAME}/pyramid_feature_matching.h" "include/pcl/${SUBSYS_NAME}/registration.h" - "include/pcl/${SUBSYS_NAME}/transforms.h" "include/pcl/${SUBSYS_NAME}/transformation_estimation.h" "include/pcl/${SUBSYS_NAME}/transformation_estimation_2D.h" "include/pcl/${SUBSYS_NAME}/transformation_estimation_svd.h" @@ -86,17 +83,10 @@ set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_normal_shooting.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_backprojection.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_estimation_organized_projection.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_distance.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_median_distance.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_surface_normal.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_features.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_one_to_one.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_poly.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_sample_consensus.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_sample_consensus_2d.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_trimmed.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_var_trimmed.hpp" - "include/pcl/${SUBSYS_NAME}/impl/correspondence_rejection_organized_boundary.hpp" "include/pcl/${SUBSYS_NAME}/impl/correspondence_types.hpp" "include/pcl/${SUBSYS_NAME}/impl/ia_ransac.hpp" "include/pcl/${SUBSYS_NAME}/impl/icp.hpp" diff --git a/registration/include/pcl/registration/boost.h b/registration/include/pcl/registration/boost.h deleted file mode 100644 index 6a6f17d115d..00000000000 --- a/registration/include/pcl/registration/boost.h +++ /dev/null @@ -1,50 +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$ - * - */ - -#pragma once -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") -#if defined __GNUC__ -#pragma GCC system_header -#endif - -//#include -#include -#include -#include -#include diff --git a/registration/include/pcl/registration/eigen.h b/registration/include/pcl/registration/eigen.h deleted file mode 100644 index 5712e8fcac4..00000000000 --- a/registration/include/pcl/registration/eigen.h +++ /dev/null @@ -1,50 +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 - -#if defined __GNUC__ -#pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") - -#include -#include -#include -#include diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp deleted file mode 100644 index 680ed690c7f..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_distance.hpp +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_DISTANCE_HPP_ */ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp deleted file mode 100644 index eaa5364e9d7..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_median_distance.hpp +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif // PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_MEDIAN_DISTANCE_HPP_ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp deleted file mode 100644 index 3f256839477..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_one_to_one.hpp +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ONE_TO_ONE_HPP_ */ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp deleted file mode 100644 index c70ea72ba5c..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_organized_boundary.hpp +++ /dev/null @@ -1,42 +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. - * Copyright (c) Alexandru-Eugen Ichim - * - * 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. - */ - -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_ORGANIZED_BOUNDARY_HPP_ */ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp deleted file mode 100644 index 65e8bbc1ca9..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_surface_normal.hpp +++ /dev/null @@ -1,42 +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$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_SURFACE_NORMAL_HPP_ */ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp deleted file mode 100644 index 9aee8cdad52..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_trimmed.hpp +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_TRIMMED_HPP_ */ diff --git a/registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp b/registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp deleted file mode 100644 index 201c6d4a4a4..00000000000 --- a/registration/include/pcl/registration/impl/correspondence_rejection_var_trimmed.hpp +++ /dev/null @@ -1,42 +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$ - * - */ -#ifndef PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ -#define PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ -PCL_DEPRECATED_HEADER(1, 15, "") -#endif /* PCL_REGISTRATION_IMPL_CORRESPONDENCE_REJECTION_VAR_TRIMMED_HPP_ */ diff --git a/registration/include/pcl/registration/ndt.h b/registration/include/pcl/registration/ndt.h index 773151be9a1..c7c7bd8d50a 100644 --- a/registration/include/pcl/registration/ndt.h +++ b/registration/include/pcl/registration/ndt.h @@ -381,24 +381,6 @@ class NormalDistributionsTransform computeHessian(Eigen::Matrix& hessian, const PointCloudSource& trans_cloud); - /** \brief Compute hessian of likelihood function w.r.t. the transformation - * vector. - * \note Equation 6.13 [Magnusson 2009]. - * \param[out] hessian the hessian matrix of the likelihood function - * w.r.t. the transformation vector - * \param[in] trans_cloud transformed point cloud - * \param[in] transform the current transform vector - */ - PCL_DEPRECATED(1, 15, "Parameter `transform` is not required") - void - computeHessian(Eigen::Matrix& hessian, - const PointCloudSource& trans_cloud, - const Eigen::Matrix& transform) - { - pcl::utils::ignore(transform); - computeHessian(hessian, trans_cloud); - } - /** \brief Compute individual point contributions to hessian of likelihood * function w.r.t. the transformation vector. * \note Equation 6.13 [Magnusson 2009]. diff --git a/registration/include/pcl/registration/transforms.h b/registration/include/pcl/registration/transforms.h deleted file mode 100644 index 2f4bfb79cfa..00000000000 --- a/registration/include/pcl/registration/transforms.h +++ /dev/null @@ -1,43 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id$ - * - */ - -#pragma once -PCL_DEPRECATED_HEADER(1, 15, "Please include pcl/common/transforms.h directly.") -#include diff --git a/sample_consensus/CMakeLists.txt b/sample_consensus/CMakeLists.txt index 4ce23771bdd..88d353d5453 100644 --- a/sample_consensus/CMakeLists.txt +++ b/sample_consensus/CMakeLists.txt @@ -30,8 +30,6 @@ set(srcs ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/lmeds.h" "include/pcl/${SUBSYS_NAME}/method_types.h" "include/pcl/${SUBSYS_NAME}/mlesac.h" diff --git a/sample_consensus/include/pcl/sample_consensus/boost.h b/sample_consensus/include/pcl/sample_consensus/boost.h deleted file mode 100644 index ea42ca4c2bb..00000000000 --- a/sample_consensus/include/pcl/sample_consensus/boost.h +++ /dev/null @@ -1,47 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -#include diff --git a/sample_consensus/include/pcl/sample_consensus/eigen.h b/sample_consensus/include/pcl/sample_consensus/eigen.h deleted file mode 100644 index 63d733321cc..00000000000 --- a/sample_consensus/include/pcl/sample_consensus/eigen.h +++ /dev/null @@ -1,47 +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 -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") -#if defined __GNUC__ -# pragma GCC system_header -#endif - -#include -#include diff --git a/segmentation/CMakeLists.txt b/segmentation/CMakeLists.txt index 85b3f64be55..bd103dbc3c2 100644 --- a/segmentation/CMakeLists.txt +++ b/segmentation/CMakeLists.txt @@ -35,7 +35,6 @@ set(srcs ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/extract_clusters.h" "include/pcl/${SUBSYS_NAME}/extract_labeled_clusters.h" "include/pcl/${SUBSYS_NAME}/extract_polygonal_prism_data.h" diff --git a/segmentation/include/pcl/segmentation/boost.h b/segmentation/include/pcl/segmentation/boost.h deleted file mode 100644 index 6ef50c3865b..00000000000 --- a/segmentation/include/pcl/segmentation/boost.h +++ /dev/null @@ -1,55 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2010-2011, Willow Garage, Inc. - * Copyright (c) 2012-, Open Perception, Inc. - * - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the copyright holder(s) nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - * $Id: io.h 5850 2012-06-06 14:04:59Z stfox88 $ - * - */ - -#pragma once -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") -#ifdef __GNUC__ -#pragma GCC system_header -#endif - -#ifndef Q_MOC_RUN -// Marking all Boost headers as system headers to remove warnings -#include -#include -#include -#include - -#include -#endif diff --git a/surface/CMakeLists.txt b/surface/CMakeLists.txt index 8f0760a84ab..a9976b70c45 100644 --- a/surface/CMakeLists.txt +++ b/surface/CMakeLists.txt @@ -136,8 +136,6 @@ set(srcs ) set(incs - "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/ear_clipping.h" "include/pcl/${SUBSYS_NAME}/gp3.h" "include/pcl/${SUBSYS_NAME}/grid_projection.h" diff --git a/surface/include/pcl/surface/boost.h b/surface/include/pcl/surface/boost.h deleted file mode 100644 index 86aca4ea82c..00000000000 --- a/surface/include/pcl/surface/boost.h +++ /dev/null @@ -1,47 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed boost headers directly.") - -#include diff --git a/surface/include/pcl/surface/eigen.h b/surface/include/pcl/surface/eigen.h deleted file mode 100644 index e3f46b0de21..00000000000 --- a/surface/include/pcl/surface/eigen.h +++ /dev/null @@ -1,47 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") - -#include diff --git a/surface/include/pcl/surface/mls.h b/surface/include/pcl/surface/mls.h index 8c3a45e1dff..7c33feddfff 100644 --- a/surface/include/pcl/surface/mls.h +++ b/surface/include/pcl/surface/mls.h @@ -144,16 +144,6 @@ namespace pcl Eigen::Vector2f calculatePrincipalCurvatures (const double u, const double v) const; - /** \brief Calculate the principal curvatures using the polynomial surface. - * \param[in] u The u-coordinate of the point in local MLS frame. - * \param[in] v The v-coordinate of the point in local MLS frame. - * \return The principal curvature [k1, k2] at the provided uv coordinates. - * \note If an error occurs then 1e-5 is returned. - */ - PCL_DEPRECATED(1, 15, "use calculatePrincipalCurvatures() instead") - inline Eigen::Vector2f - calculatePrincipleCurvatures (const double u, const double v) const { return calculatePrincipalCurvatures(u, v); }; - /** \brief Project a point orthogonal to the polynomial surface. * \param[in] u The u-coordinate of the point in local MLS frame. * \param[in] v The v-coordinate of the point in local MLS frame. diff --git a/tracking/include/pcl/tracking/pyramidal_klt.h b/tracking/include/pcl/tracking/pyramidal_klt.h index b6416dbe059..d5b44908355 100644 --- a/tracking/include/pcl/tracking/pyramidal_klt.h +++ b/tracking/include/pcl/tracking/pyramidal_klt.h @@ -254,22 +254,6 @@ class PyramidalKLTTracker : public Tracker { return (keypoints_); }; - /** \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. - */ - 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; diff --git a/visualization/CMakeLists.txt b/visualization/CMakeLists.txt index 8446cb4f31d..dff68b47bb7 100644 --- a/visualization/CMakeLists.txt +++ b/visualization/CMakeLists.txt @@ -57,7 +57,6 @@ if(NOT (${VTK_VERSION} VERSION_LESS 9.0)) endif() set(incs - "include/pcl/${SUBSYS_NAME}/eigen.h" "include/pcl/${SUBSYS_NAME}/boost.h" "include/pcl/${SUBSYS_NAME}/cloud_viewer.h" "include/pcl/${SUBSYS_NAME}/histogram_visualizer.h" @@ -75,7 +74,6 @@ set(incs "include/pcl/${SUBSYS_NAME}/mouse_event.h" "include/pcl/${SUBSYS_NAME}/window.h" "include/pcl/${SUBSYS_NAME}/range_image_visualizer.h" - "include/pcl/${SUBSYS_NAME}/vtk.h" "include/pcl/${SUBSYS_NAME}/simple_buffer_visualizer.h" "include/pcl/${SUBSYS_NAME}/pcl_plotter.h" "include/pcl/${SUBSYS_NAME}/qvtk_compatibility.h" diff --git a/visualization/include/pcl/visualization/eigen.h b/visualization/include/pcl/visualization/eigen.h deleted file mode 100644 index 09d57c502e4..00000000000 --- a/visualization/include/pcl/visualization/eigen.h +++ /dev/null @@ -1,48 +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 - -#if defined __GNUC__ -# pragma GCC system_header -#endif -PCL_DEPRECATED_HEADER(1, 15, "Please include the needed eigen headers directly.") - -#include -#include diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index 69478657759..b376ab807ba 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -1818,11 +1818,6 @@ namespace pcl std::string getCameraFile () const; - /** \brief Update camera parameters and render. */ - PCL_DEPRECATED(1,15,"updateCamera will be removed, as it does nothing.") - inline void - updateCamera () {}; - /** \brief Reset camera parameters and render. */ void resetCamera (); diff --git a/visualization/include/pcl/visualization/vtk.h b/visualization/include/pcl/visualization/vtk.h deleted file mode 100644 index 1df02a3dad4..00000000000 --- a/visualization/include/pcl/visualization/vtk.h +++ /dev/null @@ -1,10 +0,0 @@ -/* - * SPDX-License-Identifier: BSD-3-Clause - * - * Point Cloud Library (PCL) - www.pointclouds.org - * Copyright (c) 2020-, Open Perception - * - * All rights reserved - */ - -PCL_DEPRECATED_HEADER(1, 15, "Use required vtk includes instead.") From 6503e53fc23c72970ce1a782f04b867eb86160d0 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Wed, 15 May 2024 21:39:31 +0200 Subject: [PATCH 251/288] Faster octree radiusSearch ... by improving the check whether an octree node might contain a point within radius. Previously this was done by a sphere around the node center, now this done exact (like a rounded cube). Benchmarks: NormalEstimation (without OpenMP) with octree: | NormalEstimation | Old | New | |-------------------|-----------|------------| | r=0.01, cloud=milk| 914 ms | 756 ms | | r=0.01, cloud=mug | 1133 ms | 881 ms | | r=0.02, cloud=milk| 1979 ms | 1784 ms | | r=0.02, cloud=mug | 2642 ms | 2244 ms | Calling radiusSearch on every (valid) point of a cloud (r is tuned so that 5 and 50 neighbours are found on average, respectively): | Search | Old | New | |-----------------|-----------|------------| | r=0.0016, cloud1| 267 ms | 175 ms | | r=0.0022, cloud2| 319 ms | 210 ms | | r=0.0072, cloud3| 421 ms | 293 ms | | r=0.005, cloud1 | 440 ms | 356 ms | | r=0.0068, cloud2| 513 ms | 441 ms | | r=0.024, cloud3 | 877 ms | 873 ms | --- .../pcl/octree/impl/octree_pointcloud.hpp | 9 ++--- .../include/pcl/octree/impl/octree_search.hpp | 33 ++++++++++--------- 2 files changed, 21 insertions(+), 21 deletions(-) diff --git a/octree/include/pcl/octree/impl/octree_pointcloud.hpp b/octree/include/pcl/octree/impl/octree_pointcloud.hpp index ae370081059..fcabeca1f0f 100644 --- a/octree/include/pcl/octree/impl/octree_pointcloud.hpp +++ b/octree/include/pcl/octree/impl/octree_pointcloud.hpp @@ -886,12 +886,9 @@ pcl::octree::OctreePointCloud min_pt(2) = static_cast(static_cast(key_arg.z) * voxel_side_len + this->min_z_); - max_pt(0) = static_cast(static_cast(key_arg.x + 1) * voxel_side_len + - this->min_x_); - max_pt(1) = static_cast(static_cast(key_arg.y + 1) * voxel_side_len + - this->min_y_); - max_pt(2) = static_cast(static_cast(key_arg.z + 1) * voxel_side_len + - this->min_z_); + max_pt(0) = min_pt(0) + voxel_side_len; + max_pt(1) = min_pt(1) + voxel_side_len; + max_pt(2) = min_pt(2) + voxel_side_len; } ////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/octree/include/pcl/octree/impl/octree_search.hpp b/octree/include/pcl/octree/impl/octree_search.hpp index 723fa4a58b5..ea89c3d66f1 100644 --- a/octree/include/pcl/octree/impl/octree_search.hpp +++ b/octree/include/pcl/octree/impl/octree_search.hpp @@ -348,9 +348,6 @@ OctreePointCloudSearch:: std::vector& k_sqr_distances, uindex_t max_nn) const { - // get spatial voxel information - double voxel_squared_diameter = this->getVoxelSquaredDiameter(tree_depth); - // iterate over all children for (unsigned char child_idx = 0; child_idx < 8; child_idx++) { if (!this->branchHasChild(*node, child_idx)) @@ -360,7 +357,6 @@ OctreePointCloudSearch:: child_node = this->getBranchChildPtr(*node, child_idx); OctreeKey new_key; - PointT voxel_center; float squared_dist; // generate new key for current branch voxel @@ -368,17 +364,24 @@ OctreePointCloudSearch:: new_key.y = (key.y << 1) + (!!(child_idx & (1 << 1))); new_key.z = (key.z << 1) + (!!(child_idx & (1 << 0))); - // generate voxel center point for voxel at key - this->genVoxelCenterFromOctreeKey(new_key, tree_depth, voxel_center); - - // calculate distance to search point - squared_dist = pointSquaredDist(static_cast(voxel_center), point); - - // if distance is smaller than search radius - if (squared_dist + this->epsilon_ <= - voxel_squared_diameter / 4.0 + radiusSquared + - sqrt(voxel_squared_diameter * radiusSquared)) { - + // compute min distance between query point and any point in this child node, to + // decide whether we can skip it + Eigen::Vector3f min_pt, max_pt; + this->genVoxelBoundsFromOctreeKey(new_key, tree_depth, min_pt, max_pt); + squared_dist = 0.0f; + if (point.x < min_pt.x()) + squared_dist += std::pow(point.x - min_pt.x(), 2); + else if (point.x > max_pt.x()) + squared_dist += std::pow(point.x - max_pt.x(), 2); + if (point.y < min_pt.y()) + squared_dist += std::pow(point.y - min_pt.y(), 2); + else if (point.y > max_pt.y()) + squared_dist += std::pow(point.y - max_pt.y(), 2); + if (point.z < min_pt.z()) + squared_dist += std::pow(point.z - min_pt.z(), 2); + else if (point.z > max_pt.z()) + squared_dist += std::pow(point.z - max_pt.z(), 2); + if (squared_dist < (radiusSquared + this->epsilon_)) { if (child_node->getNodeType() == BRANCH_NODE) { // we have not reached maximum tree depth getNeighborsWithinRadiusRecursive(point, From d05e8f6b30fcdcd894f60516822847ca068610ec Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 18 May 2024 14:51:11 +0200 Subject: [PATCH 252/288] GICP: parallel covariance computation --- registration/include/pcl/registration/gicp.h | 11 ++++++ .../include/pcl/registration/impl/gicp.hpp | 34 ++++++++++++++++--- 2 files changed, 40 insertions(+), 5 deletions(-) diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 4084c6444e0..46fb64df210 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -125,6 +125,7 @@ class GeneralizedIterativeClosestPoint max_iterations_ = 200; transformation_epsilon_ = 5e-4; corr_dist_threshold_ = 5.; + setNumberOfThreads(0); rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src, const pcl::Indices& indices_src, const PointCloudTarget& cloud_tgt, @@ -355,6 +356,13 @@ class GeneralizedIterativeClosestPoint return rotation_gradient_tolerance_; } + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value back to + * automatic) + */ + void + setNumberOfThreads(unsigned int nr_threads = 0); + protected: /** \brief The number of neighbors used for covariances computation. * default: 20 @@ -508,6 +516,9 @@ class GeneralizedIterativeClosestPoint Eigen::Matrix3d& ddR_dTheta_dTheta, Eigen::Matrix3d& ddR_dTheta_dPsi, Eigen::Matrix3d& ddR_dPsi_dPsi) const; + + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; }; } // namespace pcl diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index f2101ad3a45..0688ef90195 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -45,6 +45,28 @@ namespace pcl { +template +void +GeneralizedIterativeClosestPoint::setNumberOfThreads( + unsigned int nr_threads) +{ +#ifdef _OPENMP + if (nr_threads == 0) + threads_ = omp_get_num_procs(); + else + threads_ = nr_threads; + PCL_DEBUG("[pcl::GeneralizedIterativeClosestPoint::setNumberOfThreads] Setting " + "number of threads to %u.\n", + threads_); +#else + threads_ = 1; + if (nr_threads != 1) + PCL_WARN("[pcl::GeneralizedIterativeClosestPoint::setNumberOfThreads] " + "Parallelization is requested, but OpenMP is not available! Continuing " + "without parallelization.\n"); +#endif // _OPENMP +} + template template void @@ -62,6 +84,7 @@ GeneralizedIterativeClosestPoint::computeCovar } Eigen::Vector3d mean; + Eigen::Matrix3d cov; pcl::Indices nn_indices(k_correspondences_); std::vector nn_dist_sq(k_correspondences_); @@ -69,11 +92,11 @@ GeneralizedIterativeClosestPoint::computeCovar if (cloud_covariances.size() < cloud->size()) cloud_covariances.resize(cloud->size()); - auto matrices_iterator = cloud_covariances.begin(); - for (auto points_iterator = cloud->begin(); points_iterator != cloud->end(); - ++points_iterator, ++matrices_iterator) { - const PointT& query_point = *points_iterator; - Eigen::Matrix3d& cov = *matrices_iterator; +#pragma omp parallel for default(none) num_threads(threads_) schedule(dynamic, 32) \ + shared(cloud, cloud_covariances, kdtree) \ + firstprivate(mean, cov, nn_indices, nn_dist_sq) + for (std::ptrdiff_t i = 0; i < static_cast(cloud->size()); ++i) { + const PointT& query_point = (*cloud)[i]; // Zero out the cov and mean cov.setZero(); mean.setZero(); @@ -124,6 +147,7 @@ GeneralizedIterativeClosestPoint::computeCovar v = gicp_epsilon_; cov += v * col * col.transpose(); } + cloud_covariances[i] = cov; } } From f7fde268b07a8771d4b42df548f8e717ff744db3 Mon Sep 17 00:00:00 2001 From: Alex Navarro <56406642+alexnavtt@users.noreply.github.com> Date: Fri, 24 May 2024 02:02:08 -0500 Subject: [PATCH 253/288] Added parallel implementation of PrincipalCurvaturesEstimation (#6048) * Added parallel implementation of PrincipalCurvatureEstimation * Fixed openMP integral type error when building on MSVC * Migrated changes to base class * Fixed signed error for OpenMP loop variable on MSVC --- .../features/impl/principal_curvatures.hpp | 102 +++++++++++------- .../pcl/features/principal_curvatures.h | 56 +++++----- 2 files changed, 90 insertions(+), 68 deletions(-) diff --git a/features/include/pcl/features/impl/principal_curvatures.hpp b/features/include/pcl/features/impl/principal_curvatures.hpp index ba32ee2a18a..0d2ddd34ebb 100644 --- a/features/include/pcl/features/impl/principal_curvatures.hpp +++ b/features/include/pcl/features/impl/principal_curvatures.hpp @@ -44,6 +44,22 @@ #include // for pcl::isFinite +/////////////////////////////////////////////////////////////////////////////////////////// +template void +pcl::PrincipalCurvaturesEstimation::setNumberOfThreads (unsigned int nr_threads) +{ +#ifdef _OPENMP + if (nr_threads == 0) + threads_ = omp_get_num_procs(); + else + threads_ = nr_threads; + PCL_DEBUG ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Setting number of threads to %u.\n", threads_); +#else + threads_ = 1; + if (nr_threads != 1) + PCL_WARN ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n"); +#endif // _OPENMP +} ////////////////////////////////////////////////////////////////////////////////////////////// template void @@ -51,62 +67,60 @@ pcl::PrincipalCurvaturesEstimation::computePointPr const pcl::PointCloud &normals, int p_idx, const pcl::Indices &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2) { - EIGEN_ALIGN16 Eigen::Matrix3f I = Eigen::Matrix3f::Identity (); - Eigen::Vector3f n_idx (normals[p_idx].normal[0], normals[p_idx].normal[1], normals[p_idx].normal[2]); - EIGEN_ALIGN16 Eigen::Matrix3f M = I - n_idx * n_idx.transpose (); // projection matrix (into tangent plane) + const auto n_idx = normals[p_idx].getNormalVector3fMap(); + EIGEN_ALIGN16 const Eigen::Matrix3f I = Eigen::Matrix3f::Identity (); + EIGEN_ALIGN16 const Eigen::Matrix3f M = I - n_idx * n_idx.transpose (); // projection matrix (into tangent plane) // Project normals into the tangent plane - Eigen::Vector3f normal; - projected_normals_.resize (indices.size ()); - xyz_centroid_.setZero (); + std::vector > projected_normals (indices.size()); + Eigen::Vector3f xyz_centroid = Eigen::Vector3f::Zero(); for (std::size_t idx = 0; idx < indices.size(); ++idx) { - normal[0] = normals[indices[idx]].normal[0]; - normal[1] = normals[indices[idx]].normal[1]; - normal[2] = normals[indices[idx]].normal[2]; - - projected_normals_[idx] = M * normal; - xyz_centroid_ += projected_normals_[idx]; + const auto normal = normals[indices[idx]].getNormalVector3fMap(); + projected_normals[idx] = M * normal; + xyz_centroid += projected_normals[idx]; } // Estimate the XYZ centroid - xyz_centroid_ /= static_cast (indices.size ()); + xyz_centroid /= static_cast (indices.size ()); // Initialize to 0 - covariance_matrix_.setZero (); + EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero(); // For each point in the cloud for (std::size_t idx = 0; idx < indices.size (); ++idx) { - demean_ = projected_normals_[idx] - xyz_centroid_; + const Eigen::Vector3f demean = projected_normals[idx] - xyz_centroid; - double demean_xy = demean_[0] * demean_[1]; - double demean_xz = demean_[0] * demean_[2]; - double demean_yz = demean_[1] * demean_[2]; + const double demean_xy = demean[0] * demean[1]; + const double demean_xz = demean[0] * demean[2]; + const double demean_yz = demean[1] * demean[2]; - covariance_matrix_(0, 0) += demean_[0] * demean_[0]; - covariance_matrix_(0, 1) += static_cast (demean_xy); - covariance_matrix_(0, 2) += static_cast (demean_xz); + covariance_matrix(0, 0) += demean[0] * demean[0]; + covariance_matrix(0, 1) += static_cast (demean_xy); + covariance_matrix(0, 2) += static_cast (demean_xz); - covariance_matrix_(1, 0) += static_cast (demean_xy); - covariance_matrix_(1, 1) += demean_[1] * demean_[1]; - covariance_matrix_(1, 2) += static_cast (demean_yz); + covariance_matrix(1, 0) += static_cast (demean_xy); + covariance_matrix(1, 1) += demean[1] * demean[1]; + covariance_matrix(1, 2) += static_cast (demean_yz); - covariance_matrix_(2, 0) += static_cast (demean_xz); - covariance_matrix_(2, 1) += static_cast (demean_yz); - covariance_matrix_(2, 2) += demean_[2] * demean_[2]; + covariance_matrix(2, 0) += static_cast (demean_xz); + covariance_matrix(2, 1) += static_cast (demean_yz); + covariance_matrix(2, 2) += demean[2] * demean[2]; } // Extract the eigenvalues and eigenvectors - pcl::eigen33 (covariance_matrix_, eigenvalues_); - pcl::computeCorrespondingEigenVector (covariance_matrix_, eigenvalues_ [2], eigenvector_); - - pcx = eigenvector_ [0]; - pcy = eigenvector_ [1]; - pcz = eigenvector_ [2]; - float indices_size = 1.0f / static_cast (indices.size ()); - pc1 = eigenvalues_ [2] * indices_size; - pc2 = eigenvalues_ [1] * indices_size; + Eigen::Vector3f eigenvalues; + Eigen::Vector3f eigenvector; + pcl::eigen33 (covariance_matrix, eigenvalues); + pcl::computeCorrespondingEigenVector (covariance_matrix, eigenvalues [2], eigenvector); + + pcx = eigenvector [0]; + pcy = eigenvector [1]; + pcz = eigenvector [2]; + const float indices_size = 1.0f / static_cast (indices.size ()); + pc1 = eigenvalues [2] * indices_size; + pc2 = eigenvalues [1] * indices_size; } @@ -123,8 +137,14 @@ pcl::PrincipalCurvaturesEstimation::computeFeature // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense if (input_->is_dense) { +#pragma omp parallel for \ + default(none) \ + shared(output) \ + firstprivate(nn_indices, nn_dists) \ + num_threads(threads_) \ + schedule(dynamic, chunk_size_) // Iterating over the entire index vector - for (std::size_t idx = 0; idx < indices_->size (); ++idx) + for (std::ptrdiff_t idx = 0; idx < static_cast (indices_->size ()); ++idx) { if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) { @@ -142,8 +162,14 @@ pcl::PrincipalCurvaturesEstimation::computeFeature } else { +#pragma omp parallel for \ + default(none) \ + shared(output) \ + firstprivate(nn_indices, nn_dists) \ + num_threads(threads_) \ + schedule(dynamic, chunk_size_) // Iterating over the entire index vector - for (std::size_t idx = 0; idx < indices_->size (); ++idx) + for (std::ptrdiff_t idx = 0; idx < static_cast (indices_->size ()); ++idx) { if (!isFinite ((*input_)[(*indices_)[idx]]) || this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0) diff --git a/features/include/pcl/features/principal_curvatures.h b/features/include/pcl/features/principal_curvatures.h index 620259947dd..f7285a113ce 100644 --- a/features/include/pcl/features/principal_curvatures.h +++ b/features/include/pcl/features/principal_curvatures.h @@ -45,14 +45,13 @@ namespace pcl { /** \brief PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of - * principal surface curvatures for a given point cloud dataset containing points and normals. + * principal surface curvatures for a given point cloud dataset containing points and normals. The output contains + * the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) and min (pc2) + * eigenvalues. Parallel execution is supported through OpenMP. * * The recommended PointOutT is pcl::PrincipalCurvatures. * - * \note The code is stateful as we do not expect this class to be multicore parallelized. Please look at - * \ref NormalEstimationOMP for an example on how to extend this to parallel implementations. - * - * \author Radu B. Rusu, Jared Glover + * \author Radu B. Rusu, Jared Glover, Alex Navarro * \ingroup features */ template @@ -73,15 +72,18 @@ namespace pcl using PointCloudOut = typename Feature::PointCloudOut; using PointCloudIn = pcl::PointCloud; - /** \brief Empty constructor. */ - PrincipalCurvaturesEstimation () : - xyz_centroid_ (Eigen::Vector3f::Zero ()), - demean_ (Eigen::Vector3f::Zero ()), - covariance_matrix_ (Eigen::Matrix3f::Zero ()), - eigenvector_ (Eigen::Vector3f::Zero ()), - eigenvalues_ (Eigen::Vector3f::Zero ()) + /** \brief Initialize the scheduler and set the number of threads to use. + * \param nr_threads the number of hardware threads to use (0 sets the value to automatic) + * \param chunk_size PCL will use dynamic scheduling with this chunk size. Setting it too + * low will lead to more parallelization overhead. Setting it too high + * will lead to a worse balancing between the threads. + */ + PrincipalCurvaturesEstimation (unsigned int nr_threads = 1, int chunk_size = 256) : + chunk_size_(chunk_size) { feature_name_ = "PrincipalCurvaturesEstimation"; + + setNumberOfThreads(nr_threads); }; /** \brief Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent @@ -101,7 +103,19 @@ namespace pcl int p_idx, const pcl::Indices &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2); + /** \brief Initialize the scheduler and set the number of threads to use. The default behavior is + * single threaded exectution + * \param nr_threads the number of hardware threads to use (0 sets the value to automatic) + */ + void + setNumberOfThreads (unsigned int nr_threads); + protected: + /** \brief The number of threads the scheduler should use. */ + unsigned int threads_; + + /** \brief Chunk size for (dynamic) scheduling. */ + int chunk_size_; /** \brief Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) * and min (pc2) eigenvalues for all points given in using the surface in @@ -110,24 +124,6 @@ namespace pcl */ void computeFeature (PointCloudOut &output) override; - - private: - /** \brief A pointer to the input dataset that contains the point normals of the XYZ dataset. */ - std::vector > projected_normals_; - - /** \brief SSE aligned placeholder for the XYZ centroid of a surface patch. */ - Eigen::Vector3f xyz_centroid_; - - /** \brief Temporary point placeholder. */ - Eigen::Vector3f demean_; - - /** \brief Placeholder for the 3x3 covariance matrix at each surface patch. */ - EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_; - - /** \brief SSE aligned eigenvectors placeholder for a covariance matrix. */ - Eigen::Vector3f eigenvector_; - /** \brief eigenvalues placeholder for a covariance matrix. */ - Eigen::Vector3f eigenvalues_; }; } From c6bbf02a084a39a02d9e2fc318a59fe2f1ff55c1 Mon Sep 17 00:00:00 2001 From: Transporter Date: Sun, 26 May 2024 10:37:57 +0200 Subject: [PATCH 254/288] Fix boost hash data type (#6053) * Fix boost hash data type * Change file name generation. --- visualization/src/pcl_visualizer.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 5f073646ac1..bc9b959c246 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -4591,10 +4591,12 @@ pcl::visualization::PCLVisualizer::getUniqueCameraFile (int argc, char **argv) // Build camera filename if (valid) { - unsigned int digest[5]; + boost::uuids::detail::sha1::digest_type digest; sha1.get_digest (digest); sstream << "."; - sstream << std::hex << digest[0] << digest[1] << digest[2] << digest[3] << digest[4]; + for (int i = 0; i < 5; ++i) { + sstream << std::hex << *(reinterpret_cast(&digest[0]) + i); + } sstream << ".cam"; } } From fc8fb1163a7d43849116679e53e6966483f5a2f2 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 24 May 2024 20:06:41 +0200 Subject: [PATCH 255/288] Small fixes and improvements --- common/include/pcl/PCLPointField.h | 3 +++ common/src/PCLPointCloud2.cpp | 1 + .../features/example_difference_of_normals.cpp | 3 ++- .../pcl/features/impl/intensity_gradient.hpp | 7 +++++++ .../include/pcl/features/impl/shot_lrf_omp.hpp | 3 --- filters/include/pcl/filters/convolution_3d.h | 1 + .../include/pcl/filters/impl/convolution_3d.hpp | 1 + .../pcl/filters/impl/radius_outlier_removal.hpp | 3 ++- .../pcl/filters/impl/uniform_sampling.hpp | 2 +- .../pcl/filters/impl/voxel_grid_covariance.hpp | 6 +++--- .../include/pcl/filters/voxel_grid_covariance.h | 3 ++- gpu/features/src/normal_3d.cu | 4 +++- recognition/CMakeLists.txt | 7 +------ registration/include/pcl/registration/gicp.h | 16 ++++++++++++++++ .../impl/correspondence_estimation.hpp | 6 +++++- .../include/pcl/registration/impl/icp_nl.hpp | 5 +---- .../sample_consensus/impl/sac_model_circle3d.hpp | 16 ++++++++++------ .../pcl/sample_consensus/impl/sac_model_cone.hpp | 5 +++++ .../impl/sac_model_ellipse3d.hpp | 10 +++++++--- .../pcl/sample_consensus/sac_model_circle3d.h | 14 ++++++++------ .../pcl/sample_consensus/sac_model_ellipse3d.h | 1 + tools/pcd_viewer.cpp | 3 --- .../include/pcl/visualization/interactor_style.h | 1 + .../include/pcl/visualization/pcl_visualizer.h | 1 + visualization/src/pcl_visualizer.cpp | 1 - 25 files changed, 82 insertions(+), 41 deletions(-) diff --git a/common/include/pcl/PCLPointField.h b/common/include/pcl/PCLPointField.h index 67acf07bd08..f4f12e3e697 100644 --- a/common/include/pcl/PCLPointField.h +++ b/common/include/pcl/PCLPointField.h @@ -45,12 +45,15 @@ namespace pcl s << " " << v.offset << std::endl; s << "datatype: "; switch(v.datatype) { + case ::pcl::PCLPointField::PointFieldTypes::BOOL: s << " BOOL" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::INT8: s << " INT8" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::UINT8: s << " UINT8" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::INT16: s << " INT16" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::UINT16: s << " UINT16" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::INT32: s << " INT32" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::UINT32: s << " UINT32" << std::endl; break; + case ::pcl::PCLPointField::PointFieldTypes::INT64: s << " INT64" << std::endl; break; + case ::pcl::PCLPointField::PointFieldTypes::UINT64: s << " UINT64" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::FLOAT32: s << " FLOAT32" << std::endl; break; case ::pcl::PCLPointField::PointFieldTypes::FLOAT64: s << " FLOAT64" << std::endl; break; default: s << " " << static_cast(v.datatype) << std::endl; diff --git a/common/src/PCLPointCloud2.cpp b/common/src/PCLPointCloud2.cpp index f5a47a2acfa..1d52cc2903b 100644 --- a/common/src/PCLPointCloud2.cpp +++ b/common/src/PCLPointCloud2.cpp @@ -137,6 +137,7 @@ pcl::PCLPointCloud2::concatenate (pcl::PCLPointCloud2 &cloud1, const pcl::PCLPoi cloud1.is_dense = cloud1.is_dense && cloud2.is_dense; cloud1.height = 1; cloud1.width = size1 + size2; + cloud1.row_step = cloud1.width * cloud1.point_step; // changed width if (simple_layout) { diff --git a/examples/features/example_difference_of_normals.cpp b/examples/features/example_difference_of_normals.cpp index d98d68cf5eb..90e830c10f8 100644 --- a/examples/features/example_difference_of_normals.cpp +++ b/examples/features/example_difference_of_normals.cpp @@ -46,8 +46,9 @@ int main (int argc, char *argv[]) bool approx = false; constexpr double decimation = 100; - if(argc < 2){ + if(argc < 3){ std::cerr << "Expected 2 arguments: inputfile outputfile" << std::endl; + return 0; } ///The file to read from. diff --git a/features/include/pcl/features/impl/intensity_gradient.hpp b/features/include/pcl/features/impl/intensity_gradient.hpp index a16b6719421..df54ae8f9e1 100644 --- a/features/include/pcl/features/impl/intensity_gradient.hpp +++ b/features/include/pcl/features/impl/intensity_gradient.hpp @@ -148,6 +148,13 @@ pcl::IntensityGradientEstimation nn_dists (k_); output.is_dense = true; +#ifdef _OPENMP + if (threads_ == 0) { + threads_ = omp_get_num_procs(); + PCL_DEBUG ("[pcl::IntensityGradientEstimation::computeFeature] Setting number of threads to %u.\n", threads_); + } +#endif // _OPENMP + // If the data is dense, we don't need to check for NaN if (surface_->is_dense) { diff --git a/features/include/pcl/features/impl/shot_lrf_omp.hpp b/features/include/pcl/features/impl/shot_lrf_omp.hpp index a28123b3e03..cde3a58d1ee 100644 --- a/features/include/pcl/features/impl/shot_lrf_omp.hpp +++ b/features/include/pcl/features/impl/shot_lrf_omp.hpp @@ -84,9 +84,6 @@ pcl::SHOTLocalReferenceFrameEstimationOMP::computeFeature ( //output_rf.confidence = getLocalRF ((*indices_)[i], rf); //if (output_rf.confidence == std::numeric_limits::max ()) - pcl::Indices n_indices; - std::vector n_sqr_distances; - this->searchForNeighbors ((*indices_)[i], search_parameter_, n_indices, n_sqr_distances); if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits::max ()) { output.is_dense = false; diff --git a/filters/include/pcl/filters/convolution_3d.h b/filters/include/pcl/filters/convolution_3d.h index ee03fdad0cf..31a5a8093e0 100644 --- a/filters/include/pcl/filters/convolution_3d.h +++ b/filters/include/pcl/filters/convolution_3d.h @@ -40,6 +40,7 @@ #pragma once #include +#include // for pcl::search::Search #include #include diff --git a/filters/include/pcl/filters/impl/convolution_3d.hpp b/filters/include/pcl/filters/impl/convolution_3d.hpp index ba5feca8ad0..4fbce289994 100644 --- a/filters/include/pcl/filters/impl/convolution_3d.hpp +++ b/filters/include/pcl/filters/impl/convolution_3d.hpp @@ -40,6 +40,7 @@ #ifndef PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP #define PCL_FILTERS_CONVOLUTION_3D_IMPL_HPP +#include // for isFinite #include #include #include diff --git a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp index 8e13ec06824..a84b2c27f71 100644 --- a/filters/include/pcl/filters/impl/radius_outlier_removal.hpp +++ b/filters/include/pcl/filters/impl/radius_outlier_removal.hpp @@ -138,7 +138,8 @@ pcl::RadiusOutlierRemoval::applyFilterIndices (Indices &indices) { // Perform the radius search // Note: k includes the query point, so is always at least 1 - int k = searcher_->radiusSearch (index, search_radius_, nn_indices, nn_dists); + // last parameter (max_nn) is the maximum number of neighbors returned. If enough neighbors are found so that point can not be an outlier, we stop searching. + int k = searcher_->radiusSearch (index, search_radius_, nn_indices, nn_dists, min_pts_radius_ + 1); // Points having too few neighbors are outliers and are passed to removed indices // Unless negative was set, then it's the opposite condition diff --git a/filters/include/pcl/filters/impl/uniform_sampling.hpp b/filters/include/pcl/filters/impl/uniform_sampling.hpp index f9ceb77563a..d51a6bcee31 100644 --- a/filters/include/pcl/filters/impl/uniform_sampling.hpp +++ b/filters/include/pcl/filters/impl/uniform_sampling.hpp @@ -48,7 +48,7 @@ pcl::UniformSampling::applyFilter (PointCloud &output) // Has the input dataset been set already? if (!input_) { - PCL_WARN ("[pcl::%s::detectKeypoints] No input dataset given!\n", getClassName ().c_str ()); + PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); output.width = output.height = 0; output.clear (); return; diff --git a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp index 0c4c458bac4..1c60d354ee6 100644 --- a/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid_covariance.hpp @@ -442,11 +442,11 @@ pcl::VoxelGridCovariance::getAllNeighborsAtPoint(const PointT& reference ////////////////////////////////////////////////////////////////////////////////////////// template void -pcl::VoxelGridCovariance::getDisplayCloud (pcl::PointCloud& cell_cloud) +pcl::VoxelGridCovariance::getDisplayCloud (pcl::PointCloud& cell_cloud, int pnt_per_cell) const { cell_cloud.clear (); - int pnt_per_cell = 1000; + // for now, we use random generator and normal distribution from boost instead of std because switching to std would make this function up to 2.8 times slower boost::mt19937 rng; boost::normal_distribution<> nd (0.0, 1.0); boost::variate_generator > var_nor (rng, nd); @@ -463,7 +463,7 @@ pcl::VoxelGridCovariance::getDisplayCloud (pcl::PointCloud& ce // Generate points for each occupied voxel with sufficient points. for (auto it = leaves_.begin (); it != leaves_.end (); ++it) { - Leaf& leaf = it->second; + const Leaf& leaf = it->second; if (leaf.nr_points >= min_points_per_voxel_) { diff --git a/filters/include/pcl/filters/voxel_grid_covariance.h b/filters/include/pcl/filters/voxel_grid_covariance.h index d2f69e788a0..2446a53d62c 100644 --- a/filters/include/pcl/filters/voxel_grid_covariance.h +++ b/filters/include/pcl/filters/voxel_grid_covariance.h @@ -434,9 +434,10 @@ namespace pcl /** \brief Get a cloud to visualize each voxels normal distribution. * \param[out] cell_cloud a cloud created by sampling the normal distributions of each voxel + * \param[in] pnt_per_cell how many points should be generated for each cell */ void - getDisplayCloud (pcl::PointCloud& cell_cloud); + getDisplayCloud (pcl::PointCloud& cell_cloud, int pnt_per_cell = 1000) const; /** \brief Search for the k-nearest occupied voxels for the given query point. * \note Only voxels containing a sufficient number of points are used. diff --git a/gpu/features/src/normal_3d.cu b/gpu/features/src/normal_3d.cu index 9dfaefd83f9..9b510d257a2 100644 --- a/gpu/features/src/normal_3d.cu +++ b/gpu/features/src/normal_3d.cu @@ -55,7 +55,8 @@ namespace pcl CTA_SIZE = 256, WAPRS = CTA_SIZE / Warp::WARP_SIZE, - MIN_NEIGHBOORS = 1 + // if there are fewer than 3 neighbors, the normal is definitely garbage + MIN_NEIGHBOORS = 3 }; struct plus @@ -86,6 +87,7 @@ namespace pcl { constexpr float NaN = std::numeric_limits::quiet_NaN(); normals.data[idx] = make_float4(NaN, NaN, NaN, NaN); + return; } const int *ibeg = indices.ptr(idx); diff --git a/recognition/CMakeLists.txt b/recognition/CMakeLists.txt index e4f5cdfbe72..d84ddea9ca2 100644 --- a/recognition/CMakeLists.txt +++ b/recognition/CMakeLists.txt @@ -2,12 +2,7 @@ set(SUBSYS_NAME recognition) set(SUBSYS_DESC "Point cloud recognition library") set(SUBSYS_DEPS common io search kdtree octree features filters registration sample_consensus ml) -if(${PCL_VERSION} VERSION_LESS "1.15.0" AND NOT TARGET Boost::filesystem) - set(DEFAULT OFF) - set(REASON "Boost filesystem is not available.") -else() - set(DEFAULT ON) -endif() +set(DEFAULT ON) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) diff --git a/registration/include/pcl/registration/gicp.h b/registration/include/pcl/registration/gicp.h index 4084c6444e0..eae29598ba9 100644 --- a/registration/include/pcl/registration/gicp.h +++ b/registration/include/pcl/registration/gicp.h @@ -52,6 +52,22 @@ namespace pcl { * The original code uses GSL and ANN while in ours we use FLANN and Newton's method * for optimization (call `useBFGS` to switch to BFGS optimizer, however Newton * is usually faster and more accurate). + * Basic usage example: + * \code + * pcl::GeneralizedIterativeClosestPoint reg; + * reg.setInputSource(src); + * reg.setInputTarget(tgt); + * // use default parameters or set them yourself, for example: + * // reg.setMaximumIterations(...); + * // reg.setTransformationEpsilon(...); + * // reg.setRotationEpsilon(...); + * // reg.setCorrespondenceRandomness(...); + * pcl::PointCloud::Ptr output(new pcl::PointCloud); + * // supply a better guess, if possible: + * Eigen::Matrix4f guess = Eigen::Matrix4f::Identity(); + * reg.align(*output, guess); + * std::cout << reg.getFinalTransformation() << std::endl; + * \endcode * \author Nizar Sallem * \ingroup registration */ diff --git a/registration/include/pcl/registration/impl/correspondence_estimation.hpp b/registration/include/pcl/registration/impl/correspondence_estimation.hpp index e21b1ffdd95..676c17876cf 100644 --- a/registration/include/pcl/registration/impl/correspondence_estimation.hpp +++ b/registration/include/pcl/registration/impl/correspondence_estimation.hpp @@ -43,6 +43,7 @@ #include #include +#include // for isXYZFinite namespace pcl { @@ -169,6 +170,8 @@ CorrespondenceEstimation::determineCorresponde // Both point types MUST be registered using the POINT_CLOUD_REGISTER_POINT_STRUCT // macro! const auto& pt = detail::pointCopyOrRef(input_, idx); + if (!input_->is_dense && !pcl::isXYZFinite(pt)) + continue; tree_->nearestKSearch(pt, 1, index, distance); if (distance[0] > max_dist_sqr) continue; @@ -251,7 +254,8 @@ CorrespondenceEstimation:: // macro! const auto& pt_src = detail::pointCopyOrRef(input_, idx); - + if (!input_->is_dense && !pcl::isXYZFinite(pt_src)) + continue; tree_->nearestKSearch(pt_src, 1, index, distance); if (distance[0] > max_dist_sqr) continue; diff --git a/registration/include/pcl/registration/impl/icp_nl.hpp b/registration/include/pcl/registration/impl/icp_nl.hpp index 3e01b9810a6..b7357385022 100644 --- a/registration/include/pcl/registration/impl/icp_nl.hpp +++ b/registration/include/pcl/registration/impl/icp_nl.hpp @@ -37,7 +37,4 @@ * $Id$ * */ -#ifndef PCL_REGISTRATION_ICP_NL_HPP_ -#define PCL_REGISTRATION_ICP_NL_HPP_ - -#endif /* PCL_REGISTRATION_ICP_NL_HPP_ */ +PCL_DEPRECATED_HEADER(1, 18, "Do not include icp_nl.hpp, it is empty.") 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 435e5d2c3f0..0ce6ce69247 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 @@ -194,7 +194,9 @@ pcl::SampleConsensusModelCircle3D::selectWithinDistance ( return; } inliers.clear (); + error_sqr_dists_.clear (); inliers.reserve (indices_->size ()); + error_sqr_dists_.reserve (indices_->size ()); const auto squared_threshold = threshold * threshold; // Iterate through the 3d points and calculate the distances from them to the sphere @@ -221,10 +223,12 @@ pcl::SampleConsensusModelCircle3D::selectWithinDistance ( Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); Eigen::Vector3d distanceVector = P - K; - if (distanceVector.squaredNorm () < squared_threshold) + const double sqr_dist = distanceVector.squaredNorm (); + if (sqr_dist < squared_threshold) { // Returns the indices of the points whose distances are smaller than the threshold inliers.push_back ((*indices_)[i]); + error_sqr_dists_.push_back (sqr_dist); } } } @@ -338,11 +342,11 @@ pcl::SampleConsensusModelCircle3D::projectPoints ( pcl::for_each_type (NdConcatenateFunctor ((*input_)[i], projected_points[i])); // Iterate through the 3d points and calculate the distances from them to the plane - for (std::size_t i = 0; i < inliers.size (); ++i) + for (const auto &inlier : inliers) { // what i have: // P : Sample Point - Eigen::Vector3d P ((*input_)[inliers[i]].x, (*input_)[inliers[i]].y, (*input_)[inliers[i]].z); + Eigen::Vector3d P ((*input_)[inlier].x, (*input_)[inlier].y, (*input_)[inlier].z); // C : Circle Center Eigen::Vector3d C (model_coefficients[0], model_coefficients[1], model_coefficients[2]); // N : Circle (Plane) Normal @@ -361,9 +365,9 @@ pcl::SampleConsensusModelCircle3D::projectPoints ( // K : Point on Circle Eigen::Vector3d K = C + r * helper_vectorP_projC.normalized (); - projected_points[i].x = static_cast (K[0]); - projected_points[i].y = static_cast (K[1]); - projected_points[i].z = static_cast (K[2]); + projected_points[inlier].x = static_cast (K[0]); + projected_points[inlier].y = static_cast (K[1]); + projected_points[inlier].z = static_cast (K[2]); } } else 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 e0be7718f0d..c3d3cd835e9 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 @@ -87,6 +87,11 @@ pcl::SampleConsensusModelCone::computeModelCoefficients ( Eigen::Vector4f ortho31 = n3.cross3(n1); float denominator = n1.dot(ortho23); + if (std::abs(denominator) < Eigen::NumTraits::dummy_precision ()) + { + PCL_ERROR ("[pcl::SampleConsensusModelCone::computeModelCoefficients] Impossible to compute stable model with these points.\n"); + return (false); + } float d1 = p1.dot (n1); float d2 = p2.dot (n2); diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp index 247a58e3d1f..33740e44904 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_ellipse3d.hpp @@ -235,7 +235,7 @@ pcl::SampleConsensusModelEllipse3D::computeModelCoefficients (const Indi model_coefficients[10] = static_cast(x_axis[2]); - PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::computeModelCoefficients] Model is (%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g).\n", + PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::computeModelCoefficients] Model is (%g,%g,%g,%g,%g,%g,%g,%g,%g,%g,%g).\n", model_coefficients[0], model_coefficients[1], model_coefficients[2], model_coefficients[3], model_coefficients[4], model_coefficients[5], model_coefficients[6], model_coefficients[7], model_coefficients[8], model_coefficients[9], model_coefficients[10]); @@ -312,12 +312,14 @@ pcl::SampleConsensusModelEllipse3D::selectWithinDistance ( Indices &inliers) { inliers.clear(); + error_sqr_dists_.clear(); // Check if the model is valid given the user constraints if (!isModelValid (model_coefficients)) { return; } inliers.reserve (indices_->size ()); + error_sqr_dists_.reserve (indices_->size ()); // c : Ellipse Center const Eigen::Vector3f c(model_coefficients[0], model_coefficients[1], model_coefficients[2]); @@ -358,10 +360,12 @@ pcl::SampleConsensusModelEllipse3D::selectWithinDistance ( float th_opt; const Eigen::Vector2f distanceVector = dvec2ellipse(params, p_(0), p_(1), th_opt); - if (distanceVector.squaredNorm() < squared_threshold) + const double sqr_dist = distanceVector.squaredNorm(); + if (sqr_dist < squared_threshold) { // Returns the indices of the points whose distances are smaller than the threshold inliers.push_back ((*indices_)[i]); + error_sqr_dists_.push_back (sqr_dist); } } } @@ -453,7 +457,7 @@ pcl::SampleConsensusModelEllipse3D::optimizeModelCoefficients ( optimized_coefficients[i] = static_cast (coeff[i]); // Compute the L2 norm of the residuals - PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g %g %g %g %g %g %g \nFinal solution: %g %g %g %g %g %g %g %g %g %g %g %g %g\n", + PCL_DEBUG ("[pcl::SampleConsensusModelEllipse3D::optimizeModelCoefficients] LM solver finished with exit code %i, having a residual norm of %g. \nInitial solution: %g %g %g %g %g %g %g %g %g %g %g\nFinal solution: %g %g %g %g %g %g %g %g %g %g %g\n", info, lm.fvec.norm (), model_coefficients[0], diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h b/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h index d4c6e53d980..7531b5f9612 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_circle3d.h @@ -65,6 +65,7 @@ namespace pcl using SampleConsensusModel::indices_; using SampleConsensusModel::radius_min_; using SampleConsensusModel::radius_max_; + using SampleConsensusModel::error_sqr_dists_; using PointCloud = typename SampleConsensusModel::PointCloud; using PointCloudPtr = typename SampleConsensusModel::PointCloudPtr; @@ -232,18 +233,19 @@ namespace pcl */ int operator() (const Eigen::VectorXd &x, Eigen::VectorXd &fvec) const { + // Same for all points, so define outside of loop: + // C : Circle Center + const Eigen::Vector3d C (x[0], x[1], x[2]); + // N : Circle (Plane) Normal + const Eigen::Vector3d N (x[4], x[5], x[6]); + // r : Radius + const double r = x[3]; for (int i = 0; i < values (); ++i) { // what i have: // P : Sample Point Eigen::Vector3d P = (*model_->input_)[indices_[i]].getVector3fMap().template cast(); - // C : Circle Center - Eigen::Vector3d C (x[0], x[1], x[2]); - // N : Circle (Plane) Normal - Eigen::Vector3d N (x[4], x[5], x[6]); - // r : Radius - double r = x[3]; Eigen::Vector3d helperVectorPC = P - C; // 1.1. get line parameter diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_ellipse3d.h b/sample_consensus/include/pcl/sample_consensus/sac_model_ellipse3d.h index fb6e8d49b1c..11b22de1585 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_ellipse3d.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_ellipse3d.h @@ -46,6 +46,7 @@ namespace pcl using SampleConsensusModel::indices_; using SampleConsensusModel::radius_min_; using SampleConsensusModel::radius_max_; + using SampleConsensusModel::error_sqr_dists_; using PointCloud = typename SampleConsensusModel::PointCloud; using PointCloudPtr = typename SampleConsensusModel::PointCloudPtr; diff --git a/tools/pcd_viewer.cpp b/tools/pcd_viewer.cpp index 7d045fc9cb7..6084d82a7ed 100644 --- a/tools/pcd_viewer.cpp +++ b/tools/pcd_viewer.cpp @@ -513,9 +513,6 @@ main (int argc, char** argv) if (useEDLRendering) p->enableEDLRendering(); - // Set whether or not we should be using the vtkVertexBufferObjectMapper - p->setUseVbos (use_vbos); - if (!p->cameraParamsSet () && !p->cameraFileLoaded ()) { Eigen::Matrix3f rotation; diff --git a/visualization/include/pcl/visualization/interactor_style.h b/visualization/include/pcl/visualization/interactor_style.h index 4202b1952b7..823235e0b8d 100644 --- a/visualization/include/pcl/visualization/interactor_style.h +++ b/visualization/include/pcl/visualization/interactor_style.h @@ -155,6 +155,7 @@ namespace pcl * buffer objects by default, transparently for the user. * \param[in] use_vbos set to true to use VBOs */ + PCL_DEPRECATED(1, 18, "this function has no effect") inline void setUseVbos (const bool use_vbos) { use_vbos_ = use_vbos; } diff --git a/visualization/include/pcl/visualization/pcl_visualizer.h b/visualization/include/pcl/visualization/pcl_visualizer.h index b376ab807ba..bd76e4f05e0 100644 --- a/visualization/include/pcl/visualization/pcl_visualizer.h +++ b/visualization/include/pcl/visualization/pcl_visualizer.h @@ -1961,6 +1961,7 @@ namespace pcl * buffer objects by default, transparently for the user. * \param[in] use_vbos set to true to use VBOs */ + PCL_DEPRECATED(1, 18, "this function has no effect") void setUseVbos (bool use_vbos); diff --git a/visualization/src/pcl_visualizer.cpp b/visualization/src/pcl_visualizer.cpp index 5f073646ac1..41dcb006b6a 100644 --- a/visualization/src/pcl_visualizer.cpp +++ b/visualization/src/pcl_visualizer.cpp @@ -439,7 +439,6 @@ void pcl::visualization::PCLVisualizer::setupStyle () style_->setCloudActorMap (cloud_actor_map_); style_->setShapeActorMap (shape_actor_map_); style_->UseTimersOn (); - style_->setUseVbos (use_vbos_); } ///////////////////////////////////////////////////////////////////////////////////////////// From 1144afdb3ae941fa6cfab462850bfc96f72695ec Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 24 May 2024 20:10:55 +0200 Subject: [PATCH 256/288] Improve documentation --- doc/tutorials/content/compiling_pcl_windows.rst | 3 +++ doc/tutorials/content/iterative_closest_point.rst | 2 +- doc/tutorials/content/normal_distributions_transform.rst | 2 +- doc/tutorials/content/pcl_vcpkg_windows.rst | 8 +++++++- .../content/sources/bspline_fitting/bspline_fitting.cpp | 2 +- .../iterative_closest_point/iterative_closest_point.cpp | 2 +- .../normal_distributions_transform.cpp | 4 ++-- filters/include/pcl/filters/approximate_voxel_grid.h | 1 + filters/include/pcl/filters/uniform_sampling.h | 1 + .../pcl/compression/octree_pointcloud_compression.h | 2 +- octree/include/pcl/octree/octree_search.h | 2 -- recognition/include/pcl/recognition/dotmod.h | 1 + .../include/pcl/recognition/hv/greedy_verification.h | 1 + recognition/include/pcl/recognition/linemod/line_rgbd.h | 1 + .../include/pcl/registration/correspondence_estimation.h | 4 ++-- registration/registration.doxy | 2 ++ 16 files changed, 26 insertions(+), 12 deletions(-) diff --git a/doc/tutorials/content/compiling_pcl_windows.rst b/doc/tutorials/content/compiling_pcl_windows.rst index 0f3577cb921..e93ef5bf563 100644 --- a/doc/tutorials/content/compiling_pcl_windows.rst +++ b/doc/tutorials/content/compiling_pcl_windows.rst @@ -332,3 +332,6 @@ Using PCL We finally managed to compile the Point Cloud Library (PCL) as binaries for Windows. You can start using them in your project by following the :ref:`using_pcl_pcl_config` tutorial. + +.. note:: + You may get errors when your program is linked if you use specific point types that are not used so often (so for example `pcl::PointXYZ` and `pcl::PointXYZI` are usually not affected). Of course, the first thing you should check is whether you correctly link to all PCL libraries (`target_link_libraries( ${PCL_LIBRARIES})` in CMake). The next thing you can try is adding `#define PCL_NO_PRECOMPILE` before including any PCL headers. The background is that on Windows, PCL is always compiled with `PCL_ONLY_CORE_POINT_TYPES` enabled, otherwise some PCL modules (e.g. pcl_features) would fail to build due to limitations of the Windows linker. The effect is that the templated classes are only instantiated for some commonly used point types, not for all. For further explanations, see the :ref:`adding_custom_ptype` tutorial. diff --git a/doc/tutorials/content/iterative_closest_point.rst b/doc/tutorials/content/iterative_closest_point.rst index 80782c9bbf9..024b685dec5 100644 --- a/doc/tutorials/content/iterative_closest_point.rst +++ b/doc/tutorials/content/iterative_closest_point.rst @@ -107,7 +107,7 @@ You will see something similar to:: 1 [20.000000%]. [pcl::IterativeClosestPoint::computeTransformation] Convergence reached. Number of iterations: 1 out of 0. Transformation difference: 0.700001 - has converged:1 score: 1.95122e-14 + ICP has converged, score: 1.95122e-14 1 4.47035e-08 -3.25963e-09 0.7 2.98023e-08 1 -1.08499e-07 -2.98023e-08 1.30385e-08 -1.67638e-08 1 1.86265e-08 diff --git a/doc/tutorials/content/normal_distributions_transform.rst b/doc/tutorials/content/normal_distributions_transform.rst index cf85d9ec5d6..5363612ba72 100644 --- a/doc/tutorials/content/normal_distributions_transform.rst +++ b/doc/tutorials/content/normal_distributions_transform.rst @@ -110,4 +110,4 @@ You should see results similar those below as well as a visualization of the ali Loaded 112586 data points from room_scan1.pcd Loaded 112624 data points from room_scan2.pcd Filtered cloud contains 12433 data points from room_scan2.pcd - Normal Distributions Transform has converged:1 score: 0.638694 + Normal Distributions Transform has converged, score: 0.638694 diff --git a/doc/tutorials/content/pcl_vcpkg_windows.rst b/doc/tutorials/content/pcl_vcpkg_windows.rst index f97ebd747c8..33d40cbe702 100644 --- a/doc/tutorials/content/pcl_vcpkg_windows.rst +++ b/doc/tutorials/content/pcl_vcpkg_windows.rst @@ -88,7 +88,7 @@ will install PCL with default options as well as default triplet type (ie. x86). .. note:: If there are new features or bugfixes that are not yet part of a release, - you can try to use --head, which downloads the master of PCL. + you can try to use `--head`, which downloads the master of PCL. You can see the available PCL version and options in VCPKG `here `_. @@ -100,6 +100,9 @@ And all features: ./vcpkg install pcl[*] +.. note:: + If you want to use anything from the PCL visualization module (like the `PCLVisualizer` for example), you need to explicitly request this from vcpkg by `./vcpkg install pcl[visualization]` or `./vcpkg install pcl[*]` (it is disabled by default). + If you want to install with a different triplet type, the easiest way is: ./vcpkg install pcl --triplet triplet_type @@ -136,6 +139,9 @@ Find PCL using CMake To use PCL in CMake project, take a look at Kunal Tyagi's minimal example `in this repository `_ +.. note:: + You may get errors when your program is linked if you use specific point types that are not used so often (so for example `pcl::PointXYZ` and `pcl::PointXYZI` are usually not affected). Of course, the first thing you should check is whether you correctly link to all PCL libraries (`target_link_libraries( ${PCL_LIBRARIES})` in CMake). The next thing you can try is adding `#define PCL_NO_PRECOMPILE` before including any PCL headers. The background is that on Windows, PCL is always compiled with `PCL_ONLY_CORE_POINT_TYPES` enabled, otherwise some PCL modules (e.g. pcl_features) would fail to build due to limitations of the Windows linker. The effect is that the templated classes are only instantiated for some commonly used point types, not for all. For further explanations, see the :ref:`adding_custom_ptype` tutorial. + Install PCL dependencies for contributions ========================================== diff --git a/doc/tutorials/content/sources/bspline_fitting/bspline_fitting.cpp b/doc/tutorials/content/sources/bspline_fitting/bspline_fitting.cpp index 2bcb0a174b6..4119d93b84e 100644 --- a/doc/tutorials/content/sources/bspline_fitting/bspline_fitting.cpp +++ b/doc/tutorials/content/sources/bspline_fitting/bspline_fitting.cpp @@ -25,7 +25,7 @@ main (int argc, char *argv[]) if (argc < 3) { printf ("\nUsage: pcl_example_nurbs_fitting_surface pcd-in-file 3dm-out-file\n\n"); - exit (0); + exit (EXIT_FAILURE); } pcd_file = argv[1]; file_3dm = argv[2]; 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 d45ab78c837..202b353826e 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 @@ -40,7 +40,7 @@ int pcl::PointCloud Final; icp.align(Final); - std::cout << "has converged:" << icp.hasConverged() << " score: " << + std::cout << "ICP has " << (icp.hasConverged()?"converged":"not converged") << ", score: " << icp.getFitnessScore() << std::endl; std::cout << icp.getFinalTransformation() << std::endl; 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 b5a525d25da..732eb408fab 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 @@ -69,8 +69,8 @@ main () pcl::PointCloud::Ptr output_cloud (new pcl::PointCloud); ndt.align (*output_cloud, init_guess); - std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged () - << " score: " << ndt.getFitnessScore () << std::endl; + std::cout << "Normal Distributions Transform has " << (ndt.hasConverged ()?"converged":"not converged") + << ", score: " << ndt.getFitnessScore () << std::endl; // Transforming unfiltered, input cloud using found transform. pcl::transformPointCloud (*input_cloud, *output_cloud, ndt.getFinalTransformation ()); diff --git a/filters/include/pcl/filters/approximate_voxel_grid.h b/filters/include/pcl/filters/approximate_voxel_grid.h index 95e16a1d868..07bf3404cb3 100644 --- a/filters/include/pcl/filters/approximate_voxel_grid.h +++ b/filters/include/pcl/filters/approximate_voxel_grid.h @@ -92,6 +92,7 @@ namespace pcl /** \brief ApproximateVoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data. * Thus, this is similar to the \ref VoxelGrid filter. * This class works best if points that are stored in memory next to each other (in the input point cloud), are also somewhat close in 3D euclidean space (this is for example usually the case for organized point clouds). If the points have no storage order (e.g. in synthetic, randomly generated point clouds), this class will give very poor results, and \ref VoxelGrid should be used instead. + * \sa VoxelGrid * \author James Bowman, Radu B. Rusu * \ingroup filters */ diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index 42f5febd804..d814adbf265 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -52,6 +52,7 @@ namespace pcl * Then, in each *voxel* (i.e., 3D box), all the points present will be * approximated (i.e., *downsampled*) with the closest point to the center of the voxel. * + * \sa VoxelGrid * \author Radu Bogdan Rusu * \ingroup filters */ diff --git a/io/include/pcl/compression/octree_pointcloud_compression.h b/io/include/pcl/compression/octree_pointcloud_compression.h index d2eae276364..4e2178fe634 100644 --- a/io/include/pcl/compression/octree_pointcloud_compression.h +++ b/io/include/pcl/compression/octree_pointcloud_compression.h @@ -55,7 +55,7 @@ namespace pcl namespace io { /** \brief @b Octree pointcloud compression class - * \note This class enables compression and decompression of point cloud data based on octree data structures. + * \note This class enables compression and decompression of point cloud data based on octree data structures. It is a lossy compression. See also `PCDWriter` for another way to compress point cloud data. * \note * \note typename: PointT: type of point used in pointcloud * \author Julius Kammerl (julius@kammerl.de) diff --git a/octree/include/pcl/octree/octree_search.h b/octree/include/pcl/octree/octree_search.h index c22fa85473e..da69f80c6ba 100644 --- a/octree/include/pcl/octree/octree_search.h +++ b/octree/include/pcl/octree/octree_search.h @@ -159,7 +159,6 @@ class OctreePointCloudSearch * \param[in] query_index the index in \a cloud representing the query point * \param[out] result_index the resultant index of the neighbor point * \param[out] sqr_distance the resultant squared distance to the neighboring point - * \return number of neighbors found */ inline void approxNearestSearch(const PointCloud& cloud, @@ -184,7 +183,6 @@ class OctreePointCloudSearch * position in the indices vector. * \param[out] result_index the resultant index of the neighbor point * \param[out] sqr_distance the resultant squared distance to the neighboring point - * \return number of neighbors found */ void approxNearestSearch(uindex_t query_index, index_t& result_index, float& sqr_distance); diff --git a/recognition/include/pcl/recognition/dotmod.h b/recognition/include/pcl/recognition/dotmod.h index b1c6451997f..be0e5661dfe 100644 --- a/recognition/include/pcl/recognition/dotmod.h +++ b/recognition/include/pcl/recognition/dotmod.h @@ -59,6 +59,7 @@ namespace pcl /** * \brief Template matching using the DOTMOD approach. * \author Stefan Holzer, Stefan Hinterstoisser + * \ingroup recognition */ class PCL_EXPORTS DOTMOD { diff --git a/recognition/include/pcl/recognition/hv/greedy_verification.h b/recognition/include/pcl/recognition/hv/greedy_verification.h index 40c874d77c6..fb7f0e95205 100644 --- a/recognition/include/pcl/recognition/hv/greedy_verification.h +++ b/recognition/include/pcl/recognition/hv/greedy_verification.h @@ -47,6 +47,7 @@ namespace pcl /** * \brief A greedy hypothesis verification method * \author Aitor Aldoma + * \ingroup recognition */ template diff --git a/recognition/include/pcl/recognition/linemod/line_rgbd.h b/recognition/include/pcl/recognition/linemod/line_rgbd.h index d9f9cd5dec8..b955f38554f 100644 --- a/recognition/include/pcl/recognition/linemod/line_rgbd.h +++ b/recognition/include/pcl/recognition/linemod/line_rgbd.h @@ -67,6 +67,7 @@ namespace pcl /** \brief High-level class for template matching using the LINEMOD approach based on RGB and Depth data. * \author Stefan Holzer + * \ingroup recognition */ template class PCL_EXPORTS LineRGBD diff --git a/registration/include/pcl/registration/correspondence_estimation.h b/registration/include/pcl/registration/correspondence_estimation.h index d8c66b050fd..7dcffc258cf 100644 --- a/registration/include/pcl/registration/correspondence_estimation.h +++ b/registration/include/pcl/registration/correspondence_estimation.h @@ -383,9 +383,9 @@ class CorrespondenceEstimationBase : public PCLBase { unsigned int num_threads_{1}; }; -/** \brief @b CorrespondenceEstimation represents the base class for +/** \brief @b CorrespondenceEstimation represents a simple class for * determining correspondences between target and query point - * sets/features. + * sets/features, using nearest neighbor search. * * Code example: * diff --git a/registration/registration.doxy b/registration/registration.doxy index eb49a954f94..bc15c427cf7 100644 --- a/registration/registration.doxy +++ b/registration/registration.doxy @@ -15,6 +15,8 @@ The pcl_registration library implements a plethora of point cloud registration algorithms for both organized and unorganized (general purpose) datasets. +PCL's methods to register one point cloud to another can be divided into two groups: the first group needs an initial guess of the transformation (pcl::IterativeClosestPoint, pcl::IterativeClosestPointWithNormals, pcl::IterativeClosestPointNonLinear, pcl::GeneralizedIterativeClosestPoint, pcl::GeneralizedIterativeClosestPoint6D, pcl::NormalDistributionsTransform, pcl::NormalDistributionsTransform2D), and the second group does not need a guess but is usually slower and less accurate (pcl::registration::FPCSInitialAlignment, pcl::registration::KFPCSInitialAlignment, pcl::SampleConsensusInitialAlignment, pcl::SampleConsensusPrerejective, pcl::PPFRegistration). Many parts of the registration process can be configured and swapped out, like the correspondence estimation, correspondence rejection, or the transformation estimation. And finally, PCL also has methods if there are more than two point clouds to align (pcl::registration::ELCH, pcl::registration::LUM, pcl::PairwiseGraphRegistration, pcl::registration::IncrementalRegistration, pcl::registration::MetaRegistration). + \image html http://www.pointclouds.org/assets/images/contents/documentation/registration_outdoor.png \image html http://www.pointclouds.org/assets/images/contents/documentation/registration_closeup.png From 6206026091bb39ac7f8a0db16e74cf1077f180db Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Fri, 24 May 2024 20:11:55 +0200 Subject: [PATCH 257/288] Use Ubuntu 24.04 on CI --- .ci/azure-pipelines/azure-pipelines.yaml | 8 ++++---- .ci/azure-pipelines/build/ubuntu.yaml | 3 +-- README.md | 4 ++-- 3 files changed, 7 insertions(+), 8 deletions(-) diff --git a/.ci/azure-pipelines/azure-pipelines.yaml b/.ci/azure-pipelines/azure-pipelines.yaml index 5b580a05ebb..1ddd73dd954 100644 --- a/.ci/azure-pipelines/azure-pipelines.yaml +++ b/.ci/azure-pipelines/azure-pipelines.yaml @@ -24,8 +24,8 @@ resources: image: pointcloudlibrary/env:20.04 - container: env2204 image: pointcloudlibrary/env:22.04 - - container: env2304 - image: pointcloudlibrary/env:23.04 + - container: env2404 + image: pointcloudlibrary/env:24.04 stages: - stage: formatting @@ -49,8 +49,8 @@ stages: CXX: g++ BUILD_GPU: ON CMAKE_ARGS: '-DPCL_WARNINGS_ARE_ERRORS=ON' - 23.04 GCC: # latest Ubuntu - CONTAINER: env2304 + 24.04 GCC: # latest Ubuntu + CONTAINER: env2404 CC: gcc CXX: g++ BUILD_GPU: ON diff --git a/.ci/azure-pipelines/build/ubuntu.yaml b/.ci/azure-pipelines/build/ubuntu.yaml index 961e34ea128..ea9897fd376 100644 --- a/.ci/azure-pipelines/build/ubuntu.yaml +++ b/.ci/azure-pipelines/build/ubuntu.yaml @@ -27,8 +27,7 @@ steps: -DBUILD_GPU=$BUILD_GPU \ -DBUILD_cuda_io=$BUILD_GPU \ -DBUILD_gpu_tracking=$BUILD_GPU \ - -DBUILD_gpu_surface=$BUILD_GPU \ - -DBUILD_gpu_people=$BUILD_GPU + -DBUILD_gpu_surface=$BUILD_GPU # Temporary fix to ensure no tests are skipped cmake $(Build.SourcesDirectory) displayName: 'CMake Configuration' diff --git a/README.md b/README.md index 0fca1a92726..e42eb23a82d 100644 --- a/README.md +++ b/README.md @@ -23,7 +23,7 @@ Continuous integration [ci-latest-build]: https://dev.azure.com/PointCloudLibrary/pcl/_build/latest?definitionId=9&branchName=master [ci-ubuntu-20.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2020.04%20GCC&label=Ubuntu%2020.04%20GCC [ci-ubuntu-22.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=Ubuntu&configuration=Ubuntu%2022.04%20Clang&label=Ubuntu%2022.04%20Clang -[ci-ubuntu-23.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2023.04%20GCC&label=Ubuntu%2023.04%20GCC +[ci-ubuntu-24.04]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20GCC&jobName=Ubuntu&configuration=Ubuntu%2024.04%20GCC&label=Ubuntu%2024.04%20GCC [ci-windows-x86]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x86&label=Windows%20VS2019%20x86 [ci-windows-x64]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20MSVC&jobName=Windows%20Build&configuration=Windows%20Build%20x64&label=Windows%20VS2019%20x64 [ci-macos-12]: https://dev.azure.com/PointCloudLibrary/pcl/_apis/build/status/9?branchName=master&stageName=Build%20Clang&jobName=macOS&configuration=macOS%20Monterey%2012&label=macOS%20Monterey%2012 @@ -33,7 +33,7 @@ Continuous integration Build Platform | Status ------------------------ | ------------------------------------------------------------------------------------------------- | -Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
      [![Status][ci-ubuntu-22.04]][ci-latest-build]
      [![Status][ci-ubuntu-23.04]][ci-latest-build] | +Ubuntu | [![Status][ci-ubuntu-20.04]][ci-latest-build]
      [![Status][ci-ubuntu-22.04]][ci-latest-build]
      [![Status][ci-ubuntu-24.04]][ci-latest-build] | Windows | [![Status][ci-windows-x86]][ci-latest-build]
      [![Status][ci-windows-x64]][ci-latest-build] | macOS | [![Status][ci-macos-12]][ci-latest-build]
      [![Status][ci-macos-13]][ci-latest-build] | Documentation | [![Status][ci-docs]][ci-latest-docs] | From ca49c6328340f62b455a823021de52f2e2672a81 Mon Sep 17 00:00:00 2001 From: Oliver <50930405+Olli1080@users.noreply.github.com> Date: Tue, 28 May 2024 13:24:36 +0200 Subject: [PATCH 258/288] Fix obj loader (#6047) * Fix obj loader Remove restriction that normals are per vertex * Fix signedness error * Fix introduced error Files without normals now created errors * Fix face indices Face indices would have been first vertex index for all vertices * Fix formatting * Fix formatting * Apply clang-tidy recommendation for performance-faster-string-find * Fix normal mapping Vector3f storage was uninitialized * Add normal testing to obj test --- io/src/obj_io.cpp | 223 ++++++++++++++++++++++++++++++++++++-------- test/io/test_io.cpp | 21 ++++- 2 files changed, 203 insertions(+), 41 deletions(-) diff --git a/io/src/obj_io.cpp b/io/src/obj_io.cpp index 19d454e120b..1e19889e8cc 100644 --- a/io/src/obj_io.cpp +++ b/io/src/obj_io.cpp @@ -546,10 +546,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, // Get normal_x and rgba fields indices int normal_x_field = -1; + std::vector normals; + + //vector[idx of vertex] + std::vector normal_mapping; + // std::size_t rgba_field = 0; for (std::size_t i = 0; i < cloud.fields.size (); ++i) if (cloud.fields[i].name == "normal_x") { + normals.reserve(cloud.width); + normal_mapping.resize(cloud.width, Eigen::Vector3f::Zero()); normal_x_field = i; break; } @@ -602,22 +609,13 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, // Vertex normal if (st[0] == "vn") { - if (normal_idx >= cloud.width) - { - if (normal_idx == cloud.width) - PCL_WARN ("[pcl:OBJReader] Too many vertex normals (expected %d), skipping remaining normals.\n", cloud.width, normal_idx + 1); - ++normal_idx; - continue; - } try { - for (int i = 1, f = normal_x_field; i < 4; ++i, ++f) - { - float value = boost::lexical_cast (st[i]); - memcpy (&cloud.data[normal_idx * cloud.point_step + cloud.fields[f].offset], - &value, - sizeof (float)); - } + normals.emplace_back( + boost::lexical_cast (st[1]), + boost::lexical_cast (st[2]), + boost::lexical_cast (st[3]) + ); ++normal_idx; } catch (const boost::bad_lexical_cast&) @@ -627,6 +625,47 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, } continue; } + + // Face + if (st[0] == "f") + { + std::vector f_st; + std::string n_st; + + pcl::Vertices face_vertices; face_vertices.vertices.resize(st.size() - 1); + for (std::size_t i = 1; i < st.size (); ++i) + { + if (st[i].find("//") != std::string::npos) + { + //covers format v//vn + pcl::split(f_st, st[i], "//"); + n_st = f_st[1]; + } + else if (st[i].find('/') != std::string::npos) + { + //covers format v/vt/vn and v/vt + pcl::split(f_st, st[i], "/"); + if (f_st.size() > 2) + n_st = f_st[2]; + } + else + f_st = { st[i] }; + + int v = std::stoi(f_st[0]); + v = (v < 0) ? point_idx + v : v - 1; + face_vertices.vertices[i - 1] = v; + + //handle normals + if (!n_st.empty()) + { + int n = std::stoi(n_st); + n = (n < 0) ? normal_idx + n : n - 1; + + normal_mapping[v] += normals[n]; + } + } + continue; + } } } catch (const char *exception) @@ -636,6 +675,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, return (-1); } + if (!normal_mapping.empty()) + { + for (uindex_t i = 0, main_offset = 0; i < cloud.width; ++i, main_offset += cloud.point_step) + { + normal_mapping[i].normalize(); + + for (int j = 0, f = normal_x_field; j < 3; ++j, ++f) + memcpy(&cloud.data[main_offset + cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float)); + } + } + double total_time = tt.toc (); PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a dense cloud in %g ms with %d points. Available dimensions: %s.\n", file_name.c_str (), total_time, @@ -684,16 +734,24 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, // Get normal_x and rgba fields indices int normal_x_field = -1; + std::vector normals; + + //vector[idx of vertex] + std::vector normal_mapping; + // std::size_t rgba_field = 0; for (std::size_t i = 0; i < mesh.cloud.fields.size (); ++i) if (mesh.cloud.fields[i].name == "normal_x") { + normals.reserve(mesh.cloud.width); + normal_mapping.resize(mesh.cloud.width, Eigen::Vector3f::Zero()); normal_x_field = i; break; } std::size_t v_idx = 0; std::size_t f_idx = 0; + std::size_t vt_idx = 0; std::string line; std::vector st; std::vector > coordinates; @@ -740,13 +798,11 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, { try { - for (int i = 1, f = normal_x_field; i < 4; ++i, ++f) - { - float value = boost::lexical_cast (st[i]); - memcpy (&mesh.cloud.data[vn_idx * mesh.cloud.point_step + mesh.cloud.fields[f].offset], - &value, - sizeof (float)); - } + normals.emplace_back( + boost::lexical_cast (st[1]), + boost::lexical_cast (st[2]), + boost::lexical_cast (st[3]) + ); ++vn_idx; } catch (const boost::bad_lexical_cast&) @@ -768,6 +824,7 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, coordinates.emplace_back(c[0], c[1]); else coordinates.emplace_back(c[0]/c[2], c[1]/c[2]); + ++vt_idx; } catch (const boost::bad_lexical_cast&) { @@ -801,23 +858,55 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, // Face if (st[0] == "f") { - // TODO read in normal indices properly - pcl::Vertices face_v; face_v.vertices.resize (st.size () - 1); + std::vector f_st; + std::string n_st; + std::string vt_st; + + pcl::Vertices face_vertices; face_vertices.vertices.resize (st.size () - 1); pcl::Vertices tex_indices; tex_indices.vertices.reserve (st.size () - 1); for (std::size_t i = 1; i < st.size (); ++i) { - char* str_end; - int v = std::strtol(st[i].c_str(), &str_end, 10); + if (st[i].find("//") != std::string::npos) + { + //covers format v//vn + pcl::split(f_st, st[i], "//"); + n_st = f_st[1]; + } + else if (st[i].find('/') != std::string::npos) + { + //covers format v/vt/vn and v/vt + pcl::split(f_st, st[i], "/"); + if (f_st.size() > 1) + vt_st = f_st[1]; + + if (f_st.size() > 2) + n_st = f_st[2]; + } + else + f_st = { st[i] }; + + int v = std::stoi(f_st[0]); v = (v < 0) ? v_idx + v : v - 1; - face_v.vertices[i-1] = v; - if (str_end[0] == '/' && str_end[1] != '/' && str_end[1] != '\0') + face_vertices.vertices[i - 1] = v; + + //handle normals + if (!n_st.empty()) { - // texture coordinate indices are optional - int tex_index = std::strtol(str_end+1, &str_end, 10); - tex_indices.vertices.push_back (tex_index - 1); + int n = std::stoi(n_st); + n = (n < 0) ? vn_idx + n : n - 1; + + normal_mapping[v] += normals[n]; + } + + if (!vt_st.empty()) + { + int vt = std::stoi(vt_st); + vt = (vt < 0) ? vt_idx + vt : vt - 1; + + tex_indices.vertices.push_back(vt); } } - mesh.tex_polygons.back ().push_back (face_v); + mesh.tex_polygons.back ().push_back (face_vertices); mesh.tex_coord_indices.back ().push_back (tex_indices); ++f_idx; continue; @@ -831,6 +920,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::TextureMesh &mesh, return (-1); } + if (!normal_mapping.empty()) + { + for (uindex_t i = 0, main_offset = 0; i < mesh.cloud.width; ++i, main_offset += mesh.cloud.point_step) + { + normal_mapping[i].normalize(); + + for (int j = 0, f = normal_x_field; j < 3; ++j, ++f) + memcpy(&mesh.cloud.data[main_offset + mesh.cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float)); + } + } + double total_time = tt.toc (); PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a TextureMesh in %g ms with %zu points, %zu texture materials, %zu polygons.\n", file_name.c_str (), total_time, @@ -879,10 +979,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, // Get normal_x and rgba fields indices int normal_x_field = -1; + std::vector normals; + + //vector[idx of vertex] + std::vector normal_mapping; + // std::size_t rgba_field = 0; for (std::size_t i = 0; i < mesh.cloud.fields.size (); ++i) if (mesh.cloud.fields[i].name == "normal_x") { + normals.reserve(mesh.cloud.width); + normal_mapping.resize(mesh.cloud.width, Eigen::Vector3f::Zero()); normal_x_field = i; break; } @@ -935,13 +1042,11 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, { try { - for (int i = 1, f = normal_x_field; i < 4; ++i, ++f) - { - float value = boost::lexical_cast (st[i]); - memcpy (&mesh.cloud.data[vn_idx * mesh.cloud.point_step + mesh.cloud.fields[f].offset], - &value, - sizeof (float)); - } + normals.emplace_back( + boost::lexical_cast (st[1]), + boost::lexical_cast (st[2]), + boost::lexical_cast (st[3]) + ); ++vn_idx; } catch (const boost::bad_lexical_cast&) @@ -955,13 +1060,40 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, // Face if (st[0] == "f") { + std::vector f_st; + std::string n_st; + pcl::Vertices face_vertices; face_vertices.vertices.resize (st.size () - 1); for (std::size_t i = 1; i < st.size (); ++i) { - int v; - sscanf (st[i].c_str (), "%d", &v); + if (st[i].find("//") != std::string::npos) + { + //covers format v//vn + pcl::split(f_st, st[i], "//"); + n_st = f_st[1]; + } + else if (st[i].find('/') != std::string::npos) + { + //covers format v/vt/vn and v/vt + pcl::split(f_st, st[i], "/"); + if (f_st.size() > 2) + n_st = f_st[2]; + } + else + f_st = { st[i] }; + + int v = std::stoi(f_st[0]); v = (v < 0) ? v_idx + v : v - 1; face_vertices.vertices[i - 1] = v; + + //handle normals + if (!n_st.empty()) + { + int n = std::stoi(n_st); + n = (n < 0) ? vn_idx + n : n - 1; + + normal_mapping[v] += normals[n]; + } } mesh.polygons.push_back (face_vertices); continue; @@ -975,6 +1107,17 @@ pcl::OBJReader::read (const std::string &file_name, pcl::PolygonMesh &mesh, return (-1); } + if (!normal_mapping.empty()) + { + for (uindex_t i = 0, main_offset = 0; i < mesh.cloud.width; ++i, main_offset += mesh.cloud.point_step) + { + normal_mapping[i].normalize(); + + for (int j = 0, f = normal_x_field; j < 3; ++j, ++f) + memcpy(&mesh.cloud.data[main_offset + mesh.cloud.fields[f].offset], &normal_mapping[i][j], sizeof(float)); + } + } + double total_time = tt.toc (); PCL_DEBUG ("[pcl::OBJReader::read] Loaded %s as a PolygonMesh in %g ms with %zu points and %zu polygons.\n", file_name.c_str (), total_time, diff --git a/test/io/test_io.cpp b/test/io/test_io.cpp index be2f83c07af..269fd83d0a9 100644 --- a/test/io/test_io.cpp +++ b/test/io/test_io.cpp @@ -1082,7 +1082,7 @@ TEST(PCL, OBJRead) fs.close (); pcl::PCLPointCloud2 blob; - pcl::OBJReader objreader = pcl::OBJReader(); + pcl::OBJReader objreader; int res = objreader.read ("test_obj.obj", blob); EXPECT_NE (res, -1); EXPECT_EQ (blob.width, 8); @@ -1121,6 +1121,25 @@ TEST(PCL, OBJRead) EXPECT_EQ (blob.fields[5].count, 1); EXPECT_EQ (blob.fields[5].datatype, pcl::PCLPointField::FLOAT32); + auto fblob = reinterpret_cast(blob.data.data()); + + size_t offset_p = 0; + size_t offset_vn = blob.fields[3].offset / 4; + for (size_t i = 0; i < blob.width; ++i, offset_p += 6, offset_vn += 6) + { + Eigen::Vector3f expected_normal = + Eigen::Vector3f(fblob[offset_p], fblob[offset_p + 1], fblob[offset_p + 2]) + .normalized(); + + Eigen::Vector3f actual_normal = + Eigen::Vector3f(fblob[offset_vn], fblob[offset_vn + 1], fblob[offset_vn + 2]) + .normalized(); + + EXPECT_NEAR(expected_normal.x(), actual_normal.x(), 1e-4); + EXPECT_NEAR(expected_normal.y(), actual_normal.y(), 1e-4); + EXPECT_NEAR(expected_normal.z(), actual_normal.z(), 1e-4); + } + remove ("test_obj.obj"); remove ("test_obj.mtl"); } From a541c5cffb120ff3bb9c18cf982cdb65e940f946 Mon Sep 17 00:00:00 2001 From: David Date: Tue, 28 May 2024 16:06:04 +0200 Subject: [PATCH 259/288] Torus ransac model (#5816) * First torus commit * Torus ransac * integrating projectPoints * Implementing more functions * Slight progress * Adding optimizeModelCoefficients * Adding an example to test during implementation * Fix a bit of the mess between Vector3 and Vector4 float / double types * Progress * Optimizer now works! * Important milestone: * optimizeModelCoefficients is ready * Moved the implementation towards a "normal based" approach * computeModelCoefficients is also ready * Removes normals * Reverting unnecessary changes.. * Several changes: * Removing torus example to test * Unsupressing errors, fixing them but some things are still not adressed * Restores unrequired file modifications * Restoring unnecessary modifications * Updating doxygen * Adds clangformat to new files * Implements a direct approach to torus SAC, with normals * Cleans up a bit, fixes some implementation issues * Fixes equation, tests are now passing * Fixed some bugs, added tests, cleanup * Fixes clang-format * Implements isModelValid * implements doSamplesVerifyModel * Adds more tests, adds normals to ML optimizer * Adds more tests, adds normals to ML optimizer * Rolls back formatting, sorry * Review day 1 * Fixes closest * Review stage + cleanup * Adds const correctness to variables * Corrects a silly mistake * Normalize direction after optimizemodelcoeffs * Format review --- sample_consensus/CMakeLists.txt | 3 + .../sample_consensus/impl/sac_model_torus.hpp | 581 ++++++ .../pcl/sample_consensus/sac_model_torus.h | 318 +++ sample_consensus/src/sac_model_torus.cpp | 45 + .../test_sample_consensus_quadric_models.cpp | 1721 ++++++++++++----- 5 files changed, 2169 insertions(+), 499 deletions(-) create mode 100644 sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp create mode 100644 sample_consensus/include/pcl/sample_consensus/sac_model_torus.h create mode 100644 sample_consensus/src/sac_model_torus.cpp diff --git a/sample_consensus/CMakeLists.txt b/sample_consensus/CMakeLists.txt index 88d353d5453..ff919f7d422 100644 --- a/sample_consensus/CMakeLists.txt +++ b/sample_consensus/CMakeLists.txt @@ -27,6 +27,7 @@ set(srcs src/sac_model_registration.cpp src/sac_model_sphere.cpp src/sac_model_ellipse3d.cpp + src/sac_model_torus.cpp ) set(incs @@ -58,6 +59,7 @@ set(incs "include/pcl/${SUBSYS_NAME}/sac_model_registration_2d.h" "include/pcl/${SUBSYS_NAME}/sac_model_sphere.h" "include/pcl/${SUBSYS_NAME}/sac_model_ellipse3d.h" + "include/pcl/${SUBSYS_NAME}/sac_model_torus.h" ) set(impl_incs @@ -85,6 +87,7 @@ set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/sac_model_registration_2d.hpp" "include/pcl/${SUBSYS_NAME}/impl/sac_model_sphere.hpp" "include/pcl/${SUBSYS_NAME}/impl/sac_model_ellipse3d.hpp" + "include/pcl/${SUBSYS_NAME}/impl/sac_model_torus.hpp" ) set(LIB_NAME "pcl_${SUBSYS_NAME}") diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp new file mode 100644 index 00000000000..dd9e7699c4d --- /dev/null +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_torus.hpp @@ -0,0 +1,581 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2009-2010, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_ +#define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_ + +// clang-format off +#include +#include +// clang-format on + +#include // for LevenbergMarquardt +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +bool +pcl::SampleConsensusModelTorus::isSampleGood( + const Indices& samples) const +{ + if (samples.size() != sample_size_) { + PCL_ERROR("[pcl::SampleConsensusTorus::isSampleGood] Wrong number of samples (is " + "%lu, should be %lu)!\n", + samples.size(), + sample_size_); + return (false); + } + + Eigen::Vector3f n0 = Eigen::Vector3f((*normals_)[samples[0]].getNormalVector3fMap()); + Eigen::Vector3f n1 = Eigen::Vector3f((*normals_)[samples[1]].getNormalVector3fMap()); + Eigen::Vector3f n2 = Eigen::Vector3f((*normals_)[samples[2]].getNormalVector3fMap()); + Eigen::Vector3f n3 = Eigen::Vector3f((*normals_)[samples[3]].getNormalVector3fMap()); + + // Required for numeric stability on computeModelCoefficients + if (std::abs((n0).cross(n1).squaredNorm()) < + Eigen::NumTraits::dummy_precision() || + std::abs((n0).cross(n2).squaredNorm()) < + Eigen::NumTraits::dummy_precision() || + std::abs((n0).cross(n3).squaredNorm()) < + Eigen::NumTraits::dummy_precision() || + std::abs((n1).cross(n2).squaredNorm()) < + Eigen::NumTraits::dummy_precision() || + std::abs((n1).cross(n3).squaredNorm()) < + Eigen::NumTraits::dummy_precision()) { + PCL_ERROR("[pcl::SampleConsensusModelEllipse3D::isSampleGood] Sample points " + "normals too similar or collinear!\n"); + return (false); + } + return (true); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +float +crossDot(Eigen::Vector3f v1, Eigen::Vector3f v2, Eigen::Vector3f v3) +{ + return v1.cross(v2).dot(v3); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +bool +pcl::SampleConsensusModelTorus::computeModelCoefficients( + const Indices& samples, Eigen::VectorXf& model_coefficients) const +{ + + // Make sure that the samples are valid + if (!isSampleGood(samples)) { + PCL_ERROR("[pcl::SampleConsensusModelTorus::computeModelCoefficients] Invalid set " + "of samples given!\n"); + return (false); + } + + if (!normals_) { + PCL_ERROR("[pcl::SampleConsensusModelTorus::computeModelCoefficients] No input " + "dataset containing normals was given!\n"); + return (false); + } + // Find axis using: + + // @article{article, + // author = {Lukacs, G. and Marshall, David and Martin, R.}, + // year = {2001}, + // month = {09}, + // pages = {}, + // title = {Geometric Least-Squares Fitting of Spheres, Cylinders, Cones and Tori} + //} + + const Eigen::Vector3f n0 = Eigen::Vector3f((*normals_)[samples[0]].getNormalVector3fMap()); + const Eigen::Vector3f n1 = Eigen::Vector3f((*normals_)[samples[1]].getNormalVector3fMap()); + const Eigen::Vector3f n2 = Eigen::Vector3f((*normals_)[samples[2]].getNormalVector3fMap()); + const Eigen::Vector3f n3 = Eigen::Vector3f((*normals_)[samples[3]].getNormalVector3fMap()); + + const Eigen::Vector3f p0 = Eigen::Vector3f((*input_)[samples[0]].getVector3fMap()); + const Eigen::Vector3f p1 = Eigen::Vector3f((*input_)[samples[1]].getVector3fMap()); + const Eigen::Vector3f p2 = Eigen::Vector3f((*input_)[samples[2]].getVector3fMap()); + const Eigen::Vector3f p3 = Eigen::Vector3f((*input_)[samples[3]].getVector3fMap()); + + const float a01 = crossDot(n0, n1, n2); + const float b01 = crossDot(n0, n1, n3); + const float a0 = crossDot(p2 - p1, n0, n2); + const float a1 = crossDot(p0 - p2, n1, n2); + const float b0 = crossDot(p3 - p1, n0, n3); + const float b1 = crossDot(p0 - p3, n1, n3); + const float a = crossDot(p0 - p2, p1 - p0, n2); + const float b = crossDot(p0 - p3, p1 - p0, n3); + + // a10*t0*t1 + a0*t0 + a1*t1 + a = 0 + // b10*t0*t1 + b0*t0 + b1*t1 + b = 0 + // + // (a0 - b0*a10/b10)* t0 + (a1-b1*a10/b10) *t1 + a - b*a10/b10 + // t0 = k * t1 + p + + const float k = -(a1 - b1 * a01 / b01) / (a0 - b0 * a01 / b01); + const float p = -(a - b * a01 / b01) / (a0 - b0 * a01 / b01); + + // Second deg eqn. + // + // b10*k*t1*t1 + b10*p*t1 | + b0*k *t1 + b0*p | + b1*t1 | + b = 0 + // + // (b10*k) * t1*t1 + (b10*p + b0*k + b1) * t1 + (b0*p + b) + + const float _a = (b01 * k); + const float _b = (b01 * p + b0 * k + b1); + const float _c = (b0 * p + b); + + const float eps = Eigen::NumTraits::dummy_precision(); + + // Check for imaginary solutions, or small denominators. + if ((_b * _b - 4 * _a * _c) < 0 || std::abs(a0 - b0 * a01) < eps || + std::abs(b01) < eps || std::abs(_a) < eps) { + PCL_DEBUG("[pcl::SampleConsensusModelTorus::computeModelCoefficients] Can't " + "compute model coefficients with this method!\n"); + return (false); + } + + const float s0 = (-_b + std::sqrt(_b * _b - 4 * _a * _c)) / (2 * _a); + const float s1 = (-_b - std::sqrt(_b * _b - 4 * _a * _c)) / (2 * _a); + + float r_maj_stddev_cycle1 = std::numeric_limits::max(); + + for (float s : {s0, s1}) { + + const float t1 = s; + const float t0 = k * t1 + p; + + // Direction vector + Eigen::Vector3f d = ((p1 + n1 * t1) - (p0 + n0 * t0)); + d.normalize(); + // Flip direction, so that the first element of the direction vector is + // positive, for consistency. + if (d[0] < 0) { + d *= -1; + } + + // Flip normals if required. Note |d| = 1 + // d + // if (n0.dot(d) / n0.norm() < M_PI / 2 ) n0 = -n0; + // if (n1.dot(d) / n1.norm() < M_PI / 2 ) n1 = -n1; + // if (n2.dot(d) / n2.norm() < M_PI / 2 ) n2 = -n2; + // if (n3.dot(d) / n3.norm() < M_PI / 2 ) n3 = -n3; + + // We fit the points to the plane of the torus. + // Ax + By + Cz + D = 0 + // We know that all for each point plus its normal + // times the minor radius will give us a point + // in that plane + // Pplane_i = P_i + n_i * r + // we substitute A,x,B,y,C,z + // dx *( P_i_x + n_i_x * r ) + dy *( P_i_y + n_i_y * r ) +dz *( P_i_z + n_i_z * r ) + // + D = 0 and finally (dx*P_i_x + dy*P_i_y + dz*P_i_z) + (dx*n_i_x + dy*n_i_y + + // dz*n_i_z ) * r + D = 0 We can set up a linear least squares system of two + // variables r and D + // + Eigen::MatrixXf A(4, 2); + A << d.dot(n0), 1, d.dot(n1), 1, d.dot(n2), 1, d.dot(n3), 1; + + Eigen::Matrix B(4, 1); + B << -d.dot(p0), -d.dot(p1), -d.dot(p2), -d.dot(p3); + + Eigen::Matrix sol; + sol = A.bdcSvd(Eigen::ComputeThinU | Eigen::ComputeThinV).solve(B); + + const float r_min = -sol(0); + const float D = sol(1); + + // Axis line and plane intersect to find the centroid of the torus + // We take a random point on the line. We find P_rand + lambda * d belongs in the + // plane + + const Eigen::Vector3f Pany = (p1 + n1 * t1); + + const float lambda = (-d.dot(Pany) - D) / d.dot(d); + + const Eigen::Vector3f centroid = Pany + d * lambda; + + // Finally, the major radius. The least square solution will be + // the average in this case. + const float r_maj = std::sqrt(((p0 - r_min * n0 - centroid).squaredNorm() + + (p1 - r_min * n1 - centroid).squaredNorm() + + (p2 - r_min * n2 - centroid).squaredNorm() + + (p3 - r_min * n3 - centroid).squaredNorm()) / + 4.f); + + const float r_maj_stddev = + std::sqrt((std::pow(r_maj - (p0 - r_min * n0 - centroid).norm(), 2) + + std::pow(r_maj - (p1 - r_min * n1 - centroid).norm(), 2) + + std::pow(r_maj - (p2 - r_min * n2 - centroid).norm(), 2) + + std::pow(r_maj - (p3 - r_min * n3 - centroid).norm(), 2)) / + 4.f); + // We select the minimum stddev cycle + if (r_maj_stddev < r_maj_stddev_cycle1) { + r_maj_stddev_cycle1 = r_maj_stddev; + } + else { + break; + } + + model_coefficients.resize(model_size_); + model_coefficients[0] = r_maj; + model_coefficients[1] = r_min; + + model_coefficients[2] = centroid[0]; + model_coefficients[3] = centroid[1]; + model_coefficients[4] = centroid[2]; + + model_coefficients[5] = d[0]; + model_coefficients[6] = d[1]; + model_coefficients[7] = d[2]; + } + return true; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::SampleConsensusModelTorus::getDistancesToModel( + const Eigen::VectorXf& model_coefficients, std::vector& distances) const +{ + + if (!isModelValid(model_coefficients)) { + distances.clear(); + return; + } + + distances.resize(indices_->size()); + + // Iterate through the 3d points and calculate the distances to the closest torus + // point + for (std::size_t i = 0; i < indices_->size(); ++i) { + const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap(); + const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap(); + + Eigen::Vector3f torus_closest; + projectPointToTorus(pt, pt_n, model_coefficients, torus_closest); + + distances[i] = (torus_closest - pt).norm(); + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::SampleConsensusModelTorus::selectWithinDistance( + const Eigen::VectorXf& model_coefficients, const double threshold, Indices& inliers) +{ + // Check if the model is valid given the user constraints + if (!isModelValid(model_coefficients)) { + inliers.clear(); + return; + } + inliers.clear(); + error_sqr_dists_.clear(); + inliers.reserve(indices_->size()); + error_sqr_dists_.reserve(indices_->size()); + + for (std::size_t i = 0; i < indices_->size(); ++i) { + const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap(); + const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap(); + + Eigen::Vector3f torus_closest; + projectPointToTorus(pt, pt_n, model_coefficients, torus_closest); + + const float distance = (torus_closest - pt).norm(); + + if (distance < threshold) { + // Returns the indices of the points whose distances are smaller than the + // threshold + inliers.push_back((*indices_)[i]); + error_sqr_dists_.push_back(distance); + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +std::size_t +pcl::SampleConsensusModelTorus::countWithinDistance( + const Eigen::VectorXf& model_coefficients, const double threshold) const +{ + if (!isModelValid(model_coefficients)) + return (0); + + std::size_t nr_p = 0; + + for (std::size_t i = 0; i < indices_->size(); ++i) { + const Eigen::Vector3f pt = (*input_)[(*indices_)[i]].getVector3fMap(); + const Eigen::Vector3f pt_n = (*normals_)[(*indices_)[i]].getNormalVector3fMap(); + + Eigen::Vector3f torus_closest; + projectPointToTorus(pt, pt_n, model_coefficients, torus_closest); + + const float distance = (torus_closest - pt).norm(); + + if (distance < threshold) { + nr_p++; + } + } + return (nr_p); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::SampleConsensusModelTorus::optimizeModelCoefficients( + const Indices& inliers, + const Eigen::VectorXf& model_coefficients, + Eigen::VectorXf& optimized_coefficients) const +{ + + optimized_coefficients = model_coefficients; + + // Needs a set of valid model coefficients + if (!isModelValid(model_coefficients)) { + PCL_ERROR("[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Given model " + "is invalid!\n"); + return; + } + + // Need more than the minimum sample size to make a difference + if (inliers.size() <= sample_size_) { + PCL_ERROR("[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Not enough " + "inliers to refine/optimize the model's coefficients (%lu)! Returning " + "the same coefficients.\n", + inliers.size()); + return; + } + + OptimizationFunctor functor(this, inliers); + Eigen::NumericalDiff num_diff(functor); + Eigen::LevenbergMarquardt, double> lm( + num_diff); + + Eigen::VectorXd coeff = model_coefficients.cast(); + int info = lm.minimize(coeff); + + if (!info) { + PCL_ERROR( + "[pcl::SampleConsensusModelTorus::optimizeModelCoefficients] Optimizer returned" + "with error (%i)! Returning ", + info); + return; + } + + // Normalize direction vector + coeff.tail<3>().normalize(); + optimized_coefficients = coeff.cast(); +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::SampleConsensusModelTorus::projectPointToTorus( + const Eigen::Vector3f& p_in, + const Eigen::Vector3f& p_n, + const Eigen::VectorXf& model_coefficients, + Eigen::Vector3f& pt_out) const +{ + + // Fetch optimization parameters + const float& R = model_coefficients[0]; + const float& r = model_coefficients[1]; + + const float& x0 = model_coefficients[2]; + const float& y0 = model_coefficients[3]; + const float& z0 = model_coefficients[4]; + + const float& nx = model_coefficients[5]; + const float& ny = model_coefficients[6]; + const float& nz = model_coefficients[7]; + + // Normal of the plane where the torus circle lies + Eigen::Vector3f n{nx, ny, nz}; + n.normalize(); + + Eigen::Vector3f pt0{x0, y0, z0}; + + // Ax + By + Cz + D = 0 + const float D = -n.dot(pt0); + + // Project to the torus circle plane folling the point normal + // we want to find lambda such that p + pn_n*lambda lies on the + // torus plane. + // A*(pt_x + lambda*pn_x) + B *(pt_y + lambda*pn_y) + ... + D = 0 + // given that: n = [A,B,C] + // n.dot(P) + lambda*n.dot(pn) + D = 0 + // + + Eigen::Vector3f pt_proj; + // If the point lies in the torus plane, we just use it as projected + + // C++20 -> [[likely]] + if (std::abs(n.dot(p_n)) > Eigen::NumTraits::dummy_precision()) { + float lambda = (-D - n.dot(p_in)) / n.dot(p_n); + pt_proj = p_in + lambda * p_n; + } + else { + pt_proj = p_in; + } + + // Closest point from the inner circle to the current point + const Eigen::Vector3f circle_closest = (pt_proj - pt0).normalized() * R + pt0; + + // From the that closest point we move towards the goal point until we + // meet the surface of the torus + pt_out = (p_in - circle_closest).normalized() * r + circle_closest; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +void +pcl::SampleConsensusModelTorus::projectPoints( + const Indices& inliers, + const Eigen::VectorXf& model_coefficients, + PointCloud& projected_points, + bool copy_data_fields) const +{ + // Needs a valid set of model coefficients + if (!isModelValid(model_coefficients)) { + PCL_ERROR( + "[pcl::SampleConsensusModelCylinder::projectPoints] Given model is invalid!\n"); + return; + } + + // Copy all the data fields from the input cloud to the projected one? + if (copy_data_fields) { + // Allocate enough space and copy the basics + projected_points.resize(input_->size()); + projected_points.width = input_->width; + projected_points.height = input_->height; + + using FieldList = typename pcl::traits::fieldList::type; + // Iterate over each point + for (std::size_t i = 0; i < input_->size(); ++i) + // Iterate over each dimension + pcl::for_each_type( + NdConcatenateFunctor((*input_)[i], projected_points[i])); + + // Iterate through the 3d points and calculate the distances from them to the plane + for (const auto& inlier : inliers) { + Eigen::Vector3f q; + const Eigen::Vector3f pt_n = (*normals_)[inlier].getNormalVector3fMap(); + projectPointToTorus( + (*input_)[inlier].getVector3fMap(), pt_n, model_coefficients, q); + projected_points[inlier].getVector3fMap() = q; + } + } + else { + // Allocate enough space and copy the basics + projected_points.resize(inliers.size()); + projected_points.width = inliers.size(); + projected_points.height = 1; + + using FieldList = typename pcl::traits::fieldList::type; + // Iterate over each point + for (std::size_t i = 0; i < inliers.size(); ++i) { + // Iterate over each dimension + pcl::for_each_type(NdConcatenateFunctor( + (*input_)[inliers[i]], projected_points[i])); + } + + for (const auto& inlier : inliers) { + Eigen::Vector3f q; + const Eigen::Vector3f pt_n = (*normals_)[inlier].getNormalVector3fMap(); + projectPointToTorus( + (*input_)[inlier].getVector3fMap(), pt_n, model_coefficients, q); + projected_points[inlier].getVector3fMap() = q; + } + } +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +bool +pcl::SampleConsensusModelTorus::doSamplesVerifyModel( + const std::set& indices, + const Eigen::VectorXf& model_coefficients, + const double threshold) const +{ + + for (const auto& index : indices) { + const Eigen::Vector3f pt_n = (*normals_)[index].getNormalVector3fMap(); + Eigen::Vector3f torus_closest; + projectPointToTorus((*input_)[index].getVector3fMap(), pt_n, model_coefficients, torus_closest); + + if (((*input_)[index].getVector3fMap() - torus_closest).squaredNorm() > threshold * threshold) + return (false); + } + return true; +} + +////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template +bool +pcl::SampleConsensusModelTorus::isModelValid( + const Eigen::VectorXf& model_coefficients) const +{ + if (!SampleConsensusModel::isModelValid(model_coefficients)) + return (false); + + if (radius_min_ != std::numeric_limits::lowest() && + (model_coefficients[0] < radius_min_ || model_coefficients[1] < radius_min_)) { + PCL_DEBUG( + "[pcl::SampleConsensusModelTorus::isModelValid] Major radius OR minor radius " + "of torus is/are too small: should be larger than %g, but are {%g, %g}.\n", + radius_min_, + model_coefficients[0], + model_coefficients[1]); + return (false); + } + if (radius_max_ != std::numeric_limits::max() && + (model_coefficients[0] > radius_max_ || model_coefficients[1] > radius_max_)) { + PCL_DEBUG( + "[pcl::SampleConsensusModelTorus::isModelValid] Major radius OR minor radius " + "of torus is/are too big: should be smaller than %g, but are {%g, %g}.\n", + radius_max_, + model_coefficients[0], + model_coefficients[1]); + return (false); + } + return (true); +} + +#define PCL_INSTANTIATE_SampleConsensusModelTorus(PointT, PointNT) \ + template class PCL_EXPORTS pcl::SampleConsensusModelTorus; + +#endif // PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_TORUS_H_ diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_torus.h b/sample_consensus/include/pcl/sample_consensus/sac_model_torus.h new file mode 100644 index 00000000000..d69a29fcd25 --- /dev/null +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_torus.h @@ -0,0 +1,318 @@ +/* + * Software License Agreement (BSD License) + * + * Point Cloud Library (PCL) - www.pointclouds.org + * Copyright (c) 2010-2011, Willow Garage, Inc. + * Copyright (c) 2012-, Open Perception, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder(s) nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#pragma once + +#include +#include +#include + +namespace pcl { + +/** \brief @b SampleConsensusModelTorus defines a model for 3D torus segmentation. + * The model coefficients are defined as: + * - \b radii.inner : the torus's inner radius + * - \b radii.outer : the torus's outer radius + * - \b torus_center_point.x : the X coordinate of the center of the torus + * - \b torus_center_point.y : the Y coordinate of the center of the torus + * - \b torus_center_point.z : the Z coordinate of the center of the torus + * - \b torus_normal.x : the X coordinate of the normal of the torus + * - \b torus_normal.y : the Y coordinate of the normal of the torus + * - \b torus_normal.z : the Z coordinate of the normal of the torus + * + * \author lasdasdas + * \ingroup sample_consensus + */ +template +class SampleConsensusModelTorus +: public SampleConsensusModel, + public SampleConsensusModelFromNormals { + using SampleConsensusModel::model_name_; + using SampleConsensusModel::input_; + using SampleConsensusModel::indices_; + using SampleConsensusModel::radius_min_; + using SampleConsensusModel::radius_max_; + using SampleConsensusModelFromNormals::normals_; + using SampleConsensusModelFromNormals::normal_distance_weight_; + using SampleConsensusModel::error_sqr_dists_; + + using PointCloud = typename SampleConsensusModel::PointCloud; + using PointCloudPtr = typename SampleConsensusModel::PointCloudPtr; + using PointCloudConstPtr = typename SampleConsensusModel::PointCloudConstPtr; + +public: + using Ptr = shared_ptr>; + using ConstPtr = shared_ptr>; + + /** \brief Constructor for base SampleConsensusModelTorus. + * \param[in] cloud the input point cloud dataset + * \param[in] random if true set the random seed to the current time, else set to + * 12345 (default: false) + */ + SampleConsensusModelTorus(const PointCloudConstPtr& cloud, bool random = false) + : SampleConsensusModel(cloud, random) + , SampleConsensusModelFromNormals() + { + model_name_ = "SampleConsensusModelTorus"; + sample_size_ = 4; + model_size_ = 8; + } + + /** \brief Constructor for base SampleConsensusModelTorus. + * \param[in] cloud the input point cloud dataset + * \param[in] indices a vector of point indices to be used from \a cloud + * \param[in] random if true set the random seed to the current time, else set to + * 12345 (default: false) + */ + SampleConsensusModelTorus(const PointCloudConstPtr& cloud, + const Indices& indices, + bool random = false) + : SampleConsensusModel(cloud, indices, random) + , SampleConsensusModelFromNormals() + { + model_name_ = "SampleConsensusModelTorus"; + sample_size_ = 4; + model_size_ = 8; + } + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + SampleConsensusModelTorus(const SampleConsensusModelTorus& source) + : SampleConsensusModel(), SampleConsensusModelFromNormals() + { + *this = source; + model_name_ = "SampleConsensusModelTorus"; + } + + /** \brief Empty destructor */ + ~SampleConsensusModelTorus() override = default; + + /** \brief Copy constructor. + * \param[in] source the model to copy into this + */ + inline SampleConsensusModelTorus& + operator=(const SampleConsensusModelTorus& source) + { + SampleConsensusModelFromNormals::operator=(source); + return (*this); + } + /** \brief Check whether the given index samples can form a valid torus model, compute + * the model coefficients from these samples and store them in model_coefficients. The + * torus coefficients are: radii, torus_center_point, torus_normal. + * \param[in] samples the point indices found as possible good candidates for creating a valid model + * \param[out] model_coefficients the resultant model coefficients + */ + bool + computeModelCoefficients(const Indices& samples, + Eigen::VectorXf& model_coefficients) const override; + + /** \brief Compute all distances from the cloud data to a given torus model. + * \param[in] model_coefficients the coefficients of a torus model that we need to compute distances to + * \param[out] distances the resultant estimated distances + */ + void + getDistancesToModel(const Eigen::VectorXf& model_coefficients, + std::vector& distances) const override; + + /** \brief Select all the points which respect the given model coefficients as + * inliers. + * \param[in] model_coefficients the coefficients of a torus model that we need to compute distances to + * \param[in] threshold a maximum admissible distance threshold for determining the inliers from the outliers + * \param[out] inliers the + * resultant model inliers + */ + void + selectWithinDistance(const Eigen::VectorXf& model_coefficients, + const double threshold, + Indices& inliers) override; + + /** \brief Count all the points which respect the given model coefficients as inliers. + * + * \param[in] model_coefficients the coefficients of a model that we need to compute distances to + * \param[in] threshold maximum admissible distance threshold for + * determining the inliers from the outliers \return the resultant number of inliers + */ + std::size_t + countWithinDistance(const Eigen::VectorXf& model_coefficients, + const double threshold) const override; + + /** \brief Recompute the torus coefficients using the given inlier set and return them + * to the user. + * \param[in] inliers the data inliers found as supporting the model + * \param[in] model_coefficients the initial guess for the optimization + * \param[out] optimized_coefficients the resultant recomputed coefficients after + * non-linear optimization + */ + void + optimizeModelCoefficients(const Indices& inliers, + const Eigen::VectorXf& model_coefficients, + Eigen::VectorXf& optimized_coefficients) const override; + + /** \brief Create a new point cloud with inliers projected onto the torus model. + * \param[in] inliers the data inliers that we want to project on the torus model + * \param[in] model_coefficients the coefficients of a torus model + * \param[out] projected_points the resultant projected points + * \param[in] copy_data_fields set to true if we need to copy the other data fields + */ + void + projectPoints(const Indices& inliers, + const Eigen::VectorXf& model_coefficients, + PointCloud& projected_points, + bool copy_data_fields = true) const override; + + /** \brief Verify whether a subset of indices verifies the given torus model + * coefficients. + * \param[in] indices the data indices that need to be tested against the torus model + * \param[in] model_coefficients the torus model coefficients + * \param[in] threshold a maximum admissible distance threshold for determining the + * inliers from the outliers + */ + bool + doSamplesVerifyModel(const std::set& indices, + const Eigen::VectorXf& model_coefficients, + const double threshold) const override; + + /** \brief Return a unique id for this model (SACMODEL_TORUS). */ + inline pcl::SacModel + getModelType() const override + { + return (SACMODEL_TORUS); + } + +protected: + using SampleConsensusModel::sample_size_; + using SampleConsensusModel::model_size_; + + /** \brief Project a point onto a torus given by its model coefficients (radii, + * torus_center_point, torus_normal) + * \param[in] pt the input point to project + * \param[in] model_coefficients the coefficients of the torus (radii, torus_center_point, torus_normal) + * \param[out] pt_proj the resultant projected point + */ + void + projectPointToTorus(const Eigen::Vector3f& pt, + const Eigen::Vector3f& pt_n, + const Eigen::VectorXf& model_coefficients, + Eigen::Vector3f& pt_proj) const; + + /** \brief Check whether a model is valid given the user constraints. + * \param[in] model_coefficients the set of model coefficients + */ + bool + isModelValid(const Eigen::VectorXf& model_coefficients) const override; + + /** \brief Check if a sample of indices results in a good sample of points + * indices. Pure virtual. + * \param[in] samples the resultant index samples + */ + bool + isSampleGood(const Indices& samples) const override; + +private: + struct OptimizationFunctor : pcl::Functor { + /** Functor constructor + * \param[in] indices the indices of data points to evaluate + * \param[in] estimator pointer to the estimator object + */ + OptimizationFunctor(const pcl::SampleConsensusModelTorus* model, + const Indices& indices) + : pcl::Functor(indices.size()), model_(model), indices_(indices) + {} + + /** Cost function to be minimized + * \param[in] x the variables array + * \param[out] fvec the resultant functions evaluations + * \return 0 + */ + int + operator()(const Eigen::VectorXd& xs, Eigen::VectorXd& fvec) const + { + // Getting constants from state vector + const double& R = xs[0]; + const double& r = xs[1]; + + const double& x0 = xs[2]; + const double& y0 = xs[3]; + const double& z0 = xs[4]; + + const Eigen::Vector3d centroid{x0, y0, z0}; + + const double& nx = xs[5]; + const double& ny = xs[6]; + const double& nz = xs[7]; + + const Eigen::Vector3d n1{0.0, 0.0, 1.0}; + const Eigen::Vector3d n2 = Eigen::Vector3d{nx, ny, nz}.normalized(); + + for (size_t j = 0; j < indices_.size(); j++) { + + size_t i = indices_[j]; + const Eigen::Vector3d pt = + (*model_->input_)[i].getVector3fMap().template cast(); + + Eigen::Vector3d pte{pt - centroid}; + + // Transposition is inversion + // Using Quaternions instead of Rodrigues + pte = Eigen::Quaterniond() + .setFromTwoVectors(n1, n2) + .toRotationMatrix() + .transpose() * + pte; + + const double& x = pte[0]; + const double& y = pte[1]; + const double& z = pte[2]; + + fvec[j] = (std::pow(sqrt(x * x + y * y) - R, 2) + z * z - r * r); + } + return 0; + } + + const pcl::SampleConsensusModelTorus* model_; + const Indices& indices_; + }; +}; +} // namespace pcl + +#ifdef PCL_NO_PRECOMPILE +#include +#endif diff --git a/sample_consensus/src/sac_model_torus.cpp b/sample_consensus/src/sac_model_torus.cpp new file mode 100644 index 00000000000..11e0b1d8f3c --- /dev/null +++ b/sample_consensus/src/sac_model_torus.cpp @@ -0,0 +1,45 @@ +/* + * 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. + * + */ + +#include + +#ifndef PCL_NO_PRECOMPILE +#include +#include +PCL_INSTANTIATE_PRODUCT(SampleConsensusModelTorus, ((pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGBA)(pcl::PointXYZRGB))((pcl::Normal))) +#endif // PCL_NO_PRECOMPILE + diff --git a/test/sample_consensus/test_sample_consensus_quadric_models.cpp b/test/sample_consensus/test_sample_consensus_quadric_models.cpp index dbdf375aa46..75606bdcf17 100644 --- a/test/sample_consensus/test_sample_consensus_quadric_models.cpp +++ b/test/sample_consensus/test_sample_consensus_quadric_models.cpp @@ -36,17 +36,17 @@ * */ -#include -#include // for EXPECT_XYZ_NEAR - #include -#include -#include -#include #include #include -#include +#include +#include #include +#include +#include +#include +#include +#include // for EXPECT_XYZ_NEAR using namespace pcl; @@ -54,526 +54,550 @@ using SampleConsensusModelSpherePtr = SampleConsensusModelSphere::Ptr; using SampleConsensusModelConePtr = SampleConsensusModelCone::Ptr; using SampleConsensusModelCircle2DPtr = SampleConsensusModelCircle2D::Ptr; using SampleConsensusModelCircle3DPtr = SampleConsensusModelCircle3D::Ptr; -using SampleConsensusModelCylinderPtr = SampleConsensusModelCylinder::Ptr; -using SampleConsensusModelNormalSpherePtr = SampleConsensusModelNormalSphere::Ptr; +using SampleConsensusModelCylinderPtr = + SampleConsensusModelCylinder::Ptr; +using SampleConsensusModelNormalSpherePtr = + SampleConsensusModelNormalSphere::Ptr; using SampleConsensusModelEllipse3DPtr = SampleConsensusModelEllipse3D::Ptr; +using SampleConsensusModelTorusPtr = SampleConsensusModelTorus::Ptr; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelSphere, RANSAC) +TEST(SampleConsensusModelSphere, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; - cloud.resize (10); - cloud[0].getVector3fMap () << 1.7068f, 1.0684f, 2.2147f; - cloud[1].getVector3fMap () << 2.4708f, 2.3081f, 1.1736f; - cloud[2].getVector3fMap () << 2.7609f, 1.9095f, 1.3574f; - cloud[3].getVector3fMap () << 2.8016f, 1.6704f, 1.5009f; - cloud[4].getVector3fMap () << 1.8517f, 2.0276f, 1.0112f; - cloud[5].getVector3fMap () << 1.8726f, 1.3539f, 2.7523f; - cloud[6].getVector3fMap () << 2.5179f, 2.3218f, 1.2074f; - cloud[7].getVector3fMap () << 2.4026f, 2.5114f, 2.7588f; - cloud[8].getVector3fMap () << 2.6999f, 2.5606f, 1.5571f; - cloud[9].getVector3fMap () << 0.0000f, 0.0000f, 0.0000f; + cloud.resize(10); + cloud[0].getVector3fMap() << 1.7068f, 1.0684f, 2.2147f; + cloud[1].getVector3fMap() << 2.4708f, 2.3081f, 1.1736f; + cloud[2].getVector3fMap() << 2.7609f, 1.9095f, 1.3574f; + cloud[3].getVector3fMap() << 2.8016f, 1.6704f, 1.5009f; + cloud[4].getVector3fMap() << 1.8517f, 2.0276f, 1.0112f; + cloud[5].getVector3fMap() << 1.8726f, 1.3539f, 2.7523f; + cloud[6].getVector3fMap() << 2.5179f, 2.3218f, 1.2074f; + cloud[7].getVector3fMap() << 2.4026f, 2.5114f, 2.7588f; + cloud[8].getVector3fMap() << 2.6999f, 2.5606f, 1.5571f; + cloud[9].getVector3fMap() << 0.0000f, 0.0000f, 0.0000f; // Create a shared sphere model pointer directly - SampleConsensusModelSpherePtr model (new SampleConsensusModelSphere (cloud.makeShared ())); + SampleConsensusModelSpherePtr model( + new SampleConsensusModelSphere(cloud.makeShared())); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (4, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (9, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(9, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (4, coeff.size ()); - EXPECT_NEAR (2, coeff[0] / coeff[3], 1e-2); - EXPECT_NEAR (2, coeff[1] / coeff[3], 1e-2); - EXPECT_NEAR (2, coeff[2] / coeff[3], 1e-2); + sac.getModelCoefficients(coeff); + EXPECT_EQ(4, coeff.size()); + EXPECT_NEAR(2, coeff[0] / coeff[3], 1e-2); + EXPECT_NEAR(2, coeff[1] / coeff[3], 1e-2); + EXPECT_NEAR(2, coeff[2] / coeff[3], 1e-2); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (4, coeff_refined.size ()); - EXPECT_NEAR (2, coeff_refined[0] / coeff_refined[3], 1e-2); - EXPECT_NEAR (2, coeff_refined[1] / coeff_refined[3], 1e-2); - EXPECT_NEAR (2, coeff_refined[2] / coeff_refined[3], 1e-2); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(4, coeff_refined.size()); + EXPECT_NEAR(2, coeff_refined[0] / coeff_refined[3], 1e-2); + EXPECT_NEAR(2, coeff_refined[1] / coeff_refined[3], 1e-2); + EXPECT_NEAR(2, coeff_refined[2] / coeff_refined[3], 1e-2); } ////////////////////////////////////////////////////////////////////////////////////////////////// template -class SampleConsensusModelSphereTest : private SampleConsensusModelSphere -{ - public: - using SampleConsensusModelSphere::SampleConsensusModelSphere; - using SampleConsensusModelSphere::countWithinDistanceStandard; -#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__) - using SampleConsensusModelSphere::countWithinDistanceSSE; +class SampleConsensusModelSphereTest : private SampleConsensusModelSphere { +public: + using SampleConsensusModelSphere::SampleConsensusModelSphere; + using SampleConsensusModelSphere::countWithinDistanceStandard; +#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__) + using SampleConsensusModelSphere::countWithinDistanceSSE; #endif -#if defined (__AVX__) && defined (__AVX2__) - using SampleConsensusModelSphere::countWithinDistanceAVX; +#if defined(__AVX__) && defined(__AVX2__) + using SampleConsensusModelSphere::countWithinDistanceAVX; #endif }; -TEST (SampleConsensusModelSphere, SIMD_countWithinDistance) // Test if all countWithinDistance implementations return the same value +TEST(SampleConsensusModelSphere, + SIMD_countWithinDistance) // Test if all countWithinDistance implementations return + // the same value { - const auto seed = static_cast (std::time (nullptr)); - srand (seed); - for (size_t i=0; i<100; i++) // Run as often as you like + const auto seed = static_cast(std::time(nullptr)); + srand(seed); + for (size_t i = 0; i < 100; i++) // Run as often as you like { // Generate a cloud with 1000 random points PointCloud cloud; pcl::Indices indices; - cloud.resize (1000); - for (std::size_t idx = 0; idx < cloud.size (); ++idx) - { - cloud[idx].x = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - cloud[idx].y = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - cloud[idx].z = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - if (rand () % 3 != 0) - { - indices.push_back (static_cast (idx)); + cloud.resize(1000); + for (std::size_t idx = 0; idx < cloud.size(); ++idx) { + cloud[idx].x = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + cloud[idx].y = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + cloud[idx].z = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + if (rand() % 3 != 0) { + indices.push_back(static_cast(idx)); } } - SampleConsensusModelSphereTest model (cloud.makeShared (), indices, true); + SampleConsensusModelSphereTest model(cloud.makeShared(), indices, true); // Generate random sphere model parameters Eigen::VectorXf model_coefficients(4); - model_coefficients << 2.0 * static_cast (rand ()) / RAND_MAX - 1.0, - 2.0 * static_cast (rand ()) / RAND_MAX - 1.0, - 2.0 * static_cast (rand ()) / RAND_MAX - 1.0, - 0.15 * static_cast (rand ()) / RAND_MAX; // center and radius + model_coefficients << 2.0 * static_cast(rand()) / RAND_MAX - 1.0, + 2.0 * static_cast(rand()) / RAND_MAX - 1.0, + 2.0 * static_cast(rand()) / RAND_MAX - 1.0, + 0.15 * static_cast(rand()) / RAND_MAX; // center and radius - const double threshold = 0.15 * static_cast (rand ()) / RAND_MAX; // threshold in [0; 0.1] + const double threshold = + 0.15 * static_cast(rand()) / RAND_MAX; // threshold in [0; 0.1] // The number of inliers is usually somewhere between 0 and 10 - const auto res_standard = model.countWithinDistanceStandard (model_coefficients, threshold); // Standard - PCL_DEBUG ("seed=%lu, i=%lu, model=(%f, %f, %f, %f), threshold=%f, res_standard=%lu\n", seed, i, - model_coefficients(0), model_coefficients(1), model_coefficients(2), model_coefficients(3), threshold, res_standard); -#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__) - const auto res_sse = model.countWithinDistanceSSE (model_coefficients, threshold); // SSE - ASSERT_EQ (res_standard, res_sse); + const auto res_standard = + model.countWithinDistanceStandard(model_coefficients, threshold); // Standard + PCL_DEBUG( + "seed=%lu, i=%lu, model=(%f, %f, %f, %f), threshold=%f, res_standard=%lu\n", + seed, + i, + model_coefficients(0), + model_coefficients(1), + model_coefficients(2), + model_coefficients(3), + threshold, + res_standard); +#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__) + const auto res_sse = + model.countWithinDistanceSSE(model_coefficients, threshold); // SSE + ASSERT_EQ(res_standard, res_sse); #endif -#if defined (__AVX__) && defined (__AVX2__) - const auto res_avx = model.countWithinDistanceAVX (model_coefficients, threshold); // AVX - ASSERT_EQ (res_standard, res_avx); +#if defined(__AVX__) && defined(__AVX2__) + const auto res_avx = + model.countWithinDistanceAVX(model_coefficients, threshold); // AVX + ASSERT_EQ(res_standard, res_avx); #endif } } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelNormalSphere, RANSAC) +TEST(SampleConsensusModelNormalSphere, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; PointCloud normals; - cloud.resize (27); normals.resize (27); - cloud[ 0].getVector3fMap () << -0.014695f, 0.009549f, 0.954775f; - cloud[ 1].getVector3fMap () << 0.014695f, 0.009549f, 0.954775f; - cloud[ 2].getVector3fMap () << -0.014695f, 0.040451f, 0.954775f; - cloud[ 3].getVector3fMap () << 0.014695f, 0.040451f, 0.954775f; - cloud[ 4].getVector3fMap () << -0.009082f, -0.015451f, 0.972049f; - cloud[ 5].getVector3fMap () << 0.009082f, -0.015451f, 0.972049f; - cloud[ 6].getVector3fMap () << -0.038471f, 0.009549f, 0.972049f; - cloud[ 7].getVector3fMap () << 0.038471f, 0.009549f, 0.972049f; - cloud[ 8].getVector3fMap () << -0.038471f, 0.040451f, 0.972049f; - cloud[ 9].getVector3fMap () << 0.038471f, 0.040451f, 0.972049f; - cloud[10].getVector3fMap () << -0.009082f, 0.065451f, 0.972049f; - cloud[11].getVector3fMap () << 0.009082f, 0.065451f, 0.972049f; - cloud[12].getVector3fMap () << -0.023776f, -0.015451f, 0.982725f; - cloud[13].getVector3fMap () << 0.023776f, -0.015451f, 0.982725f; - cloud[14].getVector3fMap () << -0.023776f, 0.065451f, 0.982725f; - cloud[15].getVector3fMap () << 0.023776f, 0.065451f, 0.982725f; - cloud[16].getVector3fMap () << -0.000000f, -0.025000f, 1.000000f; - cloud[17].getVector3fMap () << 0.000000f, -0.025000f, 1.000000f; - cloud[18].getVector3fMap () << -0.029389f, -0.015451f, 1.000000f; - cloud[19].getVector3fMap () << 0.029389f, -0.015451f, 1.000000f; - cloud[20].getVector3fMap () << -0.047553f, 0.009549f, 1.000000f; - cloud[21].getVector3fMap () << 0.047553f, 0.009549f, 1.000000f; - cloud[22].getVector3fMap () << -0.047553f, 0.040451f, 1.000000f; - cloud[23].getVector3fMap () << 0.047553f, 0.040451f, 1.000000f; - cloud[24].getVector3fMap () << -0.029389f, 0.065451f, 1.000000f; - cloud[25].getVector3fMap () << 0.029389f, 0.065451f, 1.000000f; - cloud[26].getVector3fMap () << 0.000000f, 0.075000f, 1.000000f; - - normals[ 0].getNormalVector3fMap () << -0.293893f, -0.309017f, -0.904509f; - normals[ 1].getNormalVector3fMap () << 0.293893f, -0.309017f, -0.904508f; - normals[ 2].getNormalVector3fMap () << -0.293893f, 0.309017f, -0.904509f; - normals[ 3].getNormalVector3fMap () << 0.293893f, 0.309017f, -0.904508f; - normals[ 4].getNormalVector3fMap () << -0.181636f, -0.809017f, -0.559017f; - normals[ 5].getNormalVector3fMap () << 0.181636f, -0.809017f, -0.559017f; - normals[ 6].getNormalVector3fMap () << -0.769421f, -0.309017f, -0.559017f; - normals[ 7].getNormalVector3fMap () << 0.769421f, -0.309017f, -0.559017f; - normals[ 8].getNormalVector3fMap () << -0.769421f, 0.309017f, -0.559017f; - normals[ 9].getNormalVector3fMap () << 0.769421f, 0.309017f, -0.559017f; - normals[10].getNormalVector3fMap () << -0.181636f, 0.809017f, -0.559017f; - normals[11].getNormalVector3fMap () << 0.181636f, 0.809017f, -0.559017f; - normals[12].getNormalVector3fMap () << -0.475528f, -0.809017f, -0.345491f; - normals[13].getNormalVector3fMap () << 0.475528f, -0.809017f, -0.345491f; - normals[14].getNormalVector3fMap () << -0.475528f, 0.809017f, -0.345491f; - normals[15].getNormalVector3fMap () << 0.475528f, 0.809017f, -0.345491f; - normals[16].getNormalVector3fMap () << -0.000000f, -1.000000f, 0.000000f; - normals[17].getNormalVector3fMap () << 0.000000f, -1.000000f, 0.000000f; - normals[18].getNormalVector3fMap () << -0.587785f, -0.809017f, 0.000000f; - normals[19].getNormalVector3fMap () << 0.587785f, -0.809017f, 0.000000f; - normals[20].getNormalVector3fMap () << -0.951057f, -0.309017f, 0.000000f; - normals[21].getNormalVector3fMap () << 0.951057f, -0.309017f, 0.000000f; - normals[22].getNormalVector3fMap () << -0.951057f, 0.309017f, 0.000000f; - normals[23].getNormalVector3fMap () << 0.951057f, 0.309017f, 0.000000f; - normals[24].getNormalVector3fMap () << -0.587785f, 0.809017f, 0.000000f; - normals[25].getNormalVector3fMap () << 0.587785f, 0.809017f, 0.000000f; - normals[26].getNormalVector3fMap () << 0.000000f, 1.000000f, 0.000000f; + cloud.resize(27); + normals.resize(27); + cloud[0].getVector3fMap() << -0.014695f, 0.009549f, 0.954775f; + cloud[1].getVector3fMap() << 0.014695f, 0.009549f, 0.954775f; + cloud[2].getVector3fMap() << -0.014695f, 0.040451f, 0.954775f; + cloud[3].getVector3fMap() << 0.014695f, 0.040451f, 0.954775f; + cloud[4].getVector3fMap() << -0.009082f, -0.015451f, 0.972049f; + cloud[5].getVector3fMap() << 0.009082f, -0.015451f, 0.972049f; + cloud[6].getVector3fMap() << -0.038471f, 0.009549f, 0.972049f; + cloud[7].getVector3fMap() << 0.038471f, 0.009549f, 0.972049f; + cloud[8].getVector3fMap() << -0.038471f, 0.040451f, 0.972049f; + cloud[9].getVector3fMap() << 0.038471f, 0.040451f, 0.972049f; + cloud[10].getVector3fMap() << -0.009082f, 0.065451f, 0.972049f; + cloud[11].getVector3fMap() << 0.009082f, 0.065451f, 0.972049f; + cloud[12].getVector3fMap() << -0.023776f, -0.015451f, 0.982725f; + cloud[13].getVector3fMap() << 0.023776f, -0.015451f, 0.982725f; + cloud[14].getVector3fMap() << -0.023776f, 0.065451f, 0.982725f; + cloud[15].getVector3fMap() << 0.023776f, 0.065451f, 0.982725f; + cloud[16].getVector3fMap() << -0.000000f, -0.025000f, 1.000000f; + cloud[17].getVector3fMap() << 0.000000f, -0.025000f, 1.000000f; + cloud[18].getVector3fMap() << -0.029389f, -0.015451f, 1.000000f; + cloud[19].getVector3fMap() << 0.029389f, -0.015451f, 1.000000f; + cloud[20].getVector3fMap() << -0.047553f, 0.009549f, 1.000000f; + cloud[21].getVector3fMap() << 0.047553f, 0.009549f, 1.000000f; + cloud[22].getVector3fMap() << -0.047553f, 0.040451f, 1.000000f; + cloud[23].getVector3fMap() << 0.047553f, 0.040451f, 1.000000f; + cloud[24].getVector3fMap() << -0.029389f, 0.065451f, 1.000000f; + cloud[25].getVector3fMap() << 0.029389f, 0.065451f, 1.000000f; + cloud[26].getVector3fMap() << 0.000000f, 0.075000f, 1.000000f; + + normals[0].getNormalVector3fMap() << -0.293893f, -0.309017f, -0.904509f; + normals[1].getNormalVector3fMap() << 0.293893f, -0.309017f, -0.904508f; + normals[2].getNormalVector3fMap() << -0.293893f, 0.309017f, -0.904509f; + normals[3].getNormalVector3fMap() << 0.293893f, 0.309017f, -0.904508f; + normals[4].getNormalVector3fMap() << -0.181636f, -0.809017f, -0.559017f; + normals[5].getNormalVector3fMap() << 0.181636f, -0.809017f, -0.559017f; + normals[6].getNormalVector3fMap() << -0.769421f, -0.309017f, -0.559017f; + normals[7].getNormalVector3fMap() << 0.769421f, -0.309017f, -0.559017f; + normals[8].getNormalVector3fMap() << -0.769421f, 0.309017f, -0.559017f; + normals[9].getNormalVector3fMap() << 0.769421f, 0.309017f, -0.559017f; + normals[10].getNormalVector3fMap() << -0.181636f, 0.809017f, -0.559017f; + normals[11].getNormalVector3fMap() << 0.181636f, 0.809017f, -0.559017f; + normals[12].getNormalVector3fMap() << -0.475528f, -0.809017f, -0.345491f; + normals[13].getNormalVector3fMap() << 0.475528f, -0.809017f, -0.345491f; + normals[14].getNormalVector3fMap() << -0.475528f, 0.809017f, -0.345491f; + normals[15].getNormalVector3fMap() << 0.475528f, 0.809017f, -0.345491f; + normals[16].getNormalVector3fMap() << -0.000000f, -1.000000f, 0.000000f; + normals[17].getNormalVector3fMap() << 0.000000f, -1.000000f, 0.000000f; + normals[18].getNormalVector3fMap() << -0.587785f, -0.809017f, 0.000000f; + normals[19].getNormalVector3fMap() << 0.587785f, -0.809017f, 0.000000f; + normals[20].getNormalVector3fMap() << -0.951057f, -0.309017f, 0.000000f; + normals[21].getNormalVector3fMap() << 0.951057f, -0.309017f, 0.000000f; + normals[22].getNormalVector3fMap() << -0.951057f, 0.309017f, 0.000000f; + normals[23].getNormalVector3fMap() << 0.951057f, 0.309017f, 0.000000f; + normals[24].getNormalVector3fMap() << -0.587785f, 0.809017f, 0.000000f; + normals[25].getNormalVector3fMap() << 0.587785f, 0.809017f, 0.000000f; + normals[26].getNormalVector3fMap() << 0.000000f, 1.000000f, 0.000000f; // Create a shared sphere model pointer directly - SampleConsensusModelNormalSpherePtr model (new SampleConsensusModelNormalSphere (cloud.makeShared ())); - model->setInputNormals (normals.makeShared ()); + SampleConsensusModelNormalSpherePtr model( + new SampleConsensusModelNormalSphere(cloud.makeShared())); + model->setInputNormals(normals.makeShared()); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (4, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (27, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(27, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (4, coeff.size ()); - EXPECT_NEAR (0.000, coeff[0], 1e-2); - EXPECT_NEAR (0.025, coeff[1], 1e-2); - EXPECT_NEAR (1.000, coeff[2], 1e-2); - EXPECT_NEAR (0.050, coeff[3], 1e-2); + sac.getModelCoefficients(coeff); + EXPECT_EQ(4, coeff.size()); + EXPECT_NEAR(0.000, coeff[0], 1e-2); + EXPECT_NEAR(0.025, coeff[1], 1e-2); + EXPECT_NEAR(1.000, coeff[2], 1e-2); + EXPECT_NEAR(0.050, coeff[3], 1e-2); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (4, coeff_refined.size ()); - EXPECT_NEAR (0.000, coeff_refined[0], 1e-2); - EXPECT_NEAR (0.025, coeff_refined[1], 1e-2); - EXPECT_NEAR (1.000, coeff_refined[2], 1e-2); - EXPECT_NEAR (0.050, coeff_refined[3], 1e-2); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(4, coeff_refined.size()); + EXPECT_NEAR(0.000, coeff_refined[0], 1e-2); + EXPECT_NEAR(0.025, coeff_refined[1], 1e-2); + EXPECT_NEAR(1.000, coeff_refined[2], 1e-2); + EXPECT_NEAR(0.050, coeff_refined[3], 1e-2); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelCone, RANSAC) +TEST(SampleConsensusModelCone, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; PointCloud normals; - cloud.resize (31); normals.resize (31); - - cloud[ 0].getVector3fMap () << -0.011247f, 0.200000f, 0.965384f; - cloud[ 1].getVector3fMap () << 0.000000f, 0.200000f, 0.963603f; - cloud[ 2].getVector3fMap () << 0.011247f, 0.200000f, 0.965384f; - cloud[ 3].getVector3fMap () << -0.016045f, 0.175000f, 0.977916f; - cloud[ 4].getVector3fMap () << -0.008435f, 0.175000f, 0.974038f; - cloud[ 5].getVector3fMap () << 0.004218f, 0.175000f, 0.973370f; - cloud[ 6].getVector3fMap () << 0.016045f, 0.175000f, 0.977916f; - cloud[ 7].getVector3fMap () << -0.025420f, 0.200000f, 0.974580f; - cloud[ 8].getVector3fMap () << 0.025420f, 0.200000f, 0.974580f; - cloud[ 9].getVector3fMap () << -0.012710f, 0.150000f, 0.987290f; - cloud[10].getVector3fMap () << -0.005624f, 0.150000f, 0.982692f; - cloud[11].getVector3fMap () << 0.002812f, 0.150000f, 0.982247f; - cloud[12].getVector3fMap () << 0.012710f, 0.150000f, 0.987290f; - cloud[13].getVector3fMap () << -0.022084f, 0.175000f, 0.983955f; - cloud[14].getVector3fMap () << 0.022084f, 0.175000f, 0.983955f; - cloud[15].getVector3fMap () << -0.034616f, 0.200000f, 0.988753f; - cloud[16].getVector3fMap () << 0.034616f, 0.200000f, 0.988753f; - cloud[17].getVector3fMap () << -0.006044f, 0.125000f, 0.993956f; - cloud[18].getVector3fMap () << 0.004835f, 0.125000f, 0.993345f; - cloud[19].getVector3fMap () << -0.017308f, 0.150000f, 0.994376f; - cloud[20].getVector3fMap () << 0.017308f, 0.150000f, 0.994376f; - cloud[21].getVector3fMap () << -0.025962f, 0.175000f, 0.991565f; - cloud[22].getVector3fMap () << 0.025962f, 0.175000f, 0.991565f; - cloud[23].getVector3fMap () << -0.009099f, 0.125000f, 1.000000f; - cloud[24].getVector3fMap () << 0.009099f, 0.125000f, 1.000000f; - cloud[25].getVector3fMap () << -0.018199f, 0.150000f, 1.000000f; - cloud[26].getVector3fMap () << 0.018199f, 0.150000f, 1.000000f; - cloud[27].getVector3fMap () << -0.027298f, 0.175000f, 1.000000f; - cloud[28].getVector3fMap () << 0.027298f, 0.175000f, 1.000000f; - cloud[29].getVector3fMap () << -0.036397f, 0.200000f, 1.000000f; - cloud[30].getVector3fMap () << 0.036397f, 0.200000f, 1.000000f; - - normals[ 0].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f; - normals[ 1].getNormalVector3fMap () << 0.000000f, -0.342020f, -0.939693f; - normals[ 2].getNormalVector3fMap () << 0.290381f, -0.342020f, -0.893701f; - normals[ 3].getNormalVector3fMap () << -0.552338f, -0.342020f, -0.760227f; - normals[ 4].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f; - normals[ 5].getNormalVector3fMap () << 0.145191f, -0.342020f, -0.916697f; - normals[ 6].getNormalVector3fMap () << 0.552337f, -0.342020f, -0.760227f; - normals[ 7].getNormalVector3fMap () << -0.656282f, -0.342020f, -0.656283f; - normals[ 8].getNormalVector3fMap () << 0.656282f, -0.342020f, -0.656283f; - normals[ 9].getNormalVector3fMap () << -0.656283f, -0.342020f, -0.656282f; - normals[10].getNormalVector3fMap () << -0.290381f, -0.342020f, -0.893701f; - normals[11].getNormalVector3fMap () << 0.145191f, -0.342020f, -0.916697f; - normals[12].getNormalVector3fMap () << 0.656282f, -0.342020f, -0.656282f; - normals[13].getNormalVector3fMap () << -0.760228f, -0.342020f, -0.552337f; - normals[14].getNormalVector3fMap () << 0.760228f, -0.342020f, -0.552337f; - normals[15].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290380f; - normals[16].getNormalVector3fMap () << 0.893701f, -0.342020f, -0.290380f; - normals[17].getNormalVector3fMap () << -0.624162f, -0.342020f, -0.624162f; - normals[18].getNormalVector3fMap () << 0.499329f, -0.342020f, -0.687268f; - normals[19].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290380f; - normals[20].getNormalVector3fMap () << 0.893701f, -0.342020f, -0.290380f; - normals[21].getNormalVector3fMap () << -0.893701f, -0.342020f, -0.290381f; - normals[22].getNormalVector3fMap () << 0.893701f, -0.342020f, -0.290381f; - normals[23].getNormalVector3fMap () << -0.939693f, -0.342020f, 0.000000f; - normals[24].getNormalVector3fMap () << 0.939693f, -0.342020f, 0.000000f; - normals[25].getNormalVector3fMap () << -0.939693f, -0.342020f, 0.000000f; - normals[26].getNormalVector3fMap () << 0.939693f, -0.342020f, 0.000000f; - normals[27].getNormalVector3fMap () << -0.939693f, -0.342020f, 0.000000f; - normals[28].getNormalVector3fMap () << 0.939693f, -0.342020f, 0.000000f; - normals[29].getNormalVector3fMap () << -0.939693f, -0.342020f, 0.000000f; - normals[30].getNormalVector3fMap () << 0.939693f, -0.342020f, 0.000000f; + cloud.resize(31); + normals.resize(31); + + cloud[0].getVector3fMap() << -0.011247f, 0.200000f, 0.965384f; + cloud[1].getVector3fMap() << 0.000000f, 0.200000f, 0.963603f; + cloud[2].getVector3fMap() << 0.011247f, 0.200000f, 0.965384f; + cloud[3].getVector3fMap() << -0.016045f, 0.175000f, 0.977916f; + cloud[4].getVector3fMap() << -0.008435f, 0.175000f, 0.974038f; + cloud[5].getVector3fMap() << 0.004218f, 0.175000f, 0.973370f; + cloud[6].getVector3fMap() << 0.016045f, 0.175000f, 0.977916f; + cloud[7].getVector3fMap() << -0.025420f, 0.200000f, 0.974580f; + cloud[8].getVector3fMap() << 0.025420f, 0.200000f, 0.974580f; + cloud[9].getVector3fMap() << -0.012710f, 0.150000f, 0.987290f; + cloud[10].getVector3fMap() << -0.005624f, 0.150000f, 0.982692f; + cloud[11].getVector3fMap() << 0.002812f, 0.150000f, 0.982247f; + cloud[12].getVector3fMap() << 0.012710f, 0.150000f, 0.987290f; + cloud[13].getVector3fMap() << -0.022084f, 0.175000f, 0.983955f; + cloud[14].getVector3fMap() << 0.022084f, 0.175000f, 0.983955f; + cloud[15].getVector3fMap() << -0.034616f, 0.200000f, 0.988753f; + cloud[16].getVector3fMap() << 0.034616f, 0.200000f, 0.988753f; + cloud[17].getVector3fMap() << -0.006044f, 0.125000f, 0.993956f; + cloud[18].getVector3fMap() << 0.004835f, 0.125000f, 0.993345f; + cloud[19].getVector3fMap() << -0.017308f, 0.150000f, 0.994376f; + cloud[20].getVector3fMap() << 0.017308f, 0.150000f, 0.994376f; + cloud[21].getVector3fMap() << -0.025962f, 0.175000f, 0.991565f; + cloud[22].getVector3fMap() << 0.025962f, 0.175000f, 0.991565f; + cloud[23].getVector3fMap() << -0.009099f, 0.125000f, 1.000000f; + cloud[24].getVector3fMap() << 0.009099f, 0.125000f, 1.000000f; + cloud[25].getVector3fMap() << -0.018199f, 0.150000f, 1.000000f; + cloud[26].getVector3fMap() << 0.018199f, 0.150000f, 1.000000f; + cloud[27].getVector3fMap() << -0.027298f, 0.175000f, 1.000000f; + cloud[28].getVector3fMap() << 0.027298f, 0.175000f, 1.000000f; + cloud[29].getVector3fMap() << -0.036397f, 0.200000f, 1.000000f; + cloud[30].getVector3fMap() << 0.036397f, 0.200000f, 1.000000f; + + normals[0].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f; + normals[1].getNormalVector3fMap() << 0.000000f, -0.342020f, -0.939693f; + normals[2].getNormalVector3fMap() << 0.290381f, -0.342020f, -0.893701f; + normals[3].getNormalVector3fMap() << -0.552338f, -0.342020f, -0.760227f; + normals[4].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f; + normals[5].getNormalVector3fMap() << 0.145191f, -0.342020f, -0.916697f; + normals[6].getNormalVector3fMap() << 0.552337f, -0.342020f, -0.760227f; + normals[7].getNormalVector3fMap() << -0.656282f, -0.342020f, -0.656283f; + normals[8].getNormalVector3fMap() << 0.656282f, -0.342020f, -0.656283f; + normals[9].getNormalVector3fMap() << -0.656283f, -0.342020f, -0.656282f; + normals[10].getNormalVector3fMap() << -0.290381f, -0.342020f, -0.893701f; + normals[11].getNormalVector3fMap() << 0.145191f, -0.342020f, -0.916697f; + normals[12].getNormalVector3fMap() << 0.656282f, -0.342020f, -0.656282f; + normals[13].getNormalVector3fMap() << -0.760228f, -0.342020f, -0.552337f; + normals[14].getNormalVector3fMap() << 0.760228f, -0.342020f, -0.552337f; + normals[15].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290380f; + normals[16].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290380f; + normals[17].getNormalVector3fMap() << -0.624162f, -0.342020f, -0.624162f; + normals[18].getNormalVector3fMap() << 0.499329f, -0.342020f, -0.687268f; + normals[19].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290380f; + normals[20].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290380f; + normals[21].getNormalVector3fMap() << -0.893701f, -0.342020f, -0.290381f; + normals[22].getNormalVector3fMap() << 0.893701f, -0.342020f, -0.290381f; + normals[23].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f; + normals[24].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f; + normals[25].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f; + normals[26].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f; + normals[27].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f; + normals[28].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f; + normals[29].getNormalVector3fMap() << -0.939693f, -0.342020f, 0.000000f; + normals[30].getNormalVector3fMap() << 0.939693f, -0.342020f, 0.000000f; // Create a shared cylinder model pointer directly - SampleConsensusModelConePtr model (new SampleConsensusModelCone (cloud.makeShared ())); - model->setInputNormals (normals.makeShared ()); + SampleConsensusModelConePtr model( + new SampleConsensusModelCone(cloud.makeShared())); + model->setInputNormals(normals.makeShared()); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (3, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(3, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (31, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(31, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (7, coeff.size ()); - EXPECT_NEAR (0.000000, coeff[0], 1e-2); - EXPECT_NEAR (0.100000, coeff[1], 1e-2); - EXPECT_NEAR (0.349066, coeff[6], 1e-2); + sac.getModelCoefficients(coeff); + EXPECT_EQ(7, coeff.size()); + EXPECT_NEAR(0.000000, coeff[0], 1e-2); + EXPECT_NEAR(0.100000, coeff[1], 1e-2); + EXPECT_NEAR(0.349066, coeff[6], 1e-2); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (7, coeff_refined.size ()); - EXPECT_NEAR (0.349066, coeff_refined[6], 1e-2); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(7, coeff_refined.size()); + EXPECT_NEAR(0.349066, coeff_refined[6], 1e-2); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelCylinder, RANSAC) +TEST(SampleConsensusModelCylinder, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; PointCloud normals; - cloud.resize (20); normals.resize (20); - - cloud[ 0].getVector3fMap () << -0.499902f, 2.199701f, 0.000008f; - cloud[ 1].getVector3fMap () << -0.875397f, 2.030177f, 0.050104f; - cloud[ 2].getVector3fMap () << -0.995875f, 1.635973f, 0.099846f; - cloud[ 3].getVector3fMap () << -0.779523f, 1.285527f, 0.149961f; - cloud[ 4].getVector3fMap () << -0.373285f, 1.216488f, 0.199959f; - cloud[ 5].getVector3fMap () << -0.052893f, 1.475973f, 0.250101f; - cloud[ 6].getVector3fMap () << -0.036558f, 1.887591f, 0.299839f; - cloud[ 7].getVector3fMap () << -0.335048f, 2.171994f, 0.350001f; - cloud[ 8].getVector3fMap () << -0.745456f, 2.135528f, 0.400072f; - cloud[ 9].getVector3fMap () << -0.989282f, 1.803311f, 0.449983f; - cloud[10].getVector3fMap () << -0.900651f, 1.400701f, 0.500126f; - cloud[11].getVector3fMap () << -0.539658f, 1.201468f, 0.550079f; - cloud[12].getVector3fMap () << -0.151875f, 1.340951f, 0.599983f; - cloud[13].getVector3fMap () << -0.000724f, 1.724373f, 0.649882f; - cloud[14].getVector3fMap () << -0.188573f, 2.090983f, 0.699854f; - cloud[15].getVector3fMap () << -0.587925f, 2.192257f, 0.749956f; - cloud[16].getVector3fMap () << -0.927724f, 1.958846f, 0.800008f; - cloud[17].getVector3fMap () << -0.976888f, 1.549655f, 0.849970f; - cloud[18].getVector3fMap () << -0.702003f, 1.242707f, 0.899954f; - cloud[19].getVector3fMap () << -0.289916f, 1.246296f, 0.950075f; - - normals[ 0].getNormalVector3fMap () << 0.000098f, 1.000098f, 0.000008f; - normals[ 1].getNormalVector3fMap () << -0.750891f, 0.660413f, 0.000104f; - normals[ 2].getNormalVector3fMap () << -0.991765f, -0.127949f, -0.000154f; - normals[ 3].getNormalVector3fMap () << -0.558918f, -0.829439f, -0.000039f; - normals[ 4].getNormalVector3fMap () << 0.253627f, -0.967447f, -0.000041f; - normals[ 5].getNormalVector3fMap () << 0.894105f, -0.447965f, 0.000101f; - normals[ 6].getNormalVector3fMap () << 0.926852f, 0.375543f, -0.000161f; - normals[ 7].getNormalVector3fMap () << 0.329948f, 0.943941f, 0.000001f; - normals[ 8].getNormalVector3fMap () << -0.490966f, 0.871203f, 0.000072f; - normals[ 9].getNormalVector3fMap () << -0.978507f, 0.206425f, -0.000017f; - normals[10].getNormalVector3fMap () << -0.801227f, -0.598534f, 0.000126f; - normals[11].getNormalVector3fMap () << -0.079447f, -0.996697f, 0.000079f; - normals[12].getNormalVector3fMap () << 0.696154f, -0.717889f, -0.000017f; - normals[13].getNormalVector3fMap () << 0.998685f, 0.048502f, -0.000118f; - normals[14].getNormalVector3fMap () << 0.622933f, 0.782133f, -0.000146f; - normals[15].getNormalVector3fMap () << -0.175948f, 0.984480f, -0.000044f; - normals[16].getNormalVector3fMap () << -0.855476f, 0.517824f, 0.000008f; - normals[17].getNormalVector3fMap () << -0.953769f, -0.300571f, -0.000030f; - normals[18].getNormalVector3fMap () << -0.404035f, -0.914700f, -0.000046f; - normals[19].getNormalVector3fMap () << 0.420154f, -0.907445f, 0.000075f; + cloud.resize(20); + normals.resize(20); + + cloud[0].getVector3fMap() << -0.499902f, 2.199701f, 0.000008f; + cloud[1].getVector3fMap() << -0.875397f, 2.030177f, 0.050104f; + cloud[2].getVector3fMap() << -0.995875f, 1.635973f, 0.099846f; + cloud[3].getVector3fMap() << -0.779523f, 1.285527f, 0.149961f; + cloud[4].getVector3fMap() << -0.373285f, 1.216488f, 0.199959f; + cloud[5].getVector3fMap() << -0.052893f, 1.475973f, 0.250101f; + cloud[6].getVector3fMap() << -0.036558f, 1.887591f, 0.299839f; + cloud[7].getVector3fMap() << -0.335048f, 2.171994f, 0.350001f; + cloud[8].getVector3fMap() << -0.745456f, 2.135528f, 0.400072f; + cloud[9].getVector3fMap() << -0.989282f, 1.803311f, 0.449983f; + cloud[10].getVector3fMap() << -0.900651f, 1.400701f, 0.500126f; + cloud[11].getVector3fMap() << -0.539658f, 1.201468f, 0.550079f; + cloud[12].getVector3fMap() << -0.151875f, 1.340951f, 0.599983f; + cloud[13].getVector3fMap() << -0.000724f, 1.724373f, 0.649882f; + cloud[14].getVector3fMap() << -0.188573f, 2.090983f, 0.699854f; + cloud[15].getVector3fMap() << -0.587925f, 2.192257f, 0.749956f; + cloud[16].getVector3fMap() << -0.927724f, 1.958846f, 0.800008f; + cloud[17].getVector3fMap() << -0.976888f, 1.549655f, 0.849970f; + cloud[18].getVector3fMap() << -0.702003f, 1.242707f, 0.899954f; + cloud[19].getVector3fMap() << -0.289916f, 1.246296f, 0.950075f; + + normals[0].getNormalVector3fMap() << 0.000098f, 1.000098f, 0.000008f; + normals[1].getNormalVector3fMap() << -0.750891f, 0.660413f, 0.000104f; + normals[2].getNormalVector3fMap() << -0.991765f, -0.127949f, -0.000154f; + normals[3].getNormalVector3fMap() << -0.558918f, -0.829439f, -0.000039f; + normals[4].getNormalVector3fMap() << 0.253627f, -0.967447f, -0.000041f; + normals[5].getNormalVector3fMap() << 0.894105f, -0.447965f, 0.000101f; + normals[6].getNormalVector3fMap() << 0.926852f, 0.375543f, -0.000161f; + normals[7].getNormalVector3fMap() << 0.329948f, 0.943941f, 0.000001f; + normals[8].getNormalVector3fMap() << -0.490966f, 0.871203f, 0.000072f; + normals[9].getNormalVector3fMap() << -0.978507f, 0.206425f, -0.000017f; + normals[10].getNormalVector3fMap() << -0.801227f, -0.598534f, 0.000126f; + normals[11].getNormalVector3fMap() << -0.079447f, -0.996697f, 0.000079f; + normals[12].getNormalVector3fMap() << 0.696154f, -0.717889f, -0.000017f; + normals[13].getNormalVector3fMap() << 0.998685f, 0.048502f, -0.000118f; + normals[14].getNormalVector3fMap() << 0.622933f, 0.782133f, -0.000146f; + normals[15].getNormalVector3fMap() << -0.175948f, 0.984480f, -0.000044f; + normals[16].getNormalVector3fMap() << -0.855476f, 0.517824f, 0.000008f; + normals[17].getNormalVector3fMap() << -0.953769f, -0.300571f, -0.000030f; + normals[18].getNormalVector3fMap() << -0.404035f, -0.914700f, -0.000046f; + normals[19].getNormalVector3fMap() << 0.420154f, -0.907445f, 0.000075f; // Create a shared cylinder model pointer directly - SampleConsensusModelCylinderPtr model (new SampleConsensusModelCylinder (cloud.makeShared ())); - model->setInputNormals (normals.makeShared ()); + SampleConsensusModelCylinderPtr model( + new SampleConsensusModelCylinder(cloud.makeShared())); + model->setInputNormals(normals.makeShared()); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (2, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(2, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (20, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(20, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (7, coeff.size ()); - EXPECT_NEAR (-0.5, coeff[0], 1e-3); - EXPECT_NEAR ( 1.7, coeff[1], 1e-3); - EXPECT_NEAR ( 0.5, coeff[6], 1e-3); + sac.getModelCoefficients(coeff); + EXPECT_EQ(7, coeff.size()); + EXPECT_NEAR(-0.5, coeff[0], 1e-3); + EXPECT_NEAR(1.7, coeff[1], 1e-3); + EXPECT_NEAR(0.5, coeff[6], 1e-3); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (7, coeff_refined.size ()); - EXPECT_NEAR (0.5, coeff_refined[6], 1e-3); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(7, coeff_refined.size()); + EXPECT_NEAR(0.5, coeff_refined[6], 1e-3); } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelCircle2D, RANSAC) +TEST(SampleConsensusModelCircle2D, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; - cloud.resize (18); - - cloud[ 0].getVector3fMap () << 3.587751f, -4.190982f, 0.0f; - cloud[ 1].getVector3fMap () << 3.808883f, -4.412265f, 0.0f; - cloud[ 2].getVector3fMap () << 3.587525f, -5.809143f, 0.0f; - cloud[ 3].getVector3fMap () << 2.999913f, -5.999980f, 0.0f; - cloud[ 4].getVector3fMap () << 2.412224f, -5.809090f, 0.0f; - cloud[ 5].getVector3fMap () << 2.191080f, -5.587682f, 0.0f; - cloud[ 6].getVector3fMap () << 2.048941f, -5.309003f, 0.0f; - cloud[ 7].getVector3fMap () << 2.000397f, -4.999944f, 0.0f; - cloud[ 8].getVector3fMap () << 2.999953f, -6.000056f, 0.0f; - cloud[ 9].getVector3fMap () << 2.691127f, -5.951136f, 0.0f; - cloud[10].getVector3fMap () << 2.190892f, -5.587838f, 0.0f; - cloud[11].getVector3fMap () << 2.048874f, -5.309052f, 0.0f; - cloud[12].getVector3fMap () << 1.999990f, -5.000147f, 0.0f; - cloud[13].getVector3fMap () << 2.049026f, -4.690918f, 0.0f; - cloud[14].getVector3fMap () << 2.190956f, -4.412162f, 0.0f; - cloud[15].getVector3fMap () << 2.412231f, -4.190918f, 0.0f; - cloud[16].getVector3fMap () << 2.691027f, -4.049060f, 0.0f; - cloud[17].getVector3fMap () << 2.000000f, -3.000000f, 0.0f; + cloud.resize(18); + + cloud[0].getVector3fMap() << 3.587751f, -4.190982f, 0.0f; + cloud[1].getVector3fMap() << 3.808883f, -4.412265f, 0.0f; + cloud[2].getVector3fMap() << 3.587525f, -5.809143f, 0.0f; + cloud[3].getVector3fMap() << 2.999913f, -5.999980f, 0.0f; + cloud[4].getVector3fMap() << 2.412224f, -5.809090f, 0.0f; + cloud[5].getVector3fMap() << 2.191080f, -5.587682f, 0.0f; + cloud[6].getVector3fMap() << 2.048941f, -5.309003f, 0.0f; + cloud[7].getVector3fMap() << 2.000397f, -4.999944f, 0.0f; + cloud[8].getVector3fMap() << 2.999953f, -6.000056f, 0.0f; + cloud[9].getVector3fMap() << 2.691127f, -5.951136f, 0.0f; + cloud[10].getVector3fMap() << 2.190892f, -5.587838f, 0.0f; + cloud[11].getVector3fMap() << 2.048874f, -5.309052f, 0.0f; + cloud[12].getVector3fMap() << 1.999990f, -5.000147f, 0.0f; + cloud[13].getVector3fMap() << 2.049026f, -4.690918f, 0.0f; + cloud[14].getVector3fMap() << 2.190956f, -4.412162f, 0.0f; + cloud[15].getVector3fMap() << 2.412231f, -4.190918f, 0.0f; + cloud[16].getVector3fMap() << 2.691027f, -4.049060f, 0.0f; + cloud[17].getVector3fMap() << 2.000000f, -3.000000f, 0.0f; // Create a shared 2d circle model pointer directly - SampleConsensusModelCircle2DPtr model (new SampleConsensusModelCircle2D (cloud.makeShared ())); + SampleConsensusModelCircle2DPtr model( + new SampleConsensusModelCircle2D(cloud.makeShared())); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (3, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(3, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (17, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(17, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (3, coeff.size ()); - EXPECT_NEAR ( 3, coeff[0], 1e-3); - EXPECT_NEAR (-5, coeff[1], 1e-3); - EXPECT_NEAR ( 1, coeff[2], 1e-3); + sac.getModelCoefficients(coeff); + EXPECT_EQ(3, coeff.size()); + EXPECT_NEAR(3, coeff[0], 1e-3); + EXPECT_NEAR(-5, coeff[1], 1e-3); + EXPECT_NEAR(1, coeff[2], 1e-3); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (3, coeff_refined.size ()); - EXPECT_NEAR ( 3, coeff_refined[0], 1e-3); - EXPECT_NEAR (-5, coeff_refined[1], 1e-3); - EXPECT_NEAR ( 1, coeff_refined[2], 1e-3); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(3, coeff_refined.size()); + EXPECT_NEAR(3, coeff_refined[0], 1e-3); + EXPECT_NEAR(-5, coeff_refined[1], 1e-3); + EXPECT_NEAR(1, coeff_refined[2], 1e-3); } /////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelCircle2D, SampleValidationPointsValid) +TEST(SampleConsensusModelCircle2D, SampleValidationPointsValid) { PointCloud cloud; - cloud.resize (3); + cloud.resize(3); - cloud[0].getVector3fMap () << 1.0f, 2.0f, 0.0f; - cloud[1].getVector3fMap () << 0.0f, 1.0f, 0.0f; - cloud[2].getVector3fMap () << 1.5f, 0.0f, 0.0f; + cloud[0].getVector3fMap() << 1.0f, 2.0f, 0.0f; + cloud[1].getVector3fMap() << 0.0f, 1.0f, 0.0f; + cloud[2].getVector3fMap() << 1.5f, 0.0f, 0.0f; // Create a shared line model pointer directly - SampleConsensusModelCircle2DPtr model ( - new SampleConsensusModelCircle2D (cloud.makeShared ())); + SampleConsensusModelCircle2DPtr model( + new SampleConsensusModelCircle2D(cloud.makeShared())); // Algorithm tests pcl::Indices samples; int iterations = 0; model->getSamples(iterations, samples); - EXPECT_EQ (samples.size(), 3); + EXPECT_EQ(samples.size(), 3); Eigen::VectorXf modelCoefficients; - EXPECT_TRUE (model->computeModelCoefficients (samples, modelCoefficients)); + EXPECT_TRUE(model->computeModelCoefficients(samples, modelCoefficients)); - EXPECT_NEAR (modelCoefficients[0], 1.05f, 1e-3); // center x - EXPECT_NEAR (modelCoefficients[1], 0.95f, 1e-3); // center y - EXPECT_NEAR (modelCoefficients[2], std::sqrt (1.105f), 1e-3); // radius + EXPECT_NEAR(modelCoefficients[0], 1.05f, 1e-3); // center x + EXPECT_NEAR(modelCoefficients[1], 0.95f, 1e-3); // center y + EXPECT_NEAR(modelCoefficients[2], std::sqrt(1.105f), 1e-3); // radius } using PointVector = std::vector; class SampleConsensusModelCircle2DCollinearTest - : public testing::TestWithParam { - protected: - void SetUp() override { - pointCloud_ = make_shared>(); - for(const auto& point : GetParam()) { - pointCloud_->emplace_back(point); - } +: public testing::TestWithParam { +protected: + void + SetUp() override + { + pointCloud_ = make_shared>(); + for (const auto& point : GetParam()) { + pointCloud_->emplace_back(point); } + } - PointCloud::Ptr pointCloud_ = nullptr; + PointCloud::Ptr pointCloud_ = nullptr; }; // Parametric tests clearly show the input for which they failed and provide // clearer feedback if something is changed in the future. -TEST_P (SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid) +TEST_P(SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid) { - ASSERT_NE (pointCloud_, nullptr); + ASSERT_NE(pointCloud_, nullptr); - SampleConsensusModelCircle2DPtr model ( - new SampleConsensusModelCircle2D (pointCloud_)); - ASSERT_GE (model->getInputCloud ()->size (), model->getSampleSize ()); + SampleConsensusModelCircle2DPtr model( + new SampleConsensusModelCircle2D(pointCloud_)); + ASSERT_GE(model->getInputCloud()->size(), model->getSampleSize()); // Algorithm tests // (Maybe) TODO: try to implement the "cheat point" trick from @@ -586,171 +610,194 @@ TEST_P (SampleConsensusModelCircle2DCollinearTest, SampleValidationPointsInvalid // Explicitly enforce sample order so they can act as designed pcl::Indices forcedSamples = {0, 1, 2}; Eigen::VectorXf modelCoefficients; - EXPECT_FALSE (model->computeModelCoefficients (forcedSamples, modelCoefficients)); + EXPECT_FALSE(model->computeModelCoefficients(forcedSamples, modelCoefficients)); } -INSTANTIATE_TEST_SUITE_P (CollinearInputs, SampleConsensusModelCircle2DCollinearTest, - testing::Values( // Throw in some negative coordinates and "asymmetric" points to cover more cases - PointVector {{ 0.0f, 0.0f, 0.0f}, { 1.0f, 0.0f, 0.0f}, { 2.0f, 0.0f, 0.0f}}, // collinear along x-axis - PointVector {{-1.0f, 0.0f, 0.0f}, { 1.0f, 0.0f, 0.0f}, { 2.0f, 0.0f, 0.0f}}, - PointVector {{ 0.0f, -1.0f, 0.0f}, { 0.0f, 1.0f, 0.0f}, { 0.0f, 2.0f, 0.0f}}, // collinear along y-axis - PointVector {{ 0.0f, -1.0f, 0.0f}, { 0.0f, 1.0f, 0.0f}, { 0.0f, 2.0f, 0.0f}}, - PointVector {{ 0.0f, 0.0f, 0.0f}, { 1.0f, 1.0f, 0.0f}, { 2.0f, 2.0f, 0.0f}}, // collinear along diagonal - PointVector {{ 0.0f, 0.0f, 0.0f}, {-1.0f, -1.0f, 0.0f}, {-2.0f, -2.0f, 0.0f}}, - PointVector {{-3.0f, -6.5f, 0.0f}, {-2.0f, -0.5f, 0.0f}, {-1.5f, 2.5f, 0.0f}}, // other collinear input - PointVector {{ 2.0f, 2.0f, 0.0f}, { 0.0f, 0.0f, 0.0f}, { 0.0f, 0.0f, 0.0f}}, // two points equal - PointVector {{ 0.0f, 0.0f, 0.0f}, { 2.0f, 2.0f, 0.0f}, { 0.0f, 0.0f, 0.0f}}, - PointVector {{ 0.0f, 0.0f, 0.0f}, { 0.0f, 0.0f, 0.0f}, { 2.0f, 2.0f, 0.0f}}, - PointVector {{ 1.0f, 1.0f, 0.0f}, { 1.0f, 1.0f, 0.0f}, { 1.0f, 1.0f, 0.0f}} // all points equal - ) -); +INSTANTIATE_TEST_SUITE_P( + CollinearInputs, + SampleConsensusModelCircle2DCollinearTest, + testing::Values( // Throw in some negative coordinates and "asymmetric" points to + // cover more cases + PointVector{{0.0f, 0.0f, 0.0f}, + {1.0f, 0.0f, 0.0f}, + {2.0f, 0.0f, 0.0f}}, // collinear along x-axis + PointVector{{-1.0f, 0.0f, 0.0f}, {1.0f, 0.0f, 0.0f}, {2.0f, 0.0f, 0.0f}}, + PointVector{{0.0f, -1.0f, 0.0f}, + {0.0f, 1.0f, 0.0f}, + {0.0f, 2.0f, 0.0f}}, // collinear along y-axis + PointVector{{0.0f, -1.0f, 0.0f}, {0.0f, 1.0f, 0.0f}, {0.0f, 2.0f, 0.0f}}, + PointVector{{0.0f, 0.0f, 0.0f}, + {1.0f, 1.0f, 0.0f}, + {2.0f, 2.0f, 0.0f}}, // collinear along diagonal + PointVector{{0.0f, 0.0f, 0.0f}, {-1.0f, -1.0f, 0.0f}, {-2.0f, -2.0f, 0.0f}}, + PointVector{{-3.0f, -6.5f, 0.0f}, + {-2.0f, -0.5f, 0.0f}, + {-1.5f, 2.5f, 0.0f}}, // other collinear input + PointVector{{2.0f, 2.0f, 0.0f}, + {0.0f, 0.0f, 0.0f}, + {0.0f, 0.0f, 0.0f}}, // two points equal + PointVector{{0.0f, 0.0f, 0.0f}, {2.0f, 2.0f, 0.0f}, {0.0f, 0.0f, 0.0f}}, + PointVector{{0.0f, 0.0f, 0.0f}, {0.0f, 0.0f, 0.0f}, {2.0f, 2.0f, 0.0f}}, + PointVector{{1.0f, 1.0f, 0.0f}, {1.0f, 1.0f, 0.0f}, {1.0f, 1.0f, 0.0f}} + // all points equal + )); ////////////////////////////////////////////////////////////////////////////////////////////////// template -class SampleConsensusModelCircle2DTest : private SampleConsensusModelCircle2D -{ - public: - using SampleConsensusModelCircle2D::SampleConsensusModelCircle2D; - using SampleConsensusModelCircle2D::countWithinDistanceStandard; -#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__) - using SampleConsensusModelCircle2D::countWithinDistanceSSE; +class SampleConsensusModelCircle2DTest : private SampleConsensusModelCircle2D { +public: + using SampleConsensusModelCircle2D::SampleConsensusModelCircle2D; + using SampleConsensusModelCircle2D::countWithinDistanceStandard; +#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__) + using SampleConsensusModelCircle2D::countWithinDistanceSSE; #endif -#if defined (__AVX__) && defined (__AVX2__) - using SampleConsensusModelCircle2D::countWithinDistanceAVX; +#if defined(__AVX__) && defined(__AVX2__) + using SampleConsensusModelCircle2D::countWithinDistanceAVX; #endif }; -TEST (SampleConsensusModelCircle2D, SIMD_countWithinDistance) // Test if all countWithinDistance implementations return the same value +TEST(SampleConsensusModelCircle2D, + SIMD_countWithinDistance) // Test if all countWithinDistance implementations return + // the same value { - const auto seed = static_cast (std::time (nullptr)); - srand (seed); - for (size_t i=0; i<100; i++) // Run as often as you like + const auto seed = static_cast(std::time(nullptr)); + srand(seed); + for (size_t i = 0; i < 100; i++) // Run as often as you like { // Generate a cloud with 1000 random points PointCloud cloud; pcl::Indices indices; - cloud.resize (1000); - for (std::size_t idx = 0; idx < cloud.size (); ++idx) - { - cloud[idx].x = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - cloud[idx].y = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - cloud[idx].z = 2.0 * static_cast (rand ()) / RAND_MAX - 1.0; - if (rand () % 2 == 0) - { - indices.push_back (static_cast (idx)); + cloud.resize(1000); + for (std::size_t idx = 0; idx < cloud.size(); ++idx) { + cloud[idx].x = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + cloud[idx].y = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + cloud[idx].z = 2.0 * static_cast(rand()) / RAND_MAX - 1.0; + if (rand() % 2 == 0) { + indices.push_back(static_cast(idx)); } } - SampleConsensusModelCircle2DTest model (cloud.makeShared (), indices, true); + SampleConsensusModelCircle2DTest model(cloud.makeShared(), indices, true); // Generate random circle model parameters Eigen::VectorXf model_coefficients(3); - model_coefficients << 2.0 * static_cast (rand ()) / RAND_MAX - 1.0, - 2.0 * static_cast (rand ()) / RAND_MAX - 1.0, - 0.1 * static_cast (rand ()) / RAND_MAX; // center and radius + model_coefficients << 2.0 * static_cast(rand()) / RAND_MAX - 1.0, + 2.0 * static_cast(rand()) / RAND_MAX - 1.0, + 0.1 * static_cast(rand()) / RAND_MAX; // center and radius - const double threshold = 0.1 * static_cast (rand ()) / RAND_MAX; // threshold in [0; 0.1] + const double threshold = + 0.1 * static_cast(rand()) / RAND_MAX; // threshold in [0; 0.1] // The number of inliers is usually somewhere between 0 and 20 - const auto res_standard = model.countWithinDistanceStandard (model_coefficients, threshold); // Standard - PCL_DEBUG ("seed=%lu, i=%lu, model=(%f, %f, %f), threshold=%f, res_standard=%lu\n", seed, i, - model_coefficients(0), model_coefficients(1), model_coefficients(2), threshold, res_standard); -#if defined (__SSE__) && defined (__SSE2__) && defined (__SSE4_1__) - const auto res_sse = model.countWithinDistanceSSE (model_coefficients, threshold); // SSE - ASSERT_EQ (res_standard, res_sse); + const auto res_standard = + model.countWithinDistanceStandard(model_coefficients, threshold); // Standard + PCL_DEBUG("seed=%lu, i=%lu, model=(%f, %f, %f), threshold=%f, res_standard=%lu\n", + seed, + i, + model_coefficients(0), + model_coefficients(1), + model_coefficients(2), + threshold, + res_standard); +#if defined(__SSE__) && defined(__SSE2__) && defined(__SSE4_1__) + const auto res_sse = + model.countWithinDistanceSSE(model_coefficients, threshold); // SSE + ASSERT_EQ(res_standard, res_sse); #endif -#if defined (__AVX__) && defined (__AVX2__) - const auto res_avx = model.countWithinDistanceAVX (model_coefficients, threshold); // AVX - ASSERT_EQ (res_standard, res_avx); +#if defined(__AVX__) && defined(__AVX2__) + const auto res_avx = + model.countWithinDistanceAVX(model_coefficients, threshold); // AVX + ASSERT_EQ(res_standard, res_avx); #endif } } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// -TEST (SampleConsensusModelCircle3D, RANSAC) +TEST(SampleConsensusModelCircle3D, RANSAC) { - srand (0); + srand(0); // Use a custom point cloud for these tests until we need something better PointCloud cloud; - cloud.resize (20); - - cloud[ 0].getVector3fMap () << 1.00000000f, 5.0000000f, -2.9000001f; - cloud[ 1].getVector3fMap () << 1.03420200f, 5.0000000f, -2.9060307f; - cloud[ 2].getVector3fMap () << 1.06427870f, 5.0000000f, -2.9233956f; - cloud[ 3].getVector3fMap () << 1.08660260f, 5.0000000f, -2.9500000f; - cloud[ 4].getVector3fMap () << 1.09848080f, 5.0000000f, -2.9826353f; - cloud[ 5].getVector3fMap () << 1.09848080f, 5.0000000f, -3.0173647f; - cloud[ 6].getVector3fMap () << 1.08660260f, 5.0000000f, -3.0500000f; - cloud[ 7].getVector3fMap () << 1.06427870f, 5.0000000f, -3.0766044f; - cloud[ 8].getVector3fMap () << 1.03420200f, 5.0000000f, -3.0939693f; - cloud[ 9].getVector3fMap () << 1.00000000f, 5.0000000f, -3.0999999f; - cloud[10].getVector3fMap () << 0.96579796f, 5.0000000f, -3.0939693f; - cloud[11].getVector3fMap () << 0.93572122f, 5.0000000f, -3.0766044f; - cloud[12].getVector3fMap () << 0.91339743f, 5.0000000f, -3.0500000f; - cloud[13].getVector3fMap () << 0.90151924f, 5.0000000f, -3.0173647f; - cloud[14].getVector3fMap () << 0.90151924f, 5.0000000f, -2.9826353f; - cloud[15].getVector3fMap () << 0.91339743f, 5.0000000f, -2.9500000f; - cloud[16].getVector3fMap () << 0.93572122f, 5.0000000f, -2.9233956f; - cloud[17].getVector3fMap () << 0.96579796f, 5.0000000f, -2.9060307f; - cloud[18].getVector3fMap () << 0.85000002f, 4.8499999f, -3.1500001f; - cloud[19].getVector3fMap () << 1.15000000f, 5.1500001f, -2.8499999f; + cloud.resize(20); + + cloud[0].getVector3fMap() << 1.00000000f, 5.0000000f, -2.9000001f; + cloud[1].getVector3fMap() << 1.03420200f, 5.0000000f, -2.9060307f; + cloud[2].getVector3fMap() << 1.06427870f, 5.0000000f, -2.9233956f; + cloud[3].getVector3fMap() << 1.08660260f, 5.0000000f, -2.9500000f; + cloud[4].getVector3fMap() << 1.09848080f, 5.0000000f, -2.9826353f; + cloud[5].getVector3fMap() << 1.09848080f, 5.0000000f, -3.0173647f; + cloud[6].getVector3fMap() << 1.08660260f, 5.0000000f, -3.0500000f; + cloud[7].getVector3fMap() << 1.06427870f, 5.0000000f, -3.0766044f; + cloud[8].getVector3fMap() << 1.03420200f, 5.0000000f, -3.0939693f; + cloud[9].getVector3fMap() << 1.00000000f, 5.0000000f, -3.0999999f; + cloud[10].getVector3fMap() << 0.96579796f, 5.0000000f, -3.0939693f; + cloud[11].getVector3fMap() << 0.93572122f, 5.0000000f, -3.0766044f; + cloud[12].getVector3fMap() << 0.91339743f, 5.0000000f, -3.0500000f; + cloud[13].getVector3fMap() << 0.90151924f, 5.0000000f, -3.0173647f; + cloud[14].getVector3fMap() << 0.90151924f, 5.0000000f, -2.9826353f; + cloud[15].getVector3fMap() << 0.91339743f, 5.0000000f, -2.9500000f; + cloud[16].getVector3fMap() << 0.93572122f, 5.0000000f, -2.9233956f; + cloud[17].getVector3fMap() << 0.96579796f, 5.0000000f, -2.9060307f; + cloud[18].getVector3fMap() << 0.85000002f, 4.8499999f, -3.1500001f; + cloud[19].getVector3fMap() << 1.15000000f, 5.1500001f, -2.8499999f; // Create a shared 3d circle model pointer directly - SampleConsensusModelCircle3DPtr model (new SampleConsensusModelCircle3D (cloud.makeShared ())); + SampleConsensusModelCircle3DPtr model( + new SampleConsensusModelCircle3D(cloud.makeShared())); // Create the RANSAC object - RandomSampleConsensus sac (model, 0.03); + RandomSampleConsensus sac(model, 0.03); // Algorithm tests - bool result = sac.computeModel (); - ASSERT_TRUE (result); + bool result = sac.computeModel(); + ASSERT_TRUE(result); pcl::Indices sample; - sac.getModel (sample); - EXPECT_EQ (3, sample.size ()); + sac.getModel(sample); + EXPECT_EQ(3, sample.size()); pcl::Indices inliers; - sac.getInliers (inliers); - EXPECT_EQ (18, inliers.size ()); + sac.getInliers(inliers); + EXPECT_EQ(18, inliers.size()); Eigen::VectorXf coeff; - sac.getModelCoefficients (coeff); - EXPECT_EQ (7, coeff.size ()); - EXPECT_NEAR ( 1.0, coeff[0], 1e-3); - EXPECT_NEAR ( 5.0, coeff[1], 1e-3); - EXPECT_NEAR (-3.0, coeff[2], 1e-3); - EXPECT_NEAR ( 0.1, coeff[3], 1e-3); - EXPECT_NEAR ( 0.0, coeff[4], 1e-3); + sac.getModelCoefficients(coeff); + EXPECT_EQ(7, coeff.size()); + EXPECT_NEAR(1.0, coeff[0], 1e-3); + EXPECT_NEAR(5.0, coeff[1], 1e-3); + EXPECT_NEAR(-3.0, coeff[2], 1e-3); + EXPECT_NEAR(0.1, coeff[3], 1e-3); + EXPECT_NEAR(0.0, coeff[4], 1e-3); // Use abs in y component because both variants are valid normal vectors - EXPECT_NEAR ( 1.0, std::abs (coeff[5]), 1e-3); - EXPECT_NEAR ( 0.0, coeff[6], 1e-3); + EXPECT_NEAR(1.0, std::abs(coeff[5]), 1e-3); + EXPECT_NEAR(0.0, coeff[6], 1e-3); Eigen::VectorXf coeff_refined; - model->optimizeModelCoefficients (inliers, coeff, coeff_refined); - EXPECT_EQ (7, coeff_refined.size ()); - EXPECT_NEAR ( 1.0, coeff_refined[0], 1e-3); - EXPECT_NEAR ( 5.0, coeff_refined[1], 1e-3); - EXPECT_NEAR (-3.0, coeff_refined[2], 1e-3); - EXPECT_NEAR ( 0.1, coeff_refined[3], 1e-3); - EXPECT_NEAR ( 0.0, coeff_refined[4], 1e-3); - EXPECT_NEAR ( 1.0, std::abs (coeff_refined[5]), 1e-3); - EXPECT_NEAR ( 0.0, coeff_refined[6], 1e-3); + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(7, coeff_refined.size()); + EXPECT_NEAR(1.0, coeff_refined[0], 1e-3); + EXPECT_NEAR(5.0, coeff_refined[1], 1e-3); + EXPECT_NEAR(-3.0, coeff_refined[2], 1e-3); + EXPECT_NEAR(0.1, coeff_refined[3], 1e-3); + EXPECT_NEAR(0.0, coeff_refined[4], 1e-3); + EXPECT_NEAR(1.0, std::abs(coeff_refined[5]), 1e-3); + EXPECT_NEAR(0.0, coeff_refined[6], 1e-3); } -TEST (SampleConsensusModelSphere, projectPoints) +TEST(SampleConsensusModelSphere, projectPoints) { Eigen::VectorXf model_coefficients(4); model_coefficients << -0.32, -0.89, 0.37, 0.12; // center and radius pcl::PointCloud::Ptr input(new pcl::PointCloud); - input->emplace_back(-0.259754, -0.950873, 0.318377); // inlier, dist from center=0.10 - input->emplace_back( 0.595892, 0.455094, 0.025545); // outlier, not projected - input->emplace_back(-0.221871, -0.973718, 0.353817); // inlier, dist from center=0.13 - input->emplace_back(-0.332269, -0.848851, 0.437499); // inlier, dist from center=0.08 + input->emplace_back(-0.259754, -0.950873, 0.318377); // inlier, dist from center=0.10 + input->emplace_back(0.595892, 0.455094, 0.025545); // outlier, not projected + input->emplace_back(-0.221871, -0.973718, 0.353817); // inlier, dist from center=0.13 + input->emplace_back(-0.332269, -0.848851, 0.437499); // inlier, dist from center=0.08 input->emplace_back(-0.242308, -0.561036, -0.365535); // outlier, not projected - input->emplace_back(-0.327668, -0.800009, 0.290988); // inlier, dist from center=0.12 - input->emplace_back(-0.173948, -0.883831, 0.403625); // inlier, dist from center=0.15 - input->emplace_back(-0.033891, 0.624537, -0.606994); // outlier, not projected + input->emplace_back(-0.327668, -0.800009, 0.290988); // inlier, dist from center=0.12 + input->emplace_back(-0.173948, -0.883831, 0.403625); // inlier, dist from center=0.15 + input->emplace_back(-0.033891, 0.624537, -0.606994); // outlier, not projected pcl::SampleConsensusModelSphere model(input); pcl::Indices inliers = {0, 2, 3, 5, 6}; @@ -765,20 +812,20 @@ TEST (SampleConsensusModelSphere, projectPoints) pcl::PointCloud projected_points; model.projectPoints(inliers, model_coefficients, projected_points, false); EXPECT_EQ(projected_points.size(), 5); - for(int i=0; i<5; ++i) + for (int i = 0; i < 5; ++i) EXPECT_XYZ_NEAR(projected_points[i], projected_truth[i], 1e-5); pcl::PointCloud projected_points_all; model.projectPoints(inliers, model_coefficients, projected_points_all, true); EXPECT_EQ(projected_points_all.size(), 8); EXPECT_XYZ_NEAR(projected_points_all[0], projected_truth[0], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[2], projected_truth[1], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[3], projected_truth[2], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[5], projected_truth[3], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[6], projected_truth[4], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5); } TEST(SampleConsensusModelCylinder, projectPoints) @@ -817,13 +864,13 @@ TEST(SampleConsensusModelCylinder, projectPoints) model.projectPoints(inliers, model_coefficients, projected_points_all, true); EXPECT_EQ(projected_points_all.size(), 8); EXPECT_XYZ_NEAR(projected_points_all[0], projected_truth[0], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[1], (*input)[1], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[2], projected_truth[1], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[3], projected_truth[2], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[4], (*input)[4], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[5], projected_truth[3], 1e-5); EXPECT_XYZ_NEAR(projected_points_all[6], projected_truth[4], 1e-5); - EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5); + EXPECT_XYZ_NEAR(projected_points_all[7], (*input)[7], 1e-5); } TEST(SampleConsensusModelEllipse3D, RANSAC) @@ -834,16 +881,16 @@ TEST(SampleConsensusModelEllipse3D, RANSAC) PointCloud cloud; cloud.resize(22); - cloud[ 0].getVector3fMap() << 1.000000, 5.000000, 3.000000; - cloud[ 1].getVector3fMap() << 0.690983, 5.000000, 2.902110; - cloud[ 2].getVector3fMap() << 0.412215, 5.000000, 2.618030; - cloud[ 3].getVector3fMap() << 0.190983, 5.000000, 2.175570; - cloud[ 4].getVector3fMap() << 0.048944, 5.000000, 1.618030; - cloud[ 5].getVector3fMap() << 0.000000, 5.000000, 1.000000; - cloud[ 6].getVector3fMap() << 0.048944, 5.000000, 0.381966; - cloud[ 7].getVector3fMap() << 0.190983, 5.000000, -0.175571; - cloud[ 8].getVector3fMap() << 0.412215, 5.000000, -0.618034; - cloud[ 9].getVector3fMap() << 0.690983, 5.000000, -0.902113; + cloud[0].getVector3fMap() << 1.000000, 5.000000, 3.000000; + cloud[1].getVector3fMap() << 0.690983, 5.000000, 2.902110; + cloud[2].getVector3fMap() << 0.412215, 5.000000, 2.618030; + cloud[3].getVector3fMap() << 0.190983, 5.000000, 2.175570; + cloud[4].getVector3fMap() << 0.048944, 5.000000, 1.618030; + cloud[5].getVector3fMap() << 0.000000, 5.000000, 1.000000; + cloud[6].getVector3fMap() << 0.048944, 5.000000, 0.381966; + cloud[7].getVector3fMap() << 0.190983, 5.000000, -0.175571; + cloud[8].getVector3fMap() << 0.412215, 5.000000, -0.618034; + cloud[9].getVector3fMap() << 0.690983, 5.000000, -0.902113; cloud[10].getVector3fMap() << 1.000000, 5.000000, -1.000000; cloud[11].getVector3fMap() << 1.309020, 5.000000, -0.902113; cloud[12].getVector3fMap() << 1.587790, 5.000000, -0.618034; @@ -859,7 +906,8 @@ TEST(SampleConsensusModelEllipse3D, RANSAC) cloud[21].getVector3fMap() << 1.15000000f, 5.1500001f, -2.8499999f; // Create a shared 3d ellipse model pointer directly - SampleConsensusModelEllipse3DPtr model( new SampleConsensusModelEllipse3D(cloud.makeShared())); + SampleConsensusModelEllipse3DPtr model( + new SampleConsensusModelEllipse3D(cloud.makeShared())); // Create the RANSAC object RandomSampleConsensus sac(model, 0.0011); @@ -917,10 +965,685 @@ TEST(SampleConsensusModelEllipse3D, RANSAC) EXPECT_NEAR(1.0, std::abs(coeff_refined[10]), 1e-3); } -int -main (int argc, char** argv) +// Heavy oclusion, all points on a 30 degree segment on the major radius +// and 90 degrees on the minor +TEST(SampleConsensusModelTorusOclusion, RANSAC) +{ + + srand(0); + + PointCloud cloud; + PointCloud normals; + + cloud.resize(50); + normals.resize(50); + + cloud[0].getVector3fMap() << 1.4386461277601734, -1.0569588316537601, + 3.6109405500068648; + cloud[1].getVector3fMap() << 1.5892272151771987, -1.0107131751656608, + 3.7524801792294786; + cloud[2].getVector3fMap() << 0.779450850990528, -1.1095381992814901, + 2.1362474566704086; + cloud[3].getVector3fMap() << 2.2332764042301116, -1.0712898227325813, + 4.104289150491388; + cloud[4].getVector3fMap() << 1.4625240977021328, -1.0262438455563425, + 3.6408698702774327; + cloud[5].getVector3fMap() << 1.107288574597542, -1.038213986002474, + 3.2111695308737334; + cloud[6].getVector3fMap() << 1.634136176426644, -1.0586849054858922, + 3.7791937450863844; + cloud[7].getVector3fMap() << 2.8081039281494284, -1.124052124218725, + 4.208730485774282; + cloud[8].getVector3fMap() << 2.7325382847100004, -1.0968720291167913, + 4.214374570675481; + cloud[9].getVector3fMap() << 1.1897810394404515, -1.0861469920822655, + 3.3103205876091675; + cloud[10].getVector3fMap() << 0.8242772124713484, -1.0935505936537508, + 2.4973185149793924; + cloud[11].getVector3fMap() << 2.9589166075430366, -1.0656763334810868, + 4.240842449620676; + cloud[12].getVector3fMap() << 1.7930324882302902, -1.0629548347911097, + 3.8893227292858175; + cloud[13].getVector3fMap() << 0.7810401372209808, -1.0705732580035723, + 2.305065186549668; + cloud[14].getVector3fMap() << 0.9062603270739178, -1.0815748767074063, + 2.785726514647834; + cloud[15].getVector3fMap() << 1.3832157146170436, -1.0790593653653633, + 3.546265907749163; + cloud[16].getVector3fMap() << 2.040614544849421, -1.0918678466867353, + 4.015855816881193; + cloud[17].getVector3fMap() << 2.274098663746168, -1.0273778393320356, + 4.128098505334945; + cloud[18].getVector3fMap() << 1.2518457008499417, -1.0912889870169762, + 3.38890936771287; + cloud[19].getVector3fMap() << 0.8773148573186607, -1.026298817514791, + 2.7419351335271855; + cloud[20].getVector3fMap() << 2.460972277763233, -1.0874470683716413, + 4.168209147029958; + cloud[21].getVector3fMap() << 2.326091552875379, -1.0983984335719184, + 4.125546904328003; + cloud[22].getVector3fMap() << 2.0996991277329786, -1.0707210059905774, + 4.050880542671691; + cloud[23].getVector3fMap() << 0.95831333743683, -1.061687690479444, + 2.9269785200505813; + cloud[24].getVector3fMap() << 2.0588703194976024, -1.0025516869353353, + 4.043701622831673; + normals[0].getNormalVector3fMap() << -0.6776646502188018, -0.2278353266150415, + 0.6991864456566977; + normals[1].getNormalVector3fMap() << -0.6264981002776666, -0.04285270066264479, + 0.7782440339600377; + normals[2].getNormalVector3fMap() << -0.8972132050327152, -0.4381527971259608, + 0.05505080458648829; + normals[3].getNormalVector3fMap() << -0.32813125795357256, -0.2851592909303272, + 0.9005631884270638; + normals[4].getNormalVector3fMap() << -0.6799645795137096, -0.10497538222537117, + 0.7256916285402369; + normals[5].getNormalVector3fMap() << -0.8324065340358171, -0.15285594400989705, + 0.5326672718267207; + normals[6].getNormalVector3fMap() << -0.5919262688649901, -0.2347396219435707, + 0.7710516209161101; + normals[7].getNormalVector3fMap() << -0.07514704519204393, -0.4962084968749015, + 0.8649451134193752; + normals[8].getNormalVector3fMap() << -0.11054456443635059, -0.387488116467167, + 0.9152228465626854; + normals[9].getNormalVector3fMap() << -0.7604417087668234, -0.34458796832906313, + 0.5504430394242827; + normals[10].getNormalVector3fMap() << -0.9040312337559508, -0.3742023746150035, + 0.20664005232816324; + normals[11].getNormalVector3fMap() << -0.0176869745485768, -0.2627053339243488, + 0.964713987904713; + normals[12].getNormalVector3fMap() << -0.5210086952913671, -0.25181933916444066, + 0.8155592926658195; + normals[13].getNormalVector3fMap() << -0.950388588906301, -0.2822930320142894, + 0.13066053020277188; + normals[14].getNormalVector3fMap() << -0.8850007317473024, -0.32629950682962533, + 0.3321179559275326; + normals[15].getNormalVector3fMap() << -0.6856032449538655, -0.31623746146145426, + 0.65569967094482; + normals[16].getNormalVector3fMap() << -0.3996678191380136, -0.36747138674694285, + 0.8397799796778576; + normals[17].getNormalVector3fMap() << -0.3208968621888316, -0.10951135732814456, + 0.9407616416784378; + normals[18].getNormalVector3fMap() << -0.728898292732006, -0.36515594806790613, + 0.5791100175640165; + normals[19].getNormalVector3fMap() << -0.9387598943114375, -0.1051952700591645, + 0.3281216481574453; + normals[20].getNormalVector3fMap() << -0.22602052518599647, -0.34978827348656716, + 0.9091550395427244; + normals[21].getNormalVector3fMap() << -0.27783106746442193, -0.3935937342876755, + 0.8762955382067529; + normals[22].getNormalVector3fMap() << -0.38553965278262686, -0.2828840239623112, + 0.878257254521215; + normals[23].getNormalVector3fMap() << -0.8823896524250601, -0.24675076191777665, + 0.4006277109564169; + normals[24].getNormalVector3fMap() << -0.4182604905252856, -0.010206747741342384, + 0.908269775103241; + + // 50% noise uniform [-2,2] + // + cloud[25].getVector3fMap() << 0.25023241635877147, 0.27654549396527894, + 1.07955881369387; + cloud[26].getVector3fMap() << 1.5449856383148206, -0.46768009897289264, + -2.062172100500517; + cloud[27].getVector3fMap() << 2.068709384697231, -0.8995244010670893, + 0.4472750119304405; + cloud[28].getVector3fMap() << -1.9703101501142217, 1.1677926799358453, + -1.0951161775500093; + cloud[29].getVector3fMap() << 1.5128012164196942, -0.3784790741317119, + 1.9953141538660382; + cloud[30].getVector3fMap() << -1.7035274240520712, -0.040343373432154106, + -0.13506114362465782; + cloud[31].getVector3fMap() << 1.390301434734198, -1.0836155740357354, + 1.3817400889837255; + cloud[32].getVector3fMap() << 0.6973526735174085, 1.4609265623041212, + 0.3991283042562106; + cloud[33].getVector3fMap() << 0.4585644490692351, 1.8056826118986748, + 1.1908087822224616; + cloud[34].getVector3fMap() << -1.899161354377058, -1.2250806902713103, + 1.5135509588271026; + cloud[35].getVector3fMap() << 0.05728241071603746, -1.3140082682155136, + -1.6804780212669348; + cloud[36].getVector3fMap() << -0.5371089158049953, -0.02542717526439331, + -0.6188539490393421; + cloud[37].getVector3fMap() << -0.21842672967261145, 0.6528285340670843, + 1.937369474575887; + cloud[38].getVector3fMap() << 1.6906916394191258, 1.6029527944840072, + 1.3312465637845015; + cloud[39].getVector3fMap() << 0.3871457304584722, -0.7014470556575774, + -1.3686189094260588; + cloud[40].getVector3fMap() << 1.1287360826333366, -1.8859435547052814, + -0.1392786225318703; + cloud[41].getVector3fMap() << -0.8284092960915028, 1.0112260700590863, + -1.1937340633604672; + cloud[42].getVector3fMap() << 1.8440270354564277, -0.3703200026464992, + -1.5917391524525757; + cloud[43].getVector3fMap() << 0.02671922592530418, 1.7827062803768543, + 0.22852714632858673; + cloud[44].getVector3fMap() << -1.5132468082647963, -1.3357890987499987, + -1.158617245205414; + cloud[45].getVector3fMap() << -1.1450583549521511, 1.45432498632732, + -2.095300144813141; + cloud[46].getVector3fMap() << 0.18809078359436793, -1.6008222007566066, + -1.9699784955663424; + cloud[47].getVector3fMap() << -1.1753993948548627, 1.5857927603987902, + 0.14497327864750886; + cloud[48].getVector3fMap() << 1.121788740853686, -0.27095183911320286, + -0.12199102154089814; + cloud[49].getVector3fMap() << 0.768999145889063, -2.0309651709863434, + 0.7930530394403963; + normals[25].getNormalVector3fMap() << -0.5835940349115277, 0.1757014210775822, + 0.7928095692201251; + normals[26].getNormalVector3fMap() << -0.6960838602866861, -0.42094642891496487, + -0.5816110069729798; + normals[27].getNormalVector3fMap() << 0.255914777841287, 0.6279839361250196, + -0.7349447614966528; + normals[28].getNormalVector3fMap() << -0.6075736135140413, 0.1336509980609126, + -0.7829378742140479; + normals[29].getNormalVector3fMap() << -0.4983181083004855, 0.6669454154651717, + -0.5539520518328415; + normals[30].getNormalVector3fMap() << -0.7745671302471588, 0.5084406300820161, + -0.37620989676307437; + normals[31].getNormalVector3fMap() << -0.424778132583581, -0.3243720781494619, + 0.8451900928168792; + normals[32].getNormalVector3fMap() << -0.5821055941507861, 0.35171580987235973, + 0.73310917764286; + normals[33].getNormalVector3fMap() << 0.8396655225180351, -0.48303927894460474, + 0.2482637011147448; + normals[34].getNormalVector3fMap() << 0.256742174797301, 0.7352345686595317, + 0.6273066114177216; + normals[35].getNormalVector3fMap() << -0.0652239383938407, -0.5360244339035914, + 0.8416790624214975; + normals[36].getNormalVector3fMap() << 0.6702382164209467, -0.3031905309377628, + 0.6773892789220579; + normals[37].getNormalVector3fMap() << -0.6040272704362459, -0.10302003040831528, + -0.7902771222197995; + normals[38].getNormalVector3fMap() << 0.9983521281387145, 0.041967677271189614, + -0.03913747954788317; + normals[39].getNormalVector3fMap() << -0.573664090993926, 0.46793032429526715, + 0.6722728034875713; + normals[40].getNormalVector3fMap() << -0.5945467180061245, -0.48897233716525434, + -0.6382948014791401; + normals[41].getNormalVector3fMap() << 0.11334045761805764, -0.6164053590067436, + 0.7792293462483921; + normals[42].getNormalVector3fMap() << -0.766256491311007, 0.13240541094009678, + -0.6287446196012567; + normals[43].getNormalVector3fMap() << 0.43564165550696804, 0.7816025130800787, + 0.4464458080596722; + normals[44].getNormalVector3fMap() << 0.7597220695940338, -0.5120511261307517, + -0.4007817625591101; + normals[45].getNormalVector3fMap() << -0.6597147170804349, -0.27171235425320656, + -0.7006774497681952; + normals[46].getNormalVector3fMap() << -0.14344953607996272, 0.06349058786868034, + -0.9876189426345229; + normals[47].getNormalVector3fMap() << 0.2696193746529791, 0.8928064202811087, + -0.36083526534496174; + normals[48].getNormalVector3fMap() << 0.5473019047514905, 0.29388155846326774, + -0.7836416621457739; + normals[49].getNormalVector3fMap() << 0.053697689135186716, 0.05924709269452209, + -0.9967980438327452; + + SampleConsensusModelTorus::Ptr model( + new SampleConsensusModelTorus(cloud.makeShared())); + + model->setInputNormals(normals.makeShared()); + + // Create the RANSAC object + // Small threshold to filter out the numerous outliers + RandomSampleConsensus sac(model, 0.001); + + // Algorithm tests + bool result = sac.computeModel(); + ASSERT_TRUE(result); + + pcl::Indices sample; + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); + pcl::Indices inliers; + sac.getInliers(inliers); + EXPECT_EQ(25, inliers.size()); + + Eigen::VectorXf coeff; + sac.getModelCoefficients(coeff); + + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 2, 1e-2); + EXPECT_NEAR(coeff[1], 0.25, 1e-2); + EXPECT_NEAR(coeff[2], 3, 1e-2); + EXPECT_NEAR(coeff[3], -1, 1e-2); + EXPECT_NEAR(coeff[4], 2, 1e-2); + EXPECT_NEAR(coeff[5], 0.0, 1e-2); + EXPECT_NEAR(std::abs(coeff[6]), 1.0, 1e-2); + EXPECT_NEAR(coeff[7], 0.0, 1e-2); + Eigen::VectorXf coeff_refined; + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 2, 1e-2); + EXPECT_NEAR(coeff[1], 0.25, 1e-2); + EXPECT_NEAR(coeff[2], 3, 1e-2); + EXPECT_NEAR(coeff[3], -1, 1e-2); + EXPECT_NEAR(coeff[4], 2, 1e-2); + EXPECT_NEAR(coeff[5], 0.0, 1e-2); + EXPECT_NEAR(std::abs(coeff[6]), 1.0, 1e-2); + EXPECT_NEAR(coeff[7], 2.220446049250313e-16, 1e-2); +} + +// A horn shaped torus +TEST(SampleConsensusModelTorusHorn, RANSAC) +{ + + srand(0); + + PointCloud cloud; + PointCloud normals; + + cloud.resize(7); + normals.resize(7); + + cloud[0].getVector3fMap() << 3.000501648262739, -1.0005866141772064, + 2.0196299263944386; + cloud[1].getVector3fMap() << 2.9306387358067587, -0.9355559306559758, + 1.804104008927194; + cloud[2].getVector3fMap() << 3.1148967392352143, -1.3928055353556932, + 2.1927039488583757; + cloud[3].getVector3fMap() << 3.0736420787608285, -0.8370133320562925, + 1.7603380061176133; + cloud[4].getVector3fMap() << 2.88008899080742, -1.245300517665885, 1.7510639730129496; + cloud[5].getVector3fMap() << 3.0000040500927305, -1.0005041529688534, + 2.0158691660694794; + cloud[6].getVector3fMap() << 2.983210284063484, -0.5044792022516073, + 2.0456050860401795; + normals[0].getNormalVector3fMap() << -0.6479150922982518, 0.7576547294171206, + 0.07851970557775474; + normals[1].getNormalVector3fMap() << 0.45515258767393824, -0.4228856734855979, + -0.783583964291224; + normals[2].getNormalVector3fMap() << 0.17884740355312917, -0.6114381536611204, + 0.7708157954335032; + normals[3].getNormalVector3fMap() << -0.11718185523562125, -0.2593500950773666, + -0.958647975529547; + normals[4].getNormalVector3fMap() << -0.04047436729113163, -0.08279792919404502, + -0.995744107948202; + normals[5].getNormalVector3fMap() << -0.008017000458096018, 0.9979511214462377, + 0.06347666427791779; + normals[6].getNormalVector3fMap() << -0.03329532756428898, 0.9826567250055698, + 0.18242034416071792; + + SampleConsensusModelTorus::Ptr model( + new SampleConsensusModelTorus(cloud.makeShared())); + + model->setInputNormals(normals.makeShared()); + + // Create the RANSAC object + RandomSampleConsensus sac(model, 0.2); + + // Algorithm tests + bool result = sac.computeModel(); + ASSERT_TRUE(result); + + pcl::Indices sample; + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); + pcl::Indices inliers; + sac.getInliers(inliers); + EXPECT_EQ(7, inliers.size()); + + Eigen::VectorXf coeff; + sac.getModelCoefficients(coeff); + + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 0.25, 1e-2); + EXPECT_NEAR(coeff[1], 0.25, 1e-2); + EXPECT_NEAR(coeff[2], 3, 1e-2); + EXPECT_NEAR(coeff[3], -1, 1e-2); + EXPECT_NEAR(coeff[4], 2, 1e-2); + EXPECT_NEAR(coeff[5], 0.0, 1e-2); + EXPECT_NEAR(coeff[6], 0.0, 1e-2); + EXPECT_NEAR(std::abs(coeff[7]), 1.0, 1e-2); + return; + + Eigen::VectorXf coeff_refined; + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 0.25, 1e-2); + EXPECT_NEAR(coeff[1], 0.25, 1e-2); + EXPECT_NEAR(coeff[2], 3, 1e-2); + EXPECT_NEAR(coeff[3], -1, 1e-2); + EXPECT_NEAR(coeff[4], 2, 1e-2); + EXPECT_NEAR(coeff[5], 0.0, 1e-2); + EXPECT_NEAR(coeff[6], 0.0, 1e-2); + EXPECT_NEAR(coeff[7], 1.0, 1e-2); +} + +TEST(SampleConsensusModelTorusRefine, RANSAC) +{ + + srand(0); + + PointCloud cloud; + PointCloud normals; + + cloud.resize(12); + normals.resize(12); + + cloud[0].getVector3fMap() << 2.052800042174215, -1.499473956010903, 2.5922393000558; + cloud[1].getVector3fMap() << 3.388588815443773, -0.2804951689253241, + 2.016023579560368; + cloud[2].getVector3fMap() << 2.1062433380708585, -1.9174254209231951, + 2.2138169934854175; + cloud[3].getVector3fMap() << 2.9741032000482, -1.0699765160210948, 1.2784833859363935; + cloud[4].getVector3fMap() << 3.9945837837405858, -0.24398838472758466, + 1.994969222832288; + cloud[5].getVector3fMap() << 3.29052359025732, -0.7052701711244429, + 1.4026501046485196; + cloud[6].getVector3fMap() << 3.253762467235399, -1.2666426752546665, + 1.2533731806961965; + cloud[7].getVector3fMap() << 2.793231427168476, -1.406941876180895, 2.914835409806976; + cloud[8].getVector3fMap() << 3.427656537026421, -0.3921726018138755, + 1.1167321991754167; + cloud[9].getVector3fMap() << 3.45310885872988, -1.187857062974888, 0.9128847947344318; + + normals[0].getNormalVector3fMap() << -0.9655752892034741, 0.13480487505578329, + 0.22246798992399325; + normals[1].getNormalVector3fMap() << -0.9835035116470829, -0.02321732676535275, + -0.17939286026965295; + normals[2].getNormalVector3fMap() << -0.6228348353863176, -0.7614744633300792, + 0.17953665231775656; + normals[3].getNormalVector3fMap() << -0.3027649706212169, 0.4167626949130777, + 0.8571127281131243; + normals[4].getNormalVector3fMap() << 0.9865410652838972, 0.13739803967452247, + 0.08864821037173687; + normals[5].getNormalVector3fMap() << -0.723213640950708, -0.05078427284613152, + 0.688754663994597; + normals[6].getNormalVector3fMap() << 0.4519195477489684, -0.4187464441250127, + 0.7876675300499734; + normals[7].getNormalVector3fMap() << 0.7370319397802214, -0.6656659398898118, + 0.11693064702813241; + normals[8].getNormalVector3fMap() << -0.4226770542031876, 0.7762818780175667, + -0.4676863839279862; + normals[9].getNormalVector3fMap() << 0.720025487985072, -0.5768131803911037, + -0.38581064212766236; + + // Uniform noise between -0.1 and 0.1 + cloud[0].getVector3fMap() += Eigen::Vector3f(-0.02519484, 0.03325529, 0.09188957); + cloud[1].getVector3fMap() += Eigen::Vector3f(0.06969781, -0.06921317, -0.07229406); + cloud[2].getVector3fMap() += Eigen::Vector3f(-0.00064637, -0.00231905, -0.0080026); + cloud[3].getVector3fMap() += Eigen::Vector3f(0.05039557, -0.0229141, 0.0594657); + cloud[4].getVector3fMap() += Eigen::Vector3f(-0.05717322, -0.09670288, 0.00176189); + cloud[5].getVector3fMap() += Eigen::Vector3f(0.02668492, -0.06824032, 0.05790168); + cloud[6].getVector3fMap() += Eigen::Vector3f(0.07829713, 0.06426746, 0.04172692); + cloud[7].getVector3fMap() += Eigen::Vector3f(0.0006326, -0.02518951, -0.00927858); + cloud[8].getVector3fMap() += Eigen::Vector3f(-0.04975343, 0.09912357, -0.04233801); + cloud[9].getVector3fMap() += Eigen::Vector3f(-0.04810247, 0.03382804, 0.07958129); + + // Outliers + cloud[10].getVector3fMap() << 5, 1, 1; + cloud[11].getVector3fMap() << 5, 2, 1; + + normals[10].getNormalVector3fMap() << 1, 0, 0; + normals[11].getNormalVector3fMap() << 1, 0, 0; + + SampleConsensusModelTorus::Ptr model( + new SampleConsensusModelTorus(cloud.makeShared())); + + model->setInputNormals(normals.makeShared()); + + // Create the RANSAC object + RandomSampleConsensus sac(model, 0.2); + + // Algorithm tests + bool result = sac.computeModel(); + ASSERT_TRUE(result); + + pcl::Indices sample; + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); + pcl::Indices inliers; + sac.getInliers(inliers); + EXPECT_EQ(10, inliers.size()); + + Eigen::VectorXf coeff; + sac.getModelCoefficients(coeff); + + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 1, 2e-1); + EXPECT_NEAR(coeff[1], 0.3, 2e-1); + EXPECT_NEAR(coeff[2], 3, 2e-1); + EXPECT_NEAR(coeff[3], -1, 2e-1); + EXPECT_NEAR(coeff[4], 2, 2e-1); + + if (coeff[5] < 0){ + coeff[5] *= -1.0; + coeff[6] *= -1.0; + coeff[7] *= -1.0; + } + + EXPECT_NEAR(coeff[5], 0.7071067811865476, 2e-1); + EXPECT_NEAR(coeff[6], -0.6830127018922194, 2e-1); + EXPECT_NEAR(coeff[7], 0.1830127018922194, 2e-1); + + Eigen::VectorXf coeff_refined(8); + return; + + // Optimize goes from 2e-1 to 1e-1 + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 1, 1e-1); + EXPECT_NEAR(coeff[1], 0.3, 1e-1); + EXPECT_NEAR(coeff[2], 3, 1e-1); + EXPECT_NEAR(coeff[3], -1, 1e-1); + EXPECT_NEAR(coeff[4], 2, 1e-1); + EXPECT_NEAR(coeff[5], 0.7071067811865476, 1e-1); + EXPECT_NEAR(coeff[6], -0.6830127018922194, 1e-1); + EXPECT_NEAR(coeff[7], 0.1830127018922194, 1e-1); +} + +TEST(SampleConsensusModelTorus, RANSAC) +{ + srand(0); + + PointCloud cloud; + PointCloud normals; + + cloud.resize(4); + normals.resize(4); + + cloud[0].getVector3fMap() << 8.359341574088198, 7.22552693060636, 5.4049978066219575; + cloud[1].getVector3fMap() << 7.777710489873524, 6.9794499622227635, 5.96264148630509; + cloud[2].getVector3fMap() << 7.578062528900397, 8.466627338184125, 6.764936180563802; + cloud[3].getVector3fMap() << 6.8073801963063225, 6.950495936581675, + 6.5682651621988140636; + + normals[0].getNormalVector3fMap() << 0.78726775, -0.60899961, -0.09658657; + normals[1].getNormalVector3fMap() << 0.66500173, 0.11532684, 0.73788374; + normals[2].getNormalVector3fMap() << -0.58453172, 0.0233942, -0.81103353; + normals[3].getNormalVector3fMap() << -0.92017329, -0.39125533, 0.01415573; + + // Create a shared 3d torus model pointer directly + SampleConsensusModelTorus::Ptr model( + new SampleConsensusModelTorus(cloud.makeShared())); + model->setInputNormals(normals.makeShared()); + + // Create the RANSAC object + RandomSampleConsensus sac(model, 0.11); + + // Algorithm tests + bool result = sac.computeModel(); + ASSERT_TRUE(result); + + pcl::Indices sample; + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); + pcl::Indices inliers; + sac.getInliers(inliers); + EXPECT_EQ(4, inliers.size()); + + Eigen::VectorXf coeff; + sac.getModelCoefficients(coeff); + + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 1, 1e-2); + EXPECT_NEAR(coeff[1], 0.3, 1e-2); + + EXPECT_NEAR(coeff[2], 7.758357590948854, 1e-2); + EXPECT_NEAR(coeff[3], 7.756009480304242, 1e-2); + EXPECT_NEAR(coeff[4], 6.297666724054506, 1e-2); + + EXPECT_NEAR(coeff[5], 0.7071067811865475, 1e-2); + EXPECT_NEAR(coeff[6], -0.5, 1e-2); + EXPECT_NEAR(coeff[7], 0.5, 1e-2); + + Eigen::VectorXf coeff_refined; + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(8, coeff.size()); + + EXPECT_NEAR(coeff[0], 1, 1e-2); + EXPECT_NEAR(coeff[1], 0.3, 1e-2); + + EXPECT_NEAR(coeff[2], 7.758357590948854, 1e-2); + EXPECT_NEAR(coeff[3], 7.756009480304242, 1e-2); + EXPECT_NEAR(coeff[4], 6.297666724054506, 1e-2); + + if (coeff[5] < 0){ + coeff[5] *= -1.0; + coeff[6] *= -1.0; + coeff[7] *= -1.0; + } + + EXPECT_NEAR(coeff[5], 0.7071067811865475, 1e-2); + EXPECT_NEAR(coeff[6], -0.5, 1e-2); + EXPECT_NEAR(coeff[7], 0.5, 1e-2); +} + +TEST(SampleConsensusModelTorusSelfIntersectSpindle, RANSAC) { - testing::InitGoogleTest (&argc, argv); - return (RUN_ALL_TESTS ()); + srand(0); + + PointCloud cloud; + PointCloud normals; + + cloud.resize(15); + normals.resize(15); + + cloud[0].getVector3fMap() << 4.197443296388562, -2.244178951074561, + 2.6544058976891054; + cloud[1].getVector3fMap() << 3.9469472011448596, -2.2109428683077716, + 1.8207364262436627; + cloud[2].getVector3fMap() << 4.036997360721013, -1.9837065514073593, 2.88062697126334; + cloud[3].getVector3fMap() << 4.554241490476904, -1.8200324440442106, + 2.242830580711606; + cloud[4].getVector3fMap() << 3.9088172351876764, -1.7982235216273337, + 2.268412990083617; + cloud[5].getVector3fMap() << 3.842480541291084, -1.8025598756948282, + 2.2527669926394016; + cloud[6].getVector3fMap() << 4.3496726790753755, -2.2441275500858833, + 2.239055754148472; + cloud[7].getVector3fMap() << 4.52235090070925, -1.7373785296059916, 2.466177376096933; + cloud[8].getVector3fMap() << 3.7710839801895077, -1.7082589118588576, + 2.393963290485919; + cloud[9].getVector3fMap() << 4.068180803015269, -1.3503789464621836, + 2.3423326381708147; + cloud[10].getVector3fMap() << 3.873973067071098, -1.7135016016729774, + 2.2124191518411247; + cloud[11].getVector3fMap() << 4.390758174759903, -2.171435874256942, + 2.214023036691005; + cloud[12].getVector3fMap() << 4.324106983802413, -1.3650663408422128, + 2.453692863759843; + cloud[13].getVector3fMap() << 4.345401269961894, -2.0286148560415813, + 2.456689045210522; + cloud[14].getVector3fMap() << 4.31528844186095, -2.0083582606580292, + 2.367720270538135; + normals[0].getNormalVector3fMap() << 0.6131882081326164, -0.6055955130301103, + 0.5072024211347066; + normals[1].getNormalVector3fMap() << -0.37431625455633444, -0.44239562607541916, + -0.8149683746037361; + normals[2].getNormalVector3fMap() << 0.03426300530560111, -0.20348141751799728, + 0.9784791051383237; + normals[3].getNormalVector3fMap() << 0.940856493913579, -0.2960809146555105, + 0.1646971458083096; + normals[4].getNormalVector3fMap() << -0.6286552509632886, 0.5146645236295431, + 0.5830205858745127; + normals[5].getNormalVector3fMap() << -0.3871040511550286, 0.724048220462587, + -0.5708805724705703; + normals[6].getNormalVector3fMap() << 0.8666661368649906, -0.43068753570421703, + 0.25178970153789454; + normals[7].getNormalVector3fMap() << 0.9362467937507173, -0.17430389316386408, + 0.30505752575444156; + normals[8].getNormalVector3fMap() << -0.8229596731853971, 0.3855286394843701, + -0.4172589656890726; + normals[9].getNormalVector3fMap() << -0.36653063101311856, 0.9297937437536523, + -0.033747453321582466; + normals[10].getNormalVector3fMap() << -0.9907072431684454, -0.07717115427192464, + -0.11199897893247729; + normals[11].getNormalVector3fMap() << 0.8661927924780622, -0.3669697390799624, + 0.3391802719184018; + normals[12].getNormalVector3fMap() << 0.3744106777049837, 0.8911051835726027, + 0.25641411082569643; + normals[13].getNormalVector3fMap() << 0.8809879144326921, -0.4062669413039098, + -0.2425025093212462; + normals[14].getNormalVector3fMap() << 0.8117975834319093, -0.31266565300418725, + -0.49317833789165666; + + // Create a shared 3d torus model pointer directly + SampleConsensusModelTorus::Ptr model( + new SampleConsensusModelTorus(cloud.makeShared())); + model->setInputNormals(normals.makeShared()); + + // Create the RANSAC object + RandomSampleConsensus sac(model, 0.11); + + // Algorithm tests + bool result = sac.computeModel(); + ASSERT_TRUE(result); + + pcl::Indices sample; + sac.getModel(sample); + EXPECT_EQ(4, sample.size()); + pcl::Indices inliers; + sac.getInliers(inliers); + EXPECT_EQ(15, inliers.size()); + + Eigen::VectorXf coeff; + sac.getModelCoefficients(coeff); + + EXPECT_EQ(8, coeff.size()); + EXPECT_NEAR(coeff[0], 0.25, 1e-2); + EXPECT_NEAR(coeff[1], 0.35, 1e-2); + EXPECT_NEAR(coeff[2], 4.1, 1e-2); + EXPECT_NEAR(coeff[3], -1.9, 1e-2); + EXPECT_NEAR(coeff[4], 2.3, 1e-2); + EXPECT_NEAR(coeff[5], 0.8660254037844385, 1e-2); + EXPECT_NEAR(coeff[6], -0.4330127018922194, 1e-2); + EXPECT_NEAR(coeff[7], 0.25000000000000017, 1e-2); + + Eigen::VectorXf coeff_refined; + model->optimizeModelCoefficients(inliers, coeff, coeff_refined); + EXPECT_EQ(8, coeff.size()); + EXPECT_NEAR(coeff[0], 0.25, 1e-2); + EXPECT_NEAR(coeff[1], 0.35, 1e-2); + EXPECT_NEAR(coeff[2], 4.1, 1e-2); + EXPECT_NEAR(coeff[3], -1.9, 1e-2); + EXPECT_NEAR(coeff[4], 2.3, 1e-2); + + if (coeff[5] < 0){ + coeff[5] *= -1.0; + coeff[6] *= -1.0; + coeff[7] *= -1.0; + } + + EXPECT_NEAR(coeff[5], 0.8660254037844385, 1e-2); + EXPECT_NEAR(coeff[6], -0.4330127018922194, 1e-2); + EXPECT_NEAR(coeff[7], 0.25000000000000017, 1e-2); } +int +main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return (RUN_ALL_TESTS()); +} From d21228dd3941e59c7d1e0a8cfe9bee5806a5e5da Mon Sep 17 00:00:00 2001 From: qiuyilin Date: Thu, 30 May 2024 09:27:11 +0800 Subject: [PATCH 260/288] fix by casting int to size_t --- gpu/octree/include/pcl/gpu/octree/device_format.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gpu/octree/include/pcl/gpu/octree/device_format.hpp b/gpu/octree/include/pcl/gpu/octree/device_format.hpp index e47d7f311e8..1a7be92a9af 100644 --- a/gpu/octree/include/pcl/gpu/octree/device_format.hpp +++ b/gpu/octree/include/pcl/gpu/octree/device_format.hpp @@ -58,7 +58,7 @@ namespace pcl void create(int query_number, int max_elements) { max_elems = max_elements; - data.create (query_number * max_elems); + data.create (static_cast(query_number) * static_cast(max_elems)); if (max_elems != 1) sizes.create(query_number); From fb100d959a4cf247714aa90d7ae0906ad9983ea3 Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 30 May 2024 08:11:54 +0200 Subject: [PATCH 261/288] Remove global includes and use target include for Apps (#6009) * use target_include_directories instead of globals. --- apps/3d_rec_framework/CMakeLists.txt | 2 - apps/CMakeLists.txt | 98 ++++++++++++++------------ apps/cloud_composer/CMakeLists.txt | 2 - apps/in_hand_scanner/CMakeLists.txt | 4 +- apps/modeler/CMakeLists.txt | 5 +- apps/point_cloud_editor/CMakeLists.txt | 6 +- examples/CMakeLists.txt | 1 - outofcore/tools/CMakeLists.txt | 1 - simulation/tools/CMakeLists.txt | 2 - 9 files changed, 59 insertions(+), 62 deletions(-) diff --git a/apps/3d_rec_framework/CMakeLists.txt b/apps/3d_rec_framework/CMakeLists.txt index 57015b61634..433b782ba29 100644 --- a/apps/3d_rec_framework/CMakeLists.txt +++ b/apps/3d_rec_framework/CMakeLists.txt @@ -16,8 +16,6 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include") - set(incs_fw "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/feature_wrapper/normal_estimator.h" ) diff --git a/apps/CMakeLists.txt b/apps/CMakeLists.txt index b501bac85c5..269cb62c30d 100644 --- a/apps/CMakeLists.txt +++ b/apps/CMakeLists.txt @@ -15,16 +15,40 @@ set(CMAKE_AUTOMOC ON) set(CMAKE_AUTORCC ON) set(CMAKE_AUTOUIC ON) +list(APPEND CMAKE_AUTOUIC_SEARCH_PATHS "src") + +if(VTK_FOUND) + set(incs "include/pcl/${SUBSYS_NAME}/render_views_tesselated_sphere.h") + set(srcs "src/render_views_tesselated_sphere.cpp") +endif() + +if(QHULL_FOUND) + set(incs + "include/pcl/${SUBSYS_NAME}/dominant_plane_segmentation.h" + "include/pcl/${SUBSYS_NAME}/timer.h" + ${incs} + ) + set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/dominant_plane_segmentation.hpp") + set(srcs "src/dominant_plane_segmentation.cpp" ${srcs}) +endif() + +set(LIB_NAME "pcl_${SUBSYS_NAME}") +PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${impl_incs} ${incs}) +target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search) +PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC}) +# Install include files +PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) +PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs}) + # to be filled with all targets the apps subsystem set(PCL_APPS_ALL_TARGETS) -include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include") - PCL_ADD_EXECUTABLE(pcl_test_search_speed COMPONENT ${SUBSYS_NAME} SOURCES src/test_search.cpp) target_link_libraries(pcl_test_search_speed pcl_common pcl_io pcl_search pcl_kdtree pcl_visualization) PCL_ADD_EXECUTABLE(pcl_nn_classification_example COMPONENT ${SUBSYS_NAME} SOURCES src/nn_classification_example.cpp) target_link_libraries(pcl_nn_classification_example pcl_common pcl_io pcl_features pcl_kdtree) +target_include_directories(pcl_nn_classification_example PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_pyramid_surface_matching COMPONENT ${SUBSYS_NAME} SOURCES src/pyramid_surface_matching.cpp) target_link_libraries(pcl_pyramid_surface_matching pcl_common pcl_io pcl_features pcl_registration pcl_filters) @@ -38,9 +62,6 @@ if(LIBUSB_FOUND) endif() if(VTK_FOUND) - set(incs "include/pcl/${SUBSYS_NAME}/render_views_tesselated_sphere.h") - set(srcs "src/render_views_tesselated_sphere.cpp") - PCL_ADD_EXECUTABLE(pcl_ppf_object_recognition COMPONENT ${SUBSYS_NAME} SOURCES src/ppf_object_recognition.cpp) target_link_libraries(pcl_ppf_object_recognition pcl_common pcl_io pcl_filters pcl_features pcl_registration pcl_visualization pcl_sample_consensus pcl_segmentation) @@ -70,8 +91,9 @@ if(VTK_FOUND) PCL_ADD_EXECUTABLE(pcl_face_trainer COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection/face_trainer.cpp) target_link_libraries(pcl_face_trainer pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree) - PCL_ADD_EXECUTABLE(pcl_fs_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection//filesystem_face_detection.cpp BUNDLE) + PCL_ADD_EXECUTABLE(pcl_fs_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection/filesystem_face_detection.cpp BUNDLE) target_link_libraries(pcl_fs_face_detector pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree) + target_include_directories(pcl_fs_face_detector PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_stereo_ground_segmentation COMPONENT ${SUBSYS_NAME} SOURCES src/stereo_ground_segmentation.cpp) target_link_libraries(pcl_stereo_ground_segmentation pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_features pcl_stereo) @@ -91,6 +113,7 @@ if(VTK_FOUND) BUNDLE) target_link_libraries(pcl_manual_registration pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface pcl_registration ${QTX}::Widgets) + target_include_directories(pcl_manual_registration PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_pcd_video_player COMPONENT @@ -102,6 +125,7 @@ if(VTK_FOUND) BUNDLE) target_link_libraries(pcl_pcd_video_player pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets) + target_include_directories(pcl_pcd_video_player PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) endif() if(WITH_OPENNI) @@ -154,6 +178,7 @@ if(VTK_FOUND) PCL_ADD_EXECUTABLE(pcl_openni_face_detector COMPONENT ${SUBSYS_NAME} SOURCES src/face_detection//openni_face_detection.cpp src/face_detection//openni_frame_source.cpp BUNDLE) target_link_libraries(pcl_openni_face_detector pcl_features pcl_recognition pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface pcl_keypoints pcl_ml pcl_search pcl_kdtree) + target_include_directories(pcl_openni_face_detector PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) if(QT_FOUND AND HAVE_QVTK) # OpenNI Passthrough application demo @@ -161,13 +186,13 @@ if(VTK_FOUND) COMPONENT ${SUBSYS_NAME} SOURCES + include/pcl/apps/openni_passthrough_qt.h include/pcl/apps/openni_passthrough.h src/openni_passthrough.cpp src/openni_passthrough.ui) target_link_libraries(pcl_openni_passthrough pcl_common pcl_io pcl_filters pcl_visualization ${QTX}::Widgets) - - list(APPEND CMAKE_AUTOUIC_SEARCH_PATHS "src") + target_include_directories(pcl_openni_passthrough PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) # OpenNI Organized Connected Component application demo PCL_ADD_EXECUTABLE(pcl_organized_segmentation_demo @@ -180,37 +205,43 @@ if(VTK_FOUND) src/organized_segmentation_demo.ui BUNDLE) target_link_libraries(pcl_organized_segmentation_demo pcl_common pcl_io pcl_visualization pcl_segmentation pcl_features pcl_surface ${QTX}::Widgets) + target_include_directories(pcl_organized_segmentation_demo PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) endif() if(QHULL_FOUND) - PCL_ADD_EXECUTABLE(pcl_openni_3d_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_convex_hull.cpp BUNDLE) - target_link_libraries(pcl_openni_3d_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface) - - PCL_ADD_EXECUTABLE(pcl_openni_3d_concave_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_concave_hull.cpp BUNDLE) - target_link_libraries(pcl_openni_3d_concave_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface) - - PCL_ADD_EXECUTABLE(pcl_openni_tracking COMPONENT ${SUBSYS_NAME} SOURCES src/openni_tracking.cpp BUNDLE) - target_link_libraries(pcl_openni_tracking pcl_common pcl_io pcl_surface pcl_visualization pcl_filters pcl_features pcl_segmentation pcl_tracking pcl_search) - - PCL_ADD_EXECUTABLE(pcl_openni_planar_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_planar_convex_hull.cpp BUNDLE) - target_link_libraries(pcl_openni_planar_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface) - - PCL_ADD_EXECUTABLE(pcl_ni_linemod COMPONENT ${SUBSYS_NAME} SOURCES src/ni_linemod.cpp BUNDLE) - target_link_libraries(pcl_ni_linemod pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface pcl_search) + PCL_ADD_EXECUTABLE(pcl_openni_3d_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_convex_hull.cpp BUNDLE) + target_link_libraries(pcl_openni_3d_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface) + + PCL_ADD_EXECUTABLE(pcl_openni_3d_concave_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_3d_concave_hull.cpp BUNDLE) + target_link_libraries(pcl_openni_3d_concave_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface) + + PCL_ADD_EXECUTABLE(pcl_openni_tracking COMPONENT ${SUBSYS_NAME} SOURCES src/openni_tracking.cpp BUNDLE) + target_link_libraries(pcl_openni_tracking pcl_common pcl_io pcl_surface pcl_visualization pcl_filters pcl_features pcl_segmentation pcl_tracking pcl_search) + + PCL_ADD_EXECUTABLE(pcl_openni_planar_convex_hull COMPONENT ${SUBSYS_NAME} SOURCES src/openni_planar_convex_hull.cpp BUNDLE) + target_link_libraries(pcl_openni_planar_convex_hull pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_surface) + + PCL_ADD_EXECUTABLE(pcl_ni_linemod COMPONENT ${SUBSYS_NAME} SOURCES src/ni_linemod.cpp BUNDLE) + target_link_libraries(pcl_ni_linemod pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_surface pcl_search) + target_include_directories(pcl_ni_linemod PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) endif() # QHULL_FOUND PCL_ADD_EXECUTABLE(pcl_ni_agast COMPONENT ${SUBSYS_NAME} SOURCES src/ni_agast.cpp BUNDLE) target_link_libraries(pcl_ni_agast pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_keypoints pcl_surface pcl_search) + target_include_directories(pcl_ni_agast PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_ni_brisk COMPONENT ${SUBSYS_NAME} SOURCES src/ni_brisk.cpp BUNDLE) target_link_libraries(pcl_ni_brisk pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_sample_consensus pcl_features pcl_keypoints pcl_surface pcl_search) + target_include_directories(pcl_ni_brisk PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_ni_susan COMPONENT ${SUBSYS_NAME} SOURCES src/ni_susan.cpp BUNDLE) target_link_libraries(pcl_ni_susan pcl_common pcl_visualization pcl_features pcl_keypoints pcl_search) + target_include_directories(pcl_ni_susan PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_ni_trajkovic COMPONENT ${SUBSYS_NAME} SOURCES src/ni_trajkovic.cpp BUNDLE) target_link_libraries(pcl_ni_trajkovic pcl_common pcl_visualization pcl_features pcl_keypoints pcl_search) + target_include_directories(pcl_ni_trajkovic PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) PCL_ADD_EXECUTABLE(pcl_openni_klt COMPONENT ${SUBSYS_NAME} SOURCES src/openni_klt.cpp BUNDLE) target_link_libraries(pcl_openni_klt pcl_common pcl_io pcl_visualization pcl_tracking) @@ -219,9 +250,6 @@ endif() # VTK_FOUND # OpenGL and GLUT if(OPENGL_FOUND AND GLUT_FOUND) - if(NOT WIN32) - include_directories(SYSTEM "${OPENGL_INCLUDE_DIR}") - endif() PCL_ADD_EXECUTABLE(pcl_grabcut_2d COMPONENT ${SUBSYS_NAME} SOURCES src/grabcut_2d.cpp BUNDLE) if(APPLE) set(_glut_target ${GLUT_glut_LIBRARY}) @@ -236,27 +264,9 @@ set(PCL_APPS_MODULES_NAMES_UNSORTED ${PCL_APPS_MODULES_NAMES}) topological_sort(PCL_APPS_MODULES_NAMES PCL_APPS_ _DEPENDS) sort_relative(PCL_APPS_MODULES_NAMES_UNSORTED PCL_APPS_MODULES_NAMES PCL_APPS_MODULES_DIRS) foreach(subdir ${PCL_APPS_MODULES_DIRS}) -add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/${subdir}") + add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/${subdir}") endforeach() -if(QHULL_FOUND) - set(incs - "include/pcl/${SUBSYS_NAME}/dominant_plane_segmentation.h" - "include/pcl/${SUBSYS_NAME}/timer.h" - ${incs} - ) - set(impl_incs "include/pcl/${SUBSYS_NAME}/impl/dominant_plane_segmentation.hpp") - set(srcs "src/dominant_plane_segmentation.cpp" ${srcs}) -endif() - -set(LIB_NAME "pcl_${SUBSYS_NAME}") -PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${impl_incs} ${incs}) -target_link_libraries("${LIB_NAME}" pcl_common pcl_io pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search) -PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC}) -# Install include files -PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}" ${incs}) -PCL_ADD_INCLUDES("${SUBSYS_NAME}" "${SUBSYS_NAME}/impl" ${impl_incs}) - if(CMAKE_GENERATOR_IS_IDE) set(SUBSYS_TARGET_NAME APPS_BUILD) else() diff --git a/apps/cloud_composer/CMakeLists.txt b/apps/cloud_composer/CMakeLists.txt index 3e2629fa1c8..083a0fb36e1 100644 --- a/apps/cloud_composer/CMakeLists.txt +++ b/apps/cloud_composer/CMakeLists.txt @@ -28,8 +28,6 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include") - #Create subdirectory for plugin libs set(CLOUD_COMPOSER_PLUGIN_DIR "${CMAKE_LIBRARY_OUTPUT_DIRECTORY}/cloud_composer_plugins") make_directory("${CLOUD_COMPOSER_PLUGIN_DIR}") diff --git a/apps/in_hand_scanner/CMakeLists.txt b/apps/in_hand_scanner/CMakeLists.txt index 753cb3226d7..1059de34cfc 100644 --- a/apps/in_hand_scanner/CMakeLists.txt +++ b/apps/in_hand_scanner/CMakeLists.txt @@ -75,8 +75,6 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include") - set(EXE_NAME "pcl_${SUBSUBSYS_NAME}") PCL_ADD_EXECUTABLE( @@ -91,6 +89,7 @@ PCL_ADD_EXECUTABLE( BUNDLE) target_link_libraries("${EXE_NAME}" ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL) +target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) if (${QTX} MATCHES "Qt6") target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets) endif() @@ -110,6 +109,7 @@ PCL_ADD_EXECUTABLE( BUNDLE) target_link_libraries(pcl_offline_integration ${SUBSUBSYS_LIBS} ${OPENGL_LIBRARIES} ${QTX}::Concurrent ${QTX}::Widgets ${QTX}::OpenGL) +target_include_directories(pcl_offline_integration PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) if (${QTX} MATCHES "Qt6") target_link_libraries(pcl_offline_integration ${QTX}::OpenGLWidgets) endif() diff --git a/apps/modeler/CMakeLists.txt b/apps/modeler/CMakeLists.txt index c48442c2f1c..ced6c8adaab 100644 --- a/apps/modeler/CMakeLists.txt +++ b/apps/modeler/CMakeLists.txt @@ -23,8 +23,6 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_BINARY_DIR}" "${CMAKE_CURRENT_SOURCE_DIR}/include") - # Set Qt files and resources here set(uis main_window.ui @@ -35,7 +33,7 @@ set(resources ) set(incs - "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/main_window.h" + "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/main_window.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/scene_tree.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/parameter_dialog.h" "include/pcl/${SUBSYS_NAME}/${SUBSUBSYS_NAME}/thread_controller.h" @@ -115,6 +113,7 @@ PCL_ADD_EXECUTABLE( ${impl_incs}) target_link_libraries("${EXE_NAME}" pcl_common pcl_io pcl_kdtree pcl_filters pcl_visualization pcl_segmentation pcl_surface pcl_features pcl_sample_consensus pcl_search ${QTX}::Widgets) +target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) # Install include files PCL_ADD_INCLUDES("${SUBSUBSYS_NAME}" "${SUBSUBSYS_NAME}" ${incs}) diff --git a/apps/point_cloud_editor/CMakeLists.txt b/apps/point_cloud_editor/CMakeLists.txt index 814c88eafcf..6a355b1ece6 100644 --- a/apps/point_cloud_editor/CMakeLists.txt +++ b/apps/point_cloud_editor/CMakeLists.txt @@ -68,11 +68,6 @@ set(SRCS src/denoiseParameterForm.cpp ) -include_directories( - "${CMAKE_CURRENT_BINARY_DIR}" - "${CMAKE_CURRENT_SOURCE_DIR}/include" -) - set(EXE_NAME "pcl_${SUBSUBSYS_NAME}") PCL_ADD_EXECUTABLE( ${EXE_NAME} @@ -84,6 +79,7 @@ PCL_ADD_EXECUTABLE( ${INCS}) target_link_libraries("${EXE_NAME}" ${QTX}::Widgets ${QTX}::OpenGL ${OPENGL_LIBRARIES} ${BOOST_LIBRARIES} pcl_common pcl_io pcl_filters) +target_include_directories(${EXE_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/include) if (${QTX} MATCHES "Qt6") target_link_libraries("${EXE_NAME}" ${QTX}::OpenGLWidgets) endif() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 62c02de49e0..af231303c58 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -12,7 +12,6 @@ endif() # this variable will filled with all targets added with pcl_add_example set(PCL_EXAMPLES_ALL_TARGETS) -include_directories(${PCL_INCLUDE_DIRS}) # This looks for all examples/XXX/CMakeLists.txt file (GLOB examples_sbudirs */CMakeLists.txt) # Extract only relevant XXX and append it to PCL_EXAMPLES_SUBDIRS diff --git a/outofcore/tools/CMakeLists.txt b/outofcore/tools/CMakeLists.txt index f33e8b4475d..8f353c84c54 100644 --- a/outofcore/tools/CMakeLists.txt +++ b/outofcore/tools/CMakeLists.txt @@ -13,7 +13,6 @@ if(NOT VTK_FOUND) else() set(DEFAULT TRUE) set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") set(srcs outofcore_viewer.cpp ../src/visualization/camera.cpp diff --git a/simulation/tools/CMakeLists.txt b/simulation/tools/CMakeLists.txt index 39ece06c895..f6ce17a588b 100644 --- a/simulation/tools/CMakeLists.txt +++ b/simulation/tools/CMakeLists.txt @@ -13,8 +13,6 @@ else() set(_glut_target GLUT::GLUT) endif() -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) - PCL_ADD_EXECUTABLE(pcl_sim_viewer COMPONENT ${SUBSYS_NAME} SOURCES sim_viewer.cpp) target_link_libraries (pcl_sim_viewer ${VTK_IO_TARGET_LINK_LIBRARIES} pcl_kdtree From 9cdf0ec8010c7bd49df2c58abab8b5c986cf1918 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 30 May 2024 20:07:21 +0200 Subject: [PATCH 262/288] Allow type conversion in fromPCLPointCloud2 --- common/include/pcl/conversions.h | 70 ++++++++++++++++++++++++++++- test/common/test_io.cpp | 76 ++++++++++++++++++++++++++++++++ 2 files changed, 145 insertions(+), 1 deletion(-) diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 20072819dfa..80bba0491bf 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -104,7 +104,7 @@ namespace pcl } } // Disable thrown exception per #595: http://dev.pointclouds.org/issues/595 - PCL_WARN ("Failed to find match for field '%s'.\n", pcl::traits::name::value); + PCL_WARN ("Failed to find exact match for field '%s'.\n", pcl::traits::name::value); //throw pcl::InvalidConversionException (ss.str ()); } @@ -118,6 +118,71 @@ namespace pcl return (a.serialized_offset < b.serialized_offset); } + // Helps converting PCLPointCloud2 to templated point cloud. Casts fields if datatype is different. + template + struct FieldCaster + { + FieldCaster (const std::vector& fields, const pcl::PCLPointCloud2& msg, const std::uint8_t* msg_data, std::uint8_t* cloud_data) + : fields_ (fields), msg_(msg), msg_data_(msg_data), cloud_data_(cloud_data) + {} + + template void + operator () () + { + // first check whether any field matches exactly. Then there is nothing to do because the contents are memcpy-ed elsewhere + for (const auto& field : fields_) { + if (FieldMatches()(field)) { + return; + } + } + for (const auto& field : fields_) + { + // The following check is similar to FieldMatches, but it tests for different datatypes + if ((field.name == pcl::traits::name::value) && + (field.datatype != pcl::traits::datatype::value) && + ((field.count == pcl::traits::datatype::size) || + (field.count == 0 && pcl::traits::datatype::size == 1))) { +#define PCL_CAST_POINT_FIELD(TYPE) case ::pcl::traits::asEnum_v: \ + PCL_WARN("Will try to cast field '%s' (original type is " #TYPE "). You may loose precision during casting. Make sure that this is acceptable or choose a different point type.\n", pcl::traits::name::value); \ + for (std::size_t row = 0; row < msg_.height; ++row) { \ + const std::uint8_t* row_data = msg_data_ + row * msg_.row_step; \ + for (std::size_t col = 0; col < msg_.width; ++col) { \ + const std::uint8_t* msg_data = row_data + col * msg_.point_step; \ + for(std::uint32_t i=0; i::size; ++i) { \ + *(reinterpret_cast::decomposed::type*>(cloud_data + pcl::traits::offset::value) + i) = *(reinterpret_cast(msg_data + field.offset) + i); \ + } \ + cloud_data += sizeof (PointT); \ + } \ + } \ + break; + // end of PCL_CAST_POINT_FIELD definition + + std::uint8_t* cloud_data = cloud_data_; + switch(field.datatype) { + PCL_CAST_POINT_FIELD(bool) + PCL_CAST_POINT_FIELD(std::int8_t) + PCL_CAST_POINT_FIELD(std::uint8_t) + PCL_CAST_POINT_FIELD(std::int16_t) + PCL_CAST_POINT_FIELD(std::uint16_t) + PCL_CAST_POINT_FIELD(std::int32_t) + PCL_CAST_POINT_FIELD(std::uint32_t) + PCL_CAST_POINT_FIELD(std::int64_t) + PCL_CAST_POINT_FIELD(std::uint64_t) + PCL_CAST_POINT_FIELD(float) + PCL_CAST_POINT_FIELD(double) + default: std::cout << "Unknown datatype: " << field.datatype << std::endl; + } + return; + } +#undef PCL_CAST_POINT_FIELD + } + } + + const std::vector& fields_; + const pcl::PCLPointCloud2& msg_; + const std::uint8_t* msg_data_; + std::uint8_t* cloud_data_; + }; } //namespace detail template void @@ -223,6 +288,9 @@ namespace pcl } } } + // if any fields in msg and cloud have different datatypes but the same name, we cast them: + detail::FieldCaster caster (msg.fields, msg, msg_data, reinterpret_cast(cloud.data())); + for_each_type< typename traits::fieldList::type > (caster); } /** \brief Convert a PCLPointCloud2 binary data blob into a pcl::PointCloud object using a field_map. diff --git a/test/common/test_io.cpp b/test/common/test_io.cpp index 43c2ac1709a..489fb7871ce 100644 --- a/test/common/test_io.cpp +++ b/test/common/test_io.cpp @@ -296,6 +296,82 @@ TEST (toPCLPointCloud2NoPadding, PointXYZI) } } +TEST(PCL, fromPCLPointCloud2CastingXYZI) +{ + // test fromPCLPointCloud2, but in PCLPointCloud2 the fields have different types than in PointXYZI + pcl::PCLPointCloud2 msg; + msg.height = 2; + msg.width = 2; + msg.fields.resize(4); + msg.fields[0].name = "x"; + msg.fields[0].offset = 0; + msg.fields[0].datatype = pcl::PCLPointField::FLOAT64; + msg.fields[0].count = 1; + msg.fields[1].name = "y"; + msg.fields[1].offset = 8; + msg.fields[1].datatype = pcl::PCLPointField::FLOAT64; + msg.fields[1].count = 1; + msg.fields[2].name = "z"; + msg.fields[2].offset = 16; + msg.fields[2].datatype = pcl::PCLPointField::FLOAT64; + msg.fields[2].count = 1; + msg.fields[3].name = "intensity"; + msg.fields[3].offset = 24; + msg.fields[3].datatype = pcl::PCLPointField::UINT16; + msg.fields[3].count = 1; + msg.point_step = 32; + msg.row_step = 32*msg.width; + msg.data.resize(32*msg.width*msg.height); + for(std::size_t i=0; i(i, 0) = 1.0*i; + msg.at(i, 8) = -1.6*i; + msg.at(i, 16) = -3.141*i; + msg.at(i, 24) = 123*i; + } + pcl::PointCloud cloud; + pcl::fromPCLPointCloud2(msg, cloud); + for(std::size_t i=0; i(i, 8*j) = 1000*i+j; + for(std::size_t j=0; j<9; ++j) + msg.at(i, 352*8+8*j) = (10*i+j)/10.0; + } + pcl::PointCloud cloud; + pcl::fromPCLPointCloud2(msg, cloud); + for(std::size_t i=0; i Date: Mon, 3 Jun 2024 20:17:20 +0300 Subject: [PATCH 263/288] ExtractPolygonalPrismData and ConcaveHull bugfix (#5168) * ExtractPolygonalPrismData and ConcaveHull bugfix https://github.com/PointCloudLibrary/pcl/issues/5163#issuecomment-1035406759 * ExtractPolygonalPrismData and ConcaveHull bugfix https://github.com/PointCloudLibrary/pcl/issues/5163#issuecomment-1035406759 * test by generating the concave hull manually * sin and cos for floats * azure test compilation errors * minor changes per code review * minor changes per review * Update CMakeLists.txt * Update test_concave_prism.cpp * Update extract_polygonal_prism_data.hpp * Rename * Rename * Rename * Update extract_polygonal_prism_data.hpp --------- Co-authored-by: Yoav Miller Co-authored-by: Markus Vieth <39675748+mvieth@users.noreply.github.com> --- .../extract_polygonal_prism_data.h | 14 +++ .../impl/extract_polygonal_prism_data.hpp | 22 ++++- test/segmentation/CMakeLists.txt | 4 + test/segmentation/test_concave_prism.cpp | 92 +++++++++++++++++++ 4 files changed, 131 insertions(+), 1 deletion(-) create mode 100644 test/segmentation/test_concave_prism.cpp diff --git a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h index 0739726c53e..08cc63f91d1 100644 --- a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h +++ b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h @@ -40,6 +40,7 @@ #include #include +#include // for Vertices namespace pcl { @@ -124,6 +125,16 @@ namespace pcl inline void setInputPlanarHull (const PointCloudConstPtr &hull) { planar_hull_ = hull; } + /** \brief Provide a vector of the concave polygons indices, as recieved from ConcaveHull::polygons. + * \note This is only needed when using ConcaveHull that has more than one polygon. + * \param[in] polygons - see ConcaveHull::polygons + */ + inline void + setPolygons(const std::vector& polygons) + { + polygons_ = polygons; + } + /** \brief Get a pointer the input planar hull dataset. */ inline PointCloudConstPtr getInputPlanarHull () const { return (planar_hull_); } @@ -185,6 +196,9 @@ namespace pcl /** \brief A pointer to the input planar hull dataset. */ PointCloudConstPtr planar_hull_{nullptr}; + /** \brief polygons indices vectors, as recieved from ConcaveHull */ + std::vector polygons_; + /** \brief The minimum number of points needed on the convex hull. */ int min_pts_hull_{3}; diff --git a/segmentation/include/pcl/segmentation/impl/extract_polygonal_prism_data.hpp b/segmentation/include/pcl/segmentation/impl/extract_polygonal_prism_data.hpp index 26392cddcaa..ac3a35fb2fb 100644 --- a/segmentation/include/pcl/segmentation/impl/extract_polygonal_prism_data.hpp +++ b/segmentation/include/pcl/segmentation/impl/extract_polygonal_prism_data.hpp @@ -227,6 +227,20 @@ pcl::ExtractPolygonalPrismData::segment (pcl::PointIndices &output) PointT pt_xy; pt_xy.z = 0; + std::vector> polygons(polygons_.size()); + if (polygons_.empty()) { + polygons.push_back(polygon); + } + else { // incase of concave hull, prepare separate polygons + for (size_t i = 0; i < polygons_.size(); i++) { + const auto& polygon_i = polygons_[i]; + polygons[i].reserve(polygon_i.vertices.size()); + for (const auto& pointIdx : polygon_i.vertices) { + polygons[i].points.push_back(polygon[pointIdx]); + } + } + } + output.indices.resize (indices_->size ()); int l = 0; for (std::size_t i = 0; i < projected_points.size (); ++i) @@ -243,8 +257,14 @@ pcl::ExtractPolygonalPrismData::segment (pcl::PointIndices &output) pt_xy.x = pt[k1]; pt_xy.y = pt[k2]; - if (!pcl::isXYPointIn2DXYPolygon (pt_xy, polygon)) + bool in_poly = false; + for (const auto& poly : polygons) { + in_poly ^= pcl::isXYPointIn2DXYPolygon(pt_xy, poly); + } + + if (!in_poly) { continue; + } output.indices[l++] = (*indices_)[i]; } diff --git a/test/segmentation/CMakeLists.txt b/test/segmentation/CMakeLists.txt index ae83d990e1e..3445468e187 100644 --- a/test/segmentation/CMakeLists.txt +++ b/test/segmentation/CMakeLists.txt @@ -20,6 +20,10 @@ PCL_ADD_TEST(a_segmentation_test test_segmentation LINK_WITH pcl_gtest pcl_io pcl_segmentation pcl_features pcl_kdtree pcl_search pcl_common ARGUMENTS "${PCL_SOURCE_DIR}/test/bun0.pcd" "${PCL_SOURCE_DIR}/test/car6.pcd" "${PCL_SOURCE_DIR}/test/colored_cloud.pcd") +PCL_ADD_TEST(a_prism_test test_concave_prism + FILES test_concave_prism.cpp + LINK_WITH pcl_gtest pcl_segmentation pcl_common) + PCL_ADD_TEST(test_non_linear test_non_linear FILES test_non_linear.cpp LINK_WITH pcl_gtest pcl_common pcl_io pcl_sample_consensus pcl_segmentation pcl_kdtree pcl_search diff --git a/test/segmentation/test_concave_prism.cpp b/test/segmentation/test_concave_prism.cpp new file mode 100644 index 00000000000..10ab8943614 --- /dev/null +++ b/test/segmentation/test_concave_prism.cpp @@ -0,0 +1,92 @@ +#include +#include +#include + +#include + +#include + +using namespace pcl; +using std::vector; + +TEST(ExtractPolygonalPrism, two_rings) +{ + float rMin = 0.1, rMax = 0.25f; + float dx = 0.5f; // shift the rings from [0,0,0] to [+/-dx, 0, 0] + + // prepare 2 rings + PointCloud::Ptr ring(new PointCloud); + { // use random + std::random_device rd; + std::mt19937 gen(rd()); + std::uniform_real_distribution radiusDist(rMin, rMax); + std::uniform_real_distribution radianDist(-M_PI, M_PI); + std::uniform_real_distribution zDist(-0.01f, 0.01f); + for (size_t i = 0; i < 1000; i++) { + float radius = radiusDist(gen); + float angle = radianDist(gen); + float z = zDist(gen); + PointXYZ point(cosf(angle) * radius, sinf(angle) * radius, z); + ring->push_back(point); + } + } + + PointCloud::Ptr cloud(new PointCloud); + cloud->reserve(ring->size() * 2); + for (auto& point : ring->points) { + auto left = point; + auto right = point; + left.x -= dx; + right.x += dx; + cloud->push_back(left); + cloud->push_back(right); + } + + // create hull + PointCloud::Ptr hullCloud(new PointCloud); + vector rings(4); + float radiuses[] = {rMin - 0.01f, rMax + 0.01f, rMin - 0.01f, rMax + 0.01f}; + float centers[] = {-dx, -dx, +dx, +dx}; + for (size_t i = 0; i < rings.size(); i++) { + auto r = radiuses[i]; + auto xCenter = centers[i]; + for (float a = -M_PI; a < M_PI; a += 0.05f) { + rings[i].vertices.push_back(hullCloud->size()); + PointXYZ point(xCenter + r * cosf(a), r * sinf(a), 0); + hullCloud->push_back(point); + } + } + + // add more points before using prism + size_t ringsPointCount = cloud->size(); + cloud->push_back(PointXYZ(0, 0, 0)); + for (float a = -M_PI; a < M_PI; a += 0.05f) { + float r = 4 * rMax; + PointXYZ point(r * cosf(a), r * sinf(a), 0); + cloud->push_back(point); + } + + // do prism + PointIndices::Ptr inliers(new PointIndices); + ExtractPolygonalPrismData ex; + { + ex.setInputCloud(cloud); + ex.setInputPlanarHull(hullCloud); + ex.setHeightLimits(-1, 1); + ex.setPolygons(rings); + ex.segment(*inliers); + } + + // check that all of the rings are in the prism. + EXPECT_EQ(inliers->indices.size(), ringsPointCount); + for(std::size_t i=0; iindices.size(); ++i) { + EXPECT_EQ(inliers->indices[i], i); + } +} + +int +main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return (RUN_ALL_TESTS()); +} From eb9c003fca3b7ecc667371cb8a5a47897210cb05 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E4=B8=83=E5=B0=8F=E4=B8=98=E4=BA=BA?= Date: Wed, 5 Jun 2024 19:02:38 +0800 Subject: [PATCH 264/288] Fix get fitness score ignore invalid points (#6056) * make method getFitnessScore ignore invalid points * mofify cmakelist.txt * remove registration example * redo cmakelist.txt --- examples/CMakeLists.txt | 1 - registration/include/pcl/registration/impl/registration.hpp | 4 +++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index af231303c58..54f7c1f8d8a 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -38,4 +38,3 @@ else() endif() add_custom_target(${SUBSYS_TARGET_NAME} DEPENDS ${PCL_EXAMPLES_ALL_TARGETS}) set_target_properties(${SUBSYS_TARGET_NAME} PROPERTIES FOLDER "Examples") - diff --git a/registration/include/pcl/registration/impl/registration.hpp b/registration/include/pcl/registration/impl/registration.hpp index 24a454efabd..db0faef597f 100644 --- a/registration/include/pcl/registration/impl/registration.hpp +++ b/registration/include/pcl/registration/impl/registration.hpp @@ -145,6 +145,8 @@ Registration::getFitnessScore(double max_range // For each point in the source dataset int nr = 0; for (const auto& point : input_transformed) { + if (!input_->is_dense && !pcl::isXYZFinite(point)) + continue; // Find its nearest neighbor in the target tree_->nearestKSearch(point, 1, nn_indices, nn_dists); @@ -214,4 +216,4 @@ Registration::align(PointCloudSource& output, deinitCompute(); } -} // namespace pcl +} // namespace pcl \ No newline at end of file From 5e874e903663204578fa0ace9885a544e92f13e0 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 8 Jun 2024 15:26:41 +0200 Subject: [PATCH 265/288] Give users more control regarding with which point types classes are instantiated Previously, users could only choose between all types, some types ("core types" although it is not transparent which types these are), and no types (`PCL_NO_PRECOMPILE`). `PCL_XYZ_POINT_TYPES` and `PCL_NORMAL_POINT_TYPES` are now configurable via CMake (these only take effect if `PCL_ONLY_CORE_POINT_TYPES` and `PCL_NO_PRECOMPILE` are OFF). This enables users on all platforms and compilers to reduce PCL compile times and library size. Additionally, for users of MSVC or MINGW, `PCL_ONLY_CORE_POINT_TYPES` is now ON by default and not statically added to the definitions in CMakeLists.txt. I believe this is behaviour is more transparent, and these users now have the option to set `PCL_ONLY_CORE_POINT_TYPES` to OFF and choose the instantiated types via `PCL_XYZ_POINT_TYPES` and `PCL_NORMAL_POINT_TYPES` instead. However one of these two ways to reduce the set of instantiations must be used on Windows to avoid the linker error `fatal error LNK1189: library limit of 65535 objects exceeded` when trying to link the features library. --- CMakeLists.txt | 6 +---- cmake/pcl_options.cmake | 10 ++++++++ common/include/pcl/impl/point_types.hpp | 31 +------------------------ pcl_config.h.in | 4 ++++ 4 files changed, 16 insertions(+), 35 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1741d73e20e..c898f02886d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -144,7 +144,7 @@ if(CMAKE_COMPILER_IS_GNUCXX) endif() if(CMAKE_COMPILER_IS_MSVC) - add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX -DPCL_ONLY_CORE_POINT_TYPES ${SSE_DEFINITIONS}") + add_definitions("-DBOOST_ALL_NO_LIB -D_SCL_SECURE_NO_WARNINGS -D_CRT_SECURE_NO_WARNINGS -DNOMINMAX ${SSE_DEFINITIONS}") if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") string(APPEND CMAKE_CXX_FLAGS " /fp:precise ${SSE_FLAGS} ${AVX_FLAGS}") @@ -232,10 +232,6 @@ if(CMAKE_COMPILER_IS_CLANG) set(CLANG_LIBRARIES "stdc++") endif() -if(CMAKE_COMPILER_IS_MINGW) - add_definitions(-DPCL_ONLY_CORE_POINT_TYPES) -endif() - include("${PCL_SOURCE_DIR}/cmake/pcl_utils.cmake") DISSECT_VERSION() GET_OS_INFO() diff --git a/cmake/pcl_options.cmake b/cmake/pcl_options.cmake index 1911fdf8a82..6fa8fdd359f 100644 --- a/cmake/pcl_options.cmake +++ b/cmake/pcl_options.cmake @@ -48,8 +48,18 @@ mark_as_advanced(PCL_QHULL_REQUIRED_TYPE) option(PCL_PREFER_BOOST_FILESYSTEM "Prefer boost::filesystem over std::filesystem (if compiled as C++17 or higher, std::filesystem is chosen by default)" OFF) mark_as_advanced(PCL_PREFER_BOOST_FILESYSTEM) +set(PCL_XYZ_POINT_TYPES "(pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZL)(pcl::PointXYZRGBA)(pcl::PointXYZRGB)(pcl::PointXYZRGBL)(pcl::PointXYZLAB)(pcl::PointXYZHSV)(pcl::InterestPoint)(pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal)(pcl::PointWithRange)(pcl::PointWithViewpoint)(pcl::PointWithScale)(pcl::PointSurfel)(pcl::PointDEM)" CACHE STRING "Point types with xyz information for which PCL classes will be instantiated. Alternative to PCL_ONLY_CORE_POINT_TYPES. You can remove unneeded types to reduce compile time and library size.") +mark_as_advanced(PCL_XYZ_POINT_TYPES) + +set(PCL_NORMAL_POINT_TYPES "(pcl::Normal)(pcl::PointNormal)(pcl::PointXYZRGBNormal)(pcl::PointXYZINormal)(pcl::PointXYZLNormal)(pcl::PointSurfel)" CACHE STRING "Point types with normal information for which PCL classes will be instantiated. Alternative to PCL_ONLY_CORE_POINT_TYPES. You can remove unneeded types to reduce compile time and library size.") +mark_as_advanced(PCL_NORMAL_POINT_TYPES) + # Precompile for a minimal set of point types instead of all. +if(CMAKE_COMPILER_IS_MSVC OR CMAKE_COMPILER_IS_MINGW) +option(PCL_ONLY_CORE_POINT_TYPES "Compile explicitly only for a small subset of point types (e.g., pcl::PointXYZ instead of PCL_XYZ_POINT_TYPES)." ON) +else() option(PCL_ONLY_CORE_POINT_TYPES "Compile explicitly only for a small subset of point types (e.g., pcl::PointXYZ instead of PCL_XYZ_POINT_TYPES)." OFF) +endif() mark_as_advanced(PCL_ONLY_CORE_POINT_TYPES) # Precompile for a minimal set of point types instead of all. diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 076385267d6..88ca63a4d1a 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -39,6 +39,7 @@ #pragma once #include // for PCL_MAKE_ALIGNED_OPERATOR_NEW +#include // for PCL_XYZ_POINT_TYPES, PCL_NORMAL_POINT_TYPES #include // for PCL_EXPORTS #include // for PCLPointField #include // implementee @@ -118,42 +119,12 @@ (pcl::PointXYZRGBNormal) \ (pcl::PointSurfel) \ -// Define all point types that include XYZ data -#define PCL_XYZ_POINT_TYPES \ - (pcl::PointXYZ) \ - (pcl::PointXYZI) \ - (pcl::PointXYZL) \ - (pcl::PointXYZRGBA) \ - (pcl::PointXYZRGB) \ - (pcl::PointXYZRGBL) \ - (pcl::PointXYZLAB) \ - (pcl::PointXYZHSV) \ - (pcl::InterestPoint) \ - (pcl::PointNormal) \ - (pcl::PointXYZRGBNormal) \ - (pcl::PointXYZINormal) \ - (pcl::PointXYZLNormal) \ - (pcl::PointWithRange) \ - (pcl::PointWithViewpoint) \ - (pcl::PointWithScale) \ - (pcl::PointSurfel) \ - (pcl::PointDEM) - // Define all point types with XYZ and label #define PCL_XYZL_POINT_TYPES \ (pcl::PointXYZL) \ (pcl::PointXYZRGBL) \ (pcl::PointXYZLNormal) -// Define all point types that include normal[3] data -#define PCL_NORMAL_POINT_TYPES \ - (pcl::Normal) \ - (pcl::PointNormal) \ - (pcl::PointXYZRGBNormal) \ - (pcl::PointXYZINormal) \ - (pcl::PointXYZLNormal) \ - (pcl::PointSurfel) - // Define all point types that represent features #define PCL_FEATURE_POINT_TYPES \ (pcl::PFHSignature125) \ diff --git a/pcl_config.h.in b/pcl_config.h.in index 1a7f843f49a..3277fa77b05 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -59,6 +59,10 @@ /* Precompile for a minimal set of point types instead of all. */ #cmakedefine PCL_ONLY_CORE_POINT_TYPES +#define PCL_XYZ_POINT_TYPES @PCL_XYZ_POINT_TYPES@ + +#define PCL_NORMAL_POINT_TYPES @PCL_NORMAL_POINT_TYPES@ + /* Do not precompile for any point types at all. */ #cmakedefine PCL_NO_PRECOMPILE From 976836be15b1aca6d0353363993dcf62a61f6040 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E4=B8=83=E5=B0=8F=E4=B8=98=E4=BA=BA?= Date: Tue, 18 Jun 2024 18:45:32 +0800 Subject: [PATCH 266/288] Make UniformSampling inherit from FilterIndices instead of Filter (#6064) * test passed * remove useless part * modify for expression * modify for expression again * back Ptr typedef * add resize * add ::Ptr check * replace std::isfinate with pcl::isXYZFinite --- .../pcl/filters/impl/uniform_sampling.hpp | 55 +++++++-------- .../include/pcl/filters/uniform_sampling.h | 17 +++-- test/filters/test_uniform_sampling.cpp | 70 +++++++++++++++++-- 3 files changed, 99 insertions(+), 43 deletions(-) diff --git a/filters/include/pcl/filters/impl/uniform_sampling.hpp b/filters/include/pcl/filters/impl/uniform_sampling.hpp index d51a6bcee31..c1c0f251de1 100644 --- a/filters/include/pcl/filters/impl/uniform_sampling.hpp +++ b/filters/include/pcl/filters/impl/uniform_sampling.hpp @@ -40,22 +40,17 @@ #include #include +#include ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template void -pcl::UniformSampling::applyFilter (PointCloud &output) +pcl::UniformSampling::applyFilter (Indices &indices) { - // Has the input dataset been set already? - if (!input_) - { - PCL_WARN ("[pcl::%s::applyFilter] No input dataset given!\n", getClassName ().c_str ()); - output.width = output.height = 0; - output.clear (); - return; - } + // The arrays to be used + indices.resize (indices_->size ()); + removed_indices_->resize (indices_->size ()); - output.height = 1; // downsampling breaks the organized structure - output.is_dense = true; // we filter out invalid points + int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator Eigen::Vector4f min_p, max_p; // Get the minimum and maximum dimensions @@ -79,27 +74,24 @@ pcl::UniformSampling::applyFilter (PointCloud &output) // Set up the division multiplier divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); - removed_indices_->clear(); // First pass: build a set of leaves with the point index closest to the leaf center - for (std::size_t cp = 0; cp < indices_->size (); ++cp) + for (const auto& cp : *indices_) { if (!input_->is_dense) { // Check if the point is invalid - if (!std::isfinite ((*input_)[(*indices_)[cp]].x) || - !std::isfinite ((*input_)[(*indices_)[cp]].y) || - !std::isfinite ((*input_)[(*indices_)[cp]].z)) + if (!pcl::isXYZFinite ((*input_)[cp])) { if (extract_removed_indices_) - removed_indices_->push_back ((*indices_)[cp]); + (*removed_indices_)[rii++] = cp; continue; } } Eigen::Vector4i ijk = Eigen::Vector4i::Zero (); - ijk[0] = static_cast (std::floor ((*input_)[(*indices_)[cp]].x * inverse_leaf_size_[0])); - ijk[1] = static_cast (std::floor ((*input_)[(*indices_)[cp]].y * inverse_leaf_size_[1])); - ijk[2] = static_cast (std::floor ((*input_)[(*indices_)[cp]].z * inverse_leaf_size_[2])); + ijk[0] = static_cast (std::floor ((*input_)[cp].x * inverse_leaf_size_[0])); + ijk[1] = static_cast (std::floor ((*input_)[cp].y * inverse_leaf_size_[1])); + ijk[2] = static_cast (std::floor ((*input_)[cp].z * inverse_leaf_size_[2])); // Compute the leaf index int idx = (ijk - min_b_).dot (divb_mul_); @@ -111,7 +103,7 @@ pcl::UniformSampling::applyFilter (PointCloud &output) // First time we initialize the index if (leaf.idx == -1) { - leaf.idx = (*indices_)[cp]; + leaf.idx = cp; continue; } @@ -119,33 +111,36 @@ pcl::UniformSampling::applyFilter (PointCloud &output) Eigen::Vector4f voxel_center = (ijk.cast() + Eigen::Vector4f::Constant(0.5)) * search_radius_; voxel_center[3] = 0; // Check to see if this point is closer to the leaf center than the previous one we saved - float diff_cur = ((*input_)[(*indices_)[cp]].getVector4fMap () - voxel_center).squaredNorm (); + float diff_cur = ((*input_)[cp].getVector4fMap () - voxel_center).squaredNorm (); float diff_prev = ((*input_)[leaf.idx].getVector4fMap () - voxel_center).squaredNorm (); // If current point is closer, copy its index instead if (diff_cur < diff_prev) { if (extract_removed_indices_) - removed_indices_->push_back (leaf.idx); - leaf.idx = (*indices_)[cp]; + (*removed_indices_)[rii++] = leaf.idx; + leaf.idx = cp; } else { if (extract_removed_indices_) - removed_indices_->push_back ((*indices_)[cp]); + (*removed_indices_)[rii++] = cp; } } + removed_indices_->resize(rii); // Second pass: go over all leaves and copy data - output.resize (leaves_.size ()); - std::size_t cp = 0; - + indices.resize (leaves_.size ()); for (const auto& leaf : leaves_) { if (leaf.second.count >= min_points_per_voxel_) - output[cp++] = (*input_)[leaf.second.idx]; + indices[oii++] = leaf.second.idx; + } + + indices.resize (oii); + if(negative_){ + indices.swap(*removed_indices_); } - output.resize (cp); } #define PCL_INSTANTIATE_UniformSampling(T) template class PCL_EXPORTS pcl::UniformSampling; diff --git a/filters/include/pcl/filters/uniform_sampling.h b/filters/include/pcl/filters/uniform_sampling.h index d814adbf265..53b6c26dd24 100644 --- a/filters/include/pcl/filters/uniform_sampling.h +++ b/filters/include/pcl/filters/uniform_sampling.h @@ -39,7 +39,7 @@ #pragma once -#include +#include #include @@ -57,9 +57,11 @@ namespace pcl * \ingroup filters */ template - class UniformSampling: public Filter + class UniformSampling: public FilterIndices { - using PointCloud = typename Filter::PointCloud; + using PointCloud = typename FilterIndices::PointCloud; + + using FilterIndices::negative_; using Filter::filter_name_; using Filter::input_; @@ -76,7 +78,7 @@ namespace pcl /** \brief Empty constructor. */ UniformSampling (bool extract_removed_indices = false) : - Filter(extract_removed_indices), + FilterIndices(extract_removed_indices), leaves_ (), leaf_size_ (Eigen::Vector4f::Zero ()), inverse_leaf_size_ (Eigen::Vector4f::Zero ()), @@ -120,6 +122,7 @@ namespace pcl inline unsigned int getMinimumPointsNumberPerVoxel () const { return min_points_per_voxel_; } + protected: /** \brief Simple structure to hold an nD centroid and the number of points in a leaf. */ struct Leaf @@ -147,11 +150,11 @@ namespace pcl /** \brief Minimum number of points per voxel. */ unsigned int min_points_per_voxel_{0}; - /** \brief Downsample a Point Cloud using a voxelized grid approach - * \param[out] output the resultant point cloud message + /** \brief Filtered results are indexed by an indices array. + * \param[out] indices The resultant indices. */ void - applyFilter (PointCloud &output) override; + applyFilter (Indices &indices) override; }; } diff --git a/test/filters/test_uniform_sampling.cpp b/test/filters/test_uniform_sampling.cpp index 50a3446c036..7403a1d49cd 100644 --- a/test/filters/test_uniform_sampling.cpp +++ b/test/filters/test_uniform_sampling.cpp @@ -61,17 +61,75 @@ TEST(UniformSampling, extractRemovedIndices) // sure that each cell has at least one point. As a result, we expect 1000 points in // the output cloud and the rest in removed indices. - pcl::UniformSampling us(true); // extract removed indices - us.setInputCloud(xyz); - us.setRadiusSearch(0.1); + pcl::UniformSampling::Ptr us_ptr(new pcl::UniformSampling(true));// extract removed indices + us_ptr->setRadiusSearch(0.1); pcl::PointCloud output; - us.filter(output); + pcl::Indices indices; + + // Empty input cloud + us_ptr->filter(output); + us_ptr->filter(indices); - auto removed_indices = us.getRemovedIndices(); + us_ptr->setInputCloud(xyz); + // Cloud + us_ptr->filter(output); + // Indices + us_ptr->filter(indices); + + for (const auto& outputIndex : indices) + { + // Check if the point exists in the output cloud + bool found = false; + for (const auto& j : output) + { + if (j.x == (*xyz)[outputIndex].x && + j.y == (*xyz)[outputIndex].y && + j.z == (*xyz)[outputIndex].z) + { + found = true; + break; + } + } + + // Assert that the point was found in the output cloud + ASSERT_TRUE(found); + } + + auto removed_indices = us_ptr->getRemovedIndices(); ASSERT_EQ(output.size(), 1000); - EXPECT_EQ(removed_indices->size(), xyz->size() - 1000); + EXPECT_EQ(int(removed_indices->size()), int(xyz->size() - 1000)); std::set removed_indices_set(removed_indices->begin(), removed_indices->end()); ASSERT_EQ(removed_indices_set.size(), removed_indices->size()); + + // Negative + us_ptr->setNegative (true); + us_ptr->filter(output); + removed_indices = us_ptr->getRemovedIndices (); + EXPECT_EQ (int (removed_indices->size ()), 1000); + EXPECT_EQ (int (output.size ()), int (xyz->size() - 1000)); + + // Organized + us_ptr->setKeepOrganized (true); + us_ptr->setNegative (false); + us_ptr->filter(output); + removed_indices = us_ptr->getRemovedIndices (); + EXPECT_EQ (int (removed_indices->size ()), int(xyz->size() - 1000)); + for (std::size_t i = 0; i < removed_indices->size (); ++i) + { + EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).x)); + EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).y)); + EXPECT_TRUE (std::isnan (output.at ((*removed_indices)[i]).z)); + } + + EXPECT_EQ (output.width, xyz->width); + EXPECT_EQ (output.height, xyz->height); + + // Check input cloud with nan values + us_ptr->setInputCloud (output.makeShared ()); + us_ptr->setRadiusSearch(2); + us_ptr->filter (output); + removed_indices = us_ptr->getRemovedIndices (); + EXPECT_EQ (int (removed_indices->size ()), output.size()-1); } int From d5c1a9757c194a33f2b04b9f201d4b7e80ec53b6 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 22 Jun 2024 20:01:13 +0200 Subject: [PATCH 267/288] Preparation for hidden visibility on gcc In voxel_grid_label.cpp, the implementation of `VoxelGrid` (from voxel_grid.hpp) must not be available, otherwise `VoxelGrid` is instantiated again, but with the wrong visibility attributes (would overwrite the correct instantiation from `voxel_grid.cpp`). Same thing in sac_model_normal_plane.hpp: the implementation of `SampleConsensusModelPlane` must not be available. The implementations of `dist8` and `dist4` are moved from sac_model_plane.hpp to sac_model_plane.h so that they are available when `SampleConsensusModelNormalPlane` is instantiated and the compiler can optimize. --- common/include/pcl/common/intersections.h | 4 +-- .../include/pcl/filters/impl/voxel_grid.hpp | 14 ++------ filters/include/pcl/filters/voxel_grid.h | 15 +++++++++ filters/src/voxel_grid.cpp | 4 +-- filters/src/voxel_grid_label.cpp | 5 +-- .../transformation_estimation_svd.h | 2 +- .../impl/sac_model_normal_plane.hpp | 1 - .../sample_consensus/impl/sac_model_plane.hpp | 30 ----------------- .../pcl/sample_consensus/sac_model_plane.h | 32 ++++++++++++++++--- .../nearest_pair_point_cloud_coherence.h | 3 +- .../common/ren_win_interact_map.h | 4 ++- 11 files changed, 57 insertions(+), 57 deletions(-) diff --git a/common/include/pcl/common/intersections.h b/common/include/pcl/common/intersections.h index ff227ab4382..81b578e57f6 100644 --- a/common/include/pcl/common/intersections.h +++ b/common/include/pcl/common/intersections.h @@ -86,7 +86,7 @@ namespace pcl * \param[in] angular_tolerance tolerance in radians * \return true if succeeded/planes aren't parallel */ - PCL_EXPORTS template bool + template PCL_EXPORTS bool planeWithPlaneIntersection (const Eigen::Matrix &plane_a, const Eigen::Matrix &plane_b, Eigen::Matrix &line, @@ -121,7 +121,7 @@ namespace pcl * \param[out] intersection_point the three coordinates x, y, z of the intersection point * \return true if succeeded/planes aren't parallel */ - PCL_EXPORTS template bool + template PCL_EXPORTS bool threePlanesIntersection (const Eigen::Matrix &plane_a, const Eigen::Matrix &plane_b, const Eigen::Matrix &plane_c, diff --git a/filters/include/pcl/filters/impl/voxel_grid.hpp b/filters/include/pcl/filters/impl/voxel_grid.hpp index 66de0a08100..5297a49dc2a 100644 --- a/filters/include/pcl/filters/impl/voxel_grid.hpp +++ b/filters/include/pcl/filters/impl/voxel_grid.hpp @@ -211,16 +211,6 @@ pcl::getMinMax3D (const typename pcl::PointCloud::ConstPtr &cloud, max_pt = max_p; } -struct cloud_point_index_idx -{ - unsigned int idx; - unsigned int cloud_point_index; - - cloud_point_index_idx() = default; - cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {} - bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); } -}; - ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// template void pcl::VoxelGrid::applyFilter (PointCloud &output) @@ -273,7 +263,7 @@ pcl::VoxelGrid::applyFilter (PointCloud &output) divb_mul_ = Eigen::Vector4i (1, div_b_[0], div_b_[0] * div_b_[1], 0); // Storage for mapping leaf and pointcloud indexes - std::vector index_vector; + std::vector index_vector; index_vector.reserve (indices_->size ()); // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... @@ -350,7 +340,7 @@ pcl::VoxelGrid::applyFilter (PointCloud &output) // Second pass: sort the index_vector vector using value representing target cell as index // in effect all points belonging to the same output cell will be next to each other - auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; }; + auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; }; boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func); // Third pass: count output cells diff --git a/filters/include/pcl/filters/voxel_grid.h b/filters/include/pcl/filters/voxel_grid.h index 9ecce2bb285..00bdcf50c42 100644 --- a/filters/include/pcl/filters/voxel_grid.h +++ b/filters/include/pcl/filters/voxel_grid.h @@ -866,6 +866,21 @@ namespace pcl void applyFilter (PCLPointCloud2 &output) override; }; + + namespace internal + { + /** \brief Used internally in voxel grid classes. + */ + struct cloud_point_index_idx + { + unsigned int idx; + unsigned int cloud_point_index; + + cloud_point_index_idx() = default; + cloud_point_index_idx (unsigned int idx_, unsigned int cloud_point_index_) : idx (idx_), cloud_point_index (cloud_point_index_) {} + bool operator < (const cloud_point_index_idx &p) const { return (idx < p.idx); } + }; + } } #ifdef PCL_NO_PRECOMPILE diff --git a/filters/src/voxel_grid.cpp b/filters/src/voxel_grid.cpp index de56caa46a9..7c83f277807 100644 --- a/filters/src/voxel_grid.cpp +++ b/filters/src/voxel_grid.cpp @@ -420,7 +420,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) div_b_ = max_b_ - min_b_ + Eigen::Vector4i::Ones (); div_b_[3] = 0; - std::vector index_vector; + std::vector index_vector; index_vector.reserve (indices_->size()); // Create the first xyz_offset, and set up the division multiplier @@ -545,7 +545,7 @@ pcl::VoxelGrid::applyFilter (PCLPointCloud2 &output) // Second pass: sort the index_vector vector using value representing target cell as index // in effect all points belonging to the same output cell will be next to each other - auto rightshift_func = [](const cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; }; + auto rightshift_func = [](const internal::cloud_point_index_idx &x, const unsigned offset) { return x.idx >> offset; }; boost::sort::spreadsort::integer_sort(index_vector.begin(), index_vector.end(), rightshift_func); // Third pass: count output cells diff --git a/filters/src/voxel_grid_label.cpp b/filters/src/voxel_grid_label.cpp index 13dd7cdfdb4..1d7e9ab96ad 100644 --- a/filters/src/voxel_grid_label.cpp +++ b/filters/src/voxel_grid_label.cpp @@ -37,8 +37,9 @@ */ #include +#include // for getMinMax3D #include -#include +#include // for boost::mpl::size ////////////////////////////////////////////////////////////////////////////// void @@ -111,7 +112,7 @@ pcl::VoxelGridLabel::applyFilter (PointCloud &output) int label_index = -1; label_index = pcl::getFieldIndex ("label", fields); - std::vector index_vector; + std::vector index_vector; index_vector.reserve(input_->size()); // If we don't want to process the entire cloud, but rather filter points far away from the viewpoint first... diff --git a/registration/include/pcl/registration/transformation_estimation_svd.h b/registration/include/pcl/registration/transformation_estimation_svd.h index f9c56ea59a2..60c960788bd 100644 --- a/registration/include/pcl/registration/transformation_estimation_svd.h +++ b/registration/include/pcl/registration/transformation_estimation_svd.h @@ -55,7 +55,7 @@ namespace registration { * \ingroup registration */ template -class TransformationEstimationSVD +class PCL_EXPORTS TransformationEstimationSVD : public TransformationEstimation { public: using Ptr = shared_ptr>; diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp index 0cd94ff80ee..dc96852c247 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_normal_plane.hpp @@ -42,7 +42,6 @@ #define PCL_SAMPLE_CONSENSUS_IMPL_SAC_MODEL_NORMAL_PLANE_H_ #include -#include // for dist4, dist8 #include // for getAngle3D ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp index a9a6800bbd8..be51ff89bae 100644 --- a/sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp +++ b/sample_consensus/include/pcl/sample_consensus/impl/sac_model_plane.hpp @@ -117,36 +117,6 @@ pcl::SampleConsensusModelPlane::computeModelCoefficients ( return (true); } -#define AT(POS) ((*input_)[(*indices_)[(POS)]]) - -#ifdef __AVX__ -// This function computes the distances of 8 points to the plane -template inline __m256 pcl::SampleConsensusModelPlane::dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const -{ - // The andnot-function realizes an abs-operation: the sign bit is removed - return _mm256_andnot_ps (abs_help, - _mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (AT(i ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x, AT(i+4).x, AT(i+5).x, AT(i+6).x, AT(i+7).x)), - _mm256_mul_ps (b_vec, _mm256_set_ps (AT(i ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y, AT(i+4).y, AT(i+5).y, AT(i+6).y, AT(i+7).y))), - _mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (AT(i ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z, AT(i+4).z, AT(i+5).z, AT(i+6).z, AT(i+7).z)), - d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal -} -#endif // ifdef __AVX__ - -#ifdef __SSE__ -// This function computes the distances of 4 points to the plane -template inline __m128 pcl::SampleConsensusModelPlane::dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const -{ - // The andnot-function realizes an abs-operation: the sign bit is removed - return _mm_andnot_ps (abs_help, - _mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (AT(i ).x, AT(i+1).x, AT(i+2).x, AT(i+3).x)), - _mm_mul_ps (b_vec, _mm_set_ps (AT(i ).y, AT(i+1).y, AT(i+2).y, AT(i+3).y))), - _mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (AT(i ).z, AT(i+1).z, AT(i+2).z, AT(i+3).z)), - d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal -} -#endif // ifdef __SSE__ - -#undef AT - ////////////////////////////////////////////////////////////////////////// template void pcl::SampleConsensusModelPlane::getDistancesToModel ( diff --git a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h index 2bee660a23f..2f81614c9c5 100644 --- a/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h +++ b/sample_consensus/include/pcl/sample_consensus/sac_model_plane.h @@ -139,7 +139,7 @@ namespace pcl * \ingroup sample_consensus */ template - class SampleConsensusModelPlane : public SampleConsensusModel + class PCL_EXPORTS SampleConsensusModelPlane : public SampleConsensusModel { public: using SampleConsensusModel::model_name_; @@ -292,13 +292,35 @@ namespace pcl std::size_t i = 0) const; #endif +#define PCLAT(POS) ((*input_)[(*indices_)[(POS)]]) + #ifdef __AVX__ - inline __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const; -#endif +// This function computes the distances of 8 points to the plane +inline __m256 dist8 (const std::size_t i, const __m256 &a_vec, const __m256 &b_vec, const __m256 &c_vec, const __m256 &d_vec, const __m256 &abs_help) const +{ + // The andnot-function realizes an abs-operation: the sign bit is removed + return _mm256_andnot_ps (abs_help, + _mm256_add_ps (_mm256_add_ps (_mm256_mul_ps (a_vec, _mm256_set_ps (PCLAT(i ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x, PCLAT(i+4).x, PCLAT(i+5).x, PCLAT(i+6).x, PCLAT(i+7).x)), + _mm256_mul_ps (b_vec, _mm256_set_ps (PCLAT(i ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y, PCLAT(i+4).y, PCLAT(i+5).y, PCLAT(i+6).y, PCLAT(i+7).y))), + _mm256_add_ps (_mm256_mul_ps (c_vec, _mm256_set_ps (PCLAT(i ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z, PCLAT(i+4).z, PCLAT(i+5).z, PCLAT(i+6).z, PCLAT(i+7).z)), + d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal +} +#endif // ifdef __AVX__ #ifdef __SSE__ - inline __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const; -#endif +// This function computes the distances of 4 points to the plane +inline __m128 dist4 (const std::size_t i, const __m128 &a_vec, const __m128 &b_vec, const __m128 &c_vec, const __m128 &d_vec, const __m128 &abs_help) const +{ + // The andnot-function realizes an abs-operation: the sign bit is removed + return _mm_andnot_ps (abs_help, + _mm_add_ps (_mm_add_ps (_mm_mul_ps (a_vec, _mm_set_ps (PCLAT(i ).x, PCLAT(i+1).x, PCLAT(i+2).x, PCLAT(i+3).x)), + _mm_mul_ps (b_vec, _mm_set_ps (PCLAT(i ).y, PCLAT(i+1).y, PCLAT(i+2).y, PCLAT(i+3).y))), + _mm_add_ps (_mm_mul_ps (c_vec, _mm_set_ps (PCLAT(i ).z, PCLAT(i+1).z, PCLAT(i+2).z, PCLAT(i+3).z)), + d_vec))); // TODO this could be replaced by three fmadd-instructions (if available), but the speed gain would probably be minimal +} +#endif // ifdef __SSE__ + +#undef PCLAT private: /** \brief Check if a sample of indices results in a good sample of points diff --git a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h index f7d6eda2a2b..e096baaab60 100644 --- a/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h +++ b/tracking/include/pcl/tracking/nearest_pair_point_cloud_coherence.h @@ -11,7 +11,8 @@ namespace tracking { * \ingroup tracking */ template -class NearestPairPointCloudCoherence : public PointCloudCoherence { +class PCL_EXPORTS NearestPairPointCloudCoherence +: public PointCloudCoherence { public: using PointCloudCoherence::getClassName; using PointCloudCoherence::coherence_name_; diff --git a/visualization/include/pcl/visualization/common/ren_win_interact_map.h b/visualization/include/pcl/visualization/common/ren_win_interact_map.h index 1841f13a28f..31810c5fd83 100644 --- a/visualization/include/pcl/visualization/common/ren_win_interact_map.h +++ b/visualization/include/pcl/visualization/common/ren_win_interact_map.h @@ -38,6 +38,8 @@ #pragma once +#include + #include #include @@ -53,7 +55,7 @@ namespace pcl { namespace visualization { - class RenWinInteract + class PCL_EXPORTS RenWinInteract { public: From 3c550ae7fe10258dfce5921517940f58b6223bae Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Fri, 5 Jul 2024 13:46:38 +0200 Subject: [PATCH 268/288] Fixes and improvements for FPCS and KFPCS (#6073) * Fixes and improvements for FPCS and KFPCS - Replace bad random sampling: previously, the random sampling was not guaranteed to give the user-specified number of samples, was not guaranteed to choose all points with the same probability, and might choose a point more than once. The new approach works similar to the RandomSample class - Number of threads can now be set to 0 to use automatic setting - linkMatchWithBase is not used any more. It has a bug that some indices are duplicated and others dropped. It is not necessary to use it any way because match and base_indices are already correctly ordered - ids and dists_sqr are now created with the correct size (no resize necessary later) - Add debug prints, improve documentation - fpcs and kfpcs tests: set fine tuned score threshold, early termination if a good solution is found. - kfpcs test: set higher maximum number of iterations (was previously automatically estimated as 19). This should fix the random (rare) failures on Azure pipelines * Fix for early termination in KFPCS * Use RandomSample, deprecate linkMatchWithBase --- .../include/pcl/registration/ia_fpcs.h | 1 + .../include/pcl/registration/ia_kfpcs.h | 16 +++- .../include/pcl/registration/impl/ia_fpcs.hpp | 85 +++++++++++++++---- .../pcl/registration/impl/ia_kfpcs.hpp | 48 ++++++++--- test/registration/test_fpcs_ia.cpp | 9 +- test/registration/test_fpcs_ia_data.h | 2 +- test/registration/test_kfpcs_ia.cpp | 15 ++-- test/registration/test_kfpcs_ia_data.h | 2 +- 8 files changed, 134 insertions(+), 44 deletions(-) diff --git a/registration/include/pcl/registration/ia_fpcs.h b/registration/include/pcl/registration/ia_fpcs.h index cb371b3e12b..afb9f252805 100644 --- a/registration/include/pcl/registration/ia_fpcs.h +++ b/registration/include/pcl/registration/ia_fpcs.h @@ -415,6 +415,7 @@ class FPCSInitialAlignment : public Registration + *
    • KFPCSInitialAlignment stores all solution candidates instead of only the best + * one + *
    • KFPCSInitialAlignment uses an MSAC approach to score candidates instead of + * counting inliers + * + * \author P.W.Theiler + * \ingroup registration */ template ::fitness_score_; using FPCSInitialAlignment:: score_threshold_; - using FPCSInitialAlignment:: - linkMatchWithBase; using FPCSInitialAlignment::validateMatch; /** \brief Internal computation initialization. */ diff --git a/registration/include/pcl/registration/impl/ia_fpcs.hpp b/registration/include/pcl/registration/impl/ia_fpcs.hpp index b3445f22d64..7de32edca78 100644 --- a/registration/include/pcl/registration/impl/ia_fpcs.hpp +++ b/registration/include/pcl/registration/impl/ia_fpcs.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -189,9 +190,19 @@ pcl::registration::FPCSInitialAlignment max_runtime_); + if (!candidates.empty() && candidates[0].fitness_score < score_threshold_) { + PCL_DEBUG("[%s::computeTransformation] Terminating because fitness score " + "(%g) is below threshold (%g).\n", + reg_name_.c_str(), + candidates[0].fitness_score, + score_threshold_); + abort = true; + } + else if (timer.getTimeSeconds() > max_runtime_) { + PCL_DEBUG("[%s::computeTransformation] Terminating because time exceeded.\n", + reg_name_.c_str()); + abort = true; + } #pragma omp flush(abort) } @@ -238,14 +249,14 @@ pcl::registration::FPCSInitialAlignment(indices_->size()); - const int sample_fraction_src = std::max(1, static_cast(ss / nr_samples_)); - + if (nr_samples_ > 0 && static_cast(nr_samples_) < indices_->size()) { source_indices_ = pcl::IndicesPtr(new pcl::Indices); - for (int i = 0; i < ss; i++) - if (rand() % sample_fraction_src == 0) - source_indices_->push_back((*indices_)[i]); + pcl::RandomSample random_sampling; + random_sampling.setInputCloud(input_); + random_sampling.setIndices(indices_); + random_sampling.setSample(nr_samples_); + random_sampling.setSeed(seed); + random_sampling.filter(*source_indices_); } else source_indices_ = indices_; @@ -274,6 +285,15 @@ pcl::registration::FPCSInitialAlignment( @@ -289,6 +309,9 @@ pcl::registration::FPCSInitialAlignment(min_iterations))); max_iterations_ = static_cast(first_est / (diameter_fraction * approx_overlap_ * 2.f)); + PCL_DEBUG("[%s::initCompute] Estimated max iterations as %i\n", + reg_name_.c_str(), + max_iterations_); } // set further parameter @@ -307,6 +330,14 @@ pcl::registration::FPCSInitialAlignment::max(); @@ -668,6 +699,11 @@ pcl::registration::FPCSInitialAlignment(std::floor((id / 2.f)))].index_query; match_indices[2] = pair.index_match; match_indices[3] = pair.index_query; + if (match_indices[0] == match_indices[2] || + match_indices[0] == match_indices[3] || + match_indices[1] == match_indices[2] || + match_indices[1] == match_indices[3]) + continue; // EDITED: added coarse check of match based on edge length (due to rigid-body ) if (checkBaseMatch(match_indices, dist_base) < 0) @@ -679,7 +715,16 @@ pcl::registration::FPCSInitialAlignment((1.f - fitness_score) * nr_points); float inlier_score_temp = 0; - pcl::Indices ids; - std::vector dists_sqr; + pcl::Indices ids(1); + std::vector dists_sqr(1); auto it = source_transformed.begin(); for (std::size_t i = 0; i < nr_points; it++, i++) { @@ -888,6 +933,12 @@ pcl::registration::FPCSInitialAlignment::initCompute() // generate a subset of indices of size ransac_iterations_ on which to evaluate // candidates on - std::size_t nr_indices = indices_->size(); - if (nr_indices < static_cast(ransac_iterations_)) + if (indices_->size() <= static_cast(ransac_iterations_) || + ransac_iterations_ <= 0) indices_validation_ = indices_; - else - for (int i = 0; i < ransac_iterations_; i++) - indices_validation_->push_back((*indices_)[rand() % nr_indices]); + else { + indices_validation_.reset(new pcl::Indices); + pcl::RandomSample random_sampling; + random_sampling.setInputCloud(input_); + random_sampling.setIndices(indices_); + random_sampling.setSample(ransac_iterations_); + random_sampling.filter(*indices_validation_); + } + PCL_DEBUG("[%s::initCompute] delta_=%g, max_inlier_dist_sqr_=%g, " + "coincidation_limit_=%g, max_edge_diff_=%g, max_pair_diff_=%g\n", + reg_name_.c_str(), + delta_, + max_inlier_dist_sqr_, + coincidation_limit_, + max_edge_diff_, + max_pair_diff_); return (true); } @@ -117,9 +130,10 @@ KFPCSInitialAlignment::handleMatches( std::numeric_limits::max(); // reset to std::numeric_limits::max() // to accept all candidates and not only best - // determine correspondences between base and match according to their distance to - // centroid - linkMatchWithBase(base_indices, match, correspondences_temp); + correspondences_temp.push_back(pcl::Correspondence(match[0], base_indices[0], 0.0)); + correspondences_temp.push_back(pcl::Correspondence(match[1], base_indices[1], 0.0)); + correspondences_temp.push_back(pcl::Correspondence(match[2], base_indices[2], 0.0)); + correspondences_temp.push_back(pcl::Correspondence(match[3], base_indices[3], 0.0)); // check match based on residuals of the corresponding points after transformation if (validateMatch(base_indices, match, correspondences_temp, transformation_temp) < @@ -134,6 +148,16 @@ KFPCSInitialAlignment::handleMatches( candidates.push_back( MatchingCandidate(fitness_score, correspondences_temp, transformation_temp)); } + // make sure that candidate with best fitness score is at the front, for early + // termination check + if (!candidates.empty()) { + auto best_candidate = candidates.begin(); + for (auto iter = candidates.begin(); iter < candidates.end(); ++iter) + if (iter->fitness_score < best_candidate->fitness_score) + best_candidate = iter; + if (best_candidate != candidates.begin()) + std::swap(*best_candidate, *candidates.begin()); + } } template @@ -150,8 +174,8 @@ KFPCSInitialAlignment:: float score_a = 0.f, score_b = 0.f; // residual costs based on mse - pcl::Indices ids; - std::vector dists_sqr; + pcl::Indices ids(1); + std::vector dists_sqr(1); for (const auto& source : source_transformed) { // search for nearest point using kd tree search tree_->nearestKSearch(source, 1, ids, dists_sqr); @@ -220,6 +244,10 @@ KFPCSInitialAlignment::finalCompute( fitness_score_ = candidates_[0].fitness_score; final_transformation_ = candidates_[0].transformation; *correspondences_ = candidates_[0].correspondences; + PCL_DEBUG("[%s::finalCompute] best score is %g, out of %zu candidate solutions.\n", + reg_name_.c_str(), + fitness_score_, + candidates_.size()); // here we define convergence if resulting score is above threshold converged_ = fitness_score_ < score_threshold_; diff --git a/test/registration/test_fpcs_ia.cpp b/test/registration/test_fpcs_ia.cpp index 774f06d4829..18f1d1cb02f 100644 --- a/test/registration/test_fpcs_ia.cpp +++ b/test/registration/test_fpcs_ia.cpp @@ -73,6 +73,7 @@ TEST (PCL, FPCSInitialAlignment) fpcs_ia.setNumberOfThreads (nr_threads); fpcs_ia.setApproxOverlap (approx_overlap); fpcs_ia.setDelta (delta, true); + fpcs_ia.setScoreThreshold (0.025); // if score is below this threshold, fpcs can stop because the solution is very good fpcs_ia.setNumberOfSamples (nr_samples); // align @@ -80,10 +81,10 @@ TEST (PCL, FPCSInitialAlignment) EXPECT_EQ (source_aligned.size (), cloud_source.size ()); // check for correct coarse transformation matrix - //Eigen::Matrix4f transform_res_from_fpcs = fpcs_ia.getFinalTransformation (); - //for (int i = 0; i < 4; ++i) - // for (int j = 0; j < 4; ++j) - // EXPECT_NEAR (transform_res_from_fpcs (i,j), transform_from_fpcs[i][j], 0.5); + Eigen::Matrix4f transform_res_from_fpcs = fpcs_ia.getFinalTransformation (); + for (int i = 0; i < 4; ++i) + for (int j = 0; j < 4; ++j) + EXPECT_NEAR (transform_res_from_fpcs (i,j), transform_from_fpcs[i][j], 0.25); } diff --git a/test/registration/test_fpcs_ia_data.h b/test/registration/test_fpcs_ia_data.h index ec3c8229e49..84236a2dab0 100644 --- a/test/registration/test_fpcs_ia_data.h +++ b/test/registration/test_fpcs_ia_data.h @@ -6,7 +6,7 @@ constexpr float delta = 1.f; constexpr int nr_samples = 100; const float transform_from_fpcs [4][4] = { - { -0.0019f, 0.8266f, -0.5628f, -0.0378f }, + { -0.0019f, 0.8266f, -0.5628f, 0.0378f }, { -0.9999f, -0.0094f, -0.0104f, 0.9997f }, { -0.0139f, 0.5627f, 0.8265f, 0.0521f }, { 0.f, 0.f, 0.f, 1.f } diff --git a/test/registration/test_kfpcs_ia.cpp b/test/registration/test_kfpcs_ia.cpp index ed709afc7b0..4caba0b41a4 100644 --- a/test/registration/test_kfpcs_ia.cpp +++ b/test/registration/test_kfpcs_ia.cpp @@ -49,7 +49,7 @@ using namespace pcl; using namespace pcl::io; using namespace pcl::registration; -PointCloud cloud_source, cloud_target; +PointCloud cloud_source, cloud_target; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// TEST (PCL, KFPCSInitialAlignment) @@ -57,13 +57,13 @@ 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; + PointCloud::Ptr cloud_source_ptr, cloud_target_ptr; cloud_source_ptr = cloud_source.makeShared (); cloud_target_ptr = cloud_target.makeShared (); // initialize k-fpcs - PointCloud cloud_source_aligned; - KFPCSInitialAlignment kfpcs_ia; + PointCloud cloud_source_aligned; + KFPCSInitialAlignment kfpcs_ia; kfpcs_ia.setInputSource (cloud_source_ptr); kfpcs_ia.setInputTarget (cloud_target_ptr); @@ -71,6 +71,7 @@ TEST (PCL, KFPCSInitialAlignment) kfpcs_ia.setApproxOverlap (approx_overlap); kfpcs_ia.setDelta (voxel_size, false); kfpcs_ia.setScoreThreshold (abort_score); + kfpcs_ia.setMaximumIterations (100); // repeat alignment 2 times to increase probability to ~99.99% constexpr float max_angle3d = 0.1745f, max_translation3d = 1.f; @@ -107,19 +108,19 @@ main (int argc, char** argv) { if (argc < 3) { - std::cerr << "No test files given. Please download `bun0.pcd` and `bun4.pcd` pass their path to the test." << std::endl; + std::cerr << "No test files given. Please download `office1_keypoints.pcd` and `office2_keypoints.pcd` pass their path to the test." << std::endl; return (-1); } // Input if (loadPCDFile (argv[1], cloud_source) < 0) { - std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl; + std::cerr << "Failed to read test file. Please download `office1_keypoints.pcd` and pass its path to the test." << std::endl; return (-1); } if (loadPCDFile (argv[2], cloud_target) < 0) { - std::cerr << "Failed to read test file. Please download `bun4.pcd` and pass its path to the test." << std::endl; + std::cerr << "Failed to read test file. Please download `office2_keypoints.pcd` and pass its path to the test." << std::endl; return (-1); } diff --git a/test/registration/test_kfpcs_ia_data.h b/test/registration/test_kfpcs_ia_data.h index 4b7e8905630..349c7721c92 100644 --- a/test/registration/test_kfpcs_ia_data.h +++ b/test/registration/test_kfpcs_ia_data.h @@ -3,7 +3,7 @@ constexpr int nr_threads = 1; constexpr float voxel_size = 0.1f; constexpr float approx_overlap = 0.9f; -constexpr float abort_score = 0.0f; +constexpr float abort_score = 0.4f; const float transformation_office1_office2 [4][4] = { { -0.6946f, -0.7194f, -0.0051f, -3.6352f }, From 11a701c52ae36caef9dc3d87d254c19045f7ad02 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 11 Jul 2024 09:46:39 +0200 Subject: [PATCH 269/288] CI: Install cjson In a future pull request, we can then make PCL use the system cjson instead of the old cjson code in the outofcore module See also https://github.com/PointCloudLibrary/pcl/issues/6080 --- .ci/azure-pipelines/build/macos.yaml | 2 +- .dev/docker/env/Dockerfile | 1 + .dev/docker/windows/Dockerfile | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/build/macos.yaml b/.ci/azure-pipelines/build/macos.yaml index b085dba0552..08d07d45edd 100644 --- a/.ci/azure-pipelines/build/macos.yaml +++ b/.ci/azure-pipelines/build/macos.yaml @@ -3,7 +3,7 @@ steps: # find the commit hash on a quick non-forced update too fetchDepth: 10 - script: | - brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew qt5 libpcap libomp google-benchmark + brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew qt5 libpcap libomp google-benchmark cjson brew install brewsci/science/openni git clone https://github.com/abseil/googletest.git $GOOGLE_TEST_DIR # the official endpoint changed to abseil/googletest cd $GOOGLE_TEST_DIR && git checkout release-1.8.1 diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index 27579269a1f..d1f84fe8f3c 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -34,6 +34,7 @@ RUN apt-get update \ libboost-filesystem-dev \ libboost-iostreams-dev \ libboost-system-dev \ + libcjson-dev \ libflann-dev \ libglew-dev \ libgtest-dev \ diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index 04aa5daf816..b8c5d0c64cc 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -47,6 +47,6 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm RUN cd .\vcpkg; ` .\bootstrap-vcpkg.bat; ` - .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 ` + .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 cjson ` --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; From 56adae4442915c9295e5cf6fd11af971b89fdd9b Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 11 Jul 2024 18:23:25 +0200 Subject: [PATCH 270/288] Make test_timestamp pass in all timezones Fixes https://github.com/PointCloudLibrary/pcl/issues/6074 --- test/io/test_timestamp.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/test/io/test_timestamp.cpp b/test/io/test_timestamp.cpp index a9f318217f7..a4858681baf 100644 --- a/test/io/test_timestamp.cpp +++ b/test/io/test_timestamp.cpp @@ -18,7 +18,7 @@ TEST(PCL, TestTimestampGeneratorZeroFraction) const auto timestamp = pcl::getTimestamp(time); - EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000"); + EXPECT_EQ(timestamp.size(), 15); } TEST(PCL, TestTimestampGeneratorWithFraction) @@ -28,7 +28,8 @@ TEST(PCL, TestTimestampGeneratorWithFraction) const auto timestamp = pcl::getTimestamp(dt); - EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.123456"); + ASSERT_EQ(timestamp.size(), 22); + EXPECT_EQ(timestamp.substr(15), ".123456"); } TEST(PCL, TestTimestampGeneratorWithSmallFraction) @@ -38,7 +39,8 @@ TEST(PCL, TestTimestampGeneratorWithSmallFraction) const auto timestamp = pcl::getTimestamp(dt); - EXPECT_EQ(timestamp, "19700101T" + getTimeOffset() + "0000.000123"); + ASSERT_EQ(timestamp.size(), 22); + EXPECT_EQ(timestamp.substr(15), ".000123"); } TEST(PCL, TestParseTimestamp) From c21e2dd6c3897309d61ccd03cd9238bfc1e6e285 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E5=AD=99=E6=96=87?= Date: Thu, 18 Jul 2024 15:24:32 +0800 Subject: [PATCH 271/288] lib not found when install with relwithdebinfo --- PCLConfig.cmake.in | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index 98f9bcef95c..a650af86fd7 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -435,6 +435,8 @@ set(PCL_INCLUDE_DIRS "${PCL_CONF_INCLUDE_DIR}") #set a suffix for debug libraries set(PCL_DEBUG_SUFFIX "@CMAKE_DEBUG_POSTFIX@") set(PCL_RELEASE_SUFFIX "@CMAKE_RELEASE_POSTFIX@") +set(PCL_RELWITHDEBINFO_SUFFIX "@CMAKE_RELWITHDEBINFO_POSTFIX@") +set(PCL_MINSIZEREL_SUFFIX "@CMAKE_MINSIZEREL_POSTFIX@") set(PCL_SHARED_LIBS "@PCL_SHARED_LIBS@") @@ -539,7 +541,8 @@ foreach(component ${PCL_TO_FIND_COMPONENTS}) # Skip find_library for header only modules list(FIND pcl_header_only_components ${component} _is_header_only) if(_is_header_only EQUAL -1) - find_library(PCL_${COMPONENT}_LIBRARY ${pcl_component}${PCL_RELEASE_SUFFIX} + find_library(PCL_${COMPONENT}_LIBRARY + NAMES ${pcl_component}${PCL_RELEASE_SUFFIX} ${pcl_component}${PCL_RELWITHDEBINFO_SUFFIX} ${pcl_component}${PCL_MINSIZEREL_SUFFIX} HINTS ${PCL_LIBRARY_DIRS} DOC "path to ${pcl_component} library" NO_DEFAULT_PATH) From f48626aeb880fc0f2ee277763da58fd6799a2583 Mon Sep 17 00:00:00 2001 From: "bin.sun" Date: Fri, 19 Jul 2024 20:00:02 +0800 Subject: [PATCH 272/288] fix optimizeModelCoefficients use a uninitialized var when do optimization (#6088) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * bugfix: fix SampleConsensusModelCircle3D:optimizeModelCoefficients used a uninitialized variable * add cylinder axis after minimization --------- Co-authored-by: 孙文 --- .../include/pcl/sample_consensus/impl/sac_model_circle3d.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) 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 0ce6ce69247..f5e691ee2ca 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 @@ -301,8 +301,9 @@ pcl::SampleConsensusModelCircle3D::optimizeModelCoefficients ( OptimizationFunctor functor (this, inliers); Eigen::NumericalDiff num_diff (functor); Eigen::LevenbergMarquardt, double> lm (num_diff); - Eigen::VectorXd coeff; + Eigen::VectorXd coeff = optimized_coefficients.cast(); int info = lm.minimize (coeff); + coeff.tail(3).normalize(); // normalize the cylinder axis for (Eigen::Index i = 0; i < coeff.size (); ++i) optimized_coefficients[i] = static_cast (coeff[i]); From 3bf835be1f46b49af94888048415aae0a88d24a7 Mon Sep 17 00:00:00 2001 From: Reini Urban Date: Wed, 24 Jul 2024 14:15:38 +0200 Subject: [PATCH 273/288] minor doc typo --- common/include/pcl/range_image/range_image_planar.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index 85afe3889b3..4abdf741285 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -133,7 +133,7 @@ namespace pcl * \param sensor_pose the pose of the virtual depth camera * \param coordinate_frame the used coordinate frame of the point cloud * \param noise_level what is the typical noise of the sensor - is used for averaging in the z-buffer - * \param min_range minimum range to consifder points + * \param min_range minimum range to consider points */ template void createFromPointCloudWithFixedSize (const PointCloudType& point_cloud, From d511a7f46fe82a1dd200e6025e1ab301b7d4fde2 Mon Sep 17 00:00:00 2001 From: Reini Urban Date: Sat, 27 Jul 2024 07:40:47 +0200 Subject: [PATCH 274/288] fix saveRangeImagePlanarFilePNG mixed up args. also fix the style. --- io/src/vtk_lib_io.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/io/src/vtk_lib_io.cpp b/io/src/vtk_lib_io.cpp index 623110f0f8b..f13855dd6c9 100644 --- a/io/src/vtk_lib_io.cpp +++ b/io/src/vtk_lib_io.cpp @@ -531,7 +531,7 @@ pcl::io::saveRangeImagePlanarFilePNG ( for (int x = 0; x < dims[0]; x++) { float* pixel = static_cast(image->GetScalarPointer(x,y,0)); - pixel[0] = range_image(y,x).range; + *pixel = range_image(x,y).range; } } From c5c376b2d4e104c33832331b6931c71978ab62f5 Mon Sep 17 00:00:00 2001 From: Roman Teterin Date: Mon, 29 Jul 2024 12:04:28 +0100 Subject: [PATCH 275/288] Fixed an integer overflow issue in the PassThrough filter. --- filters/src/passthrough.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/filters/src/passthrough.cpp b/filters/src/passthrough.cpp index c56a285a0f5..4614bd18684 100644 --- a/filters/src/passthrough.cpp +++ b/filters/src/passthrough.cpp @@ -61,7 +61,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) return; } - int nr_points = input_->width * input_->height; + uindex_t nr_points = input_->width * input_->height; // Check if we're going to keep the organized structure of the cloud or not if (keep_organized_) @@ -96,10 +96,10 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) removed_indices_->resize (input_->data.size ()); - int nr_p = 0; - int nr_removed_p = 0; + uindex_t nr_p = 0; + uindex_t nr_removed_p = 0; // Create the first xyz_offset - Eigen::Array4i xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset, + Eigen::Array xyz_offset (input_->fields[x_idx_].offset, input_->fields[y_idx_].offset, input_->fields[z_idx_].offset, 0); Eigen::Vector4f pt = Eigen::Vector4f::Zero (); @@ -131,7 +131,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) { float distance_value = 0; // Go over all points - for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) + for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) { // Copy all the fields memcpy (&output.data[cp * output.point_step], &input_->data[cp * output.point_step], output.point_step); @@ -175,7 +175,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) { // Go over all points float distance_value = 0; - for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) + for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) { // Get the distance value memcpy (&distance_value, &input_->data[cp * input_->point_step + input_->fields[distance_idx].offset], @@ -242,7 +242,7 @@ pcl::PassThrough::applyFilter (PCLPointCloud2 &output) // No distance filtering, process all data. No need to check for is_organized here as we did it above else { - for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) + for (uindex_t cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) { // Unoptimized memcpys: assume fields x, y, z are in random order memcpy (&pt[0], &input_->data[xyz_offset[0]], sizeof(float)); // NOLINT(readability-container-data-pointer) @@ -296,7 +296,7 @@ pcl::PassThrough::applyFilter (Indices &indices) // The arrays to be used indices.resize (indices_->size ()); removed_indices_->resize (indices_->size ()); - int oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator + uindex_t oii = 0, rii = 0; // oii = output indices iterator, rii = removed indices iterator const auto x_offset = input_->fields[x_idx_].offset, y_offset = input_->fields[y_idx_].offset, z_offset = input_->fields[z_idx_].offset; From 5ea0195a5c08291d11c5132612e3667deb36799a Mon Sep 17 00:00:00 2001 From: Markus Vieth <39675748+mvieth@users.noreply.github.com> Date: Tue, 6 Aug 2024 12:56:35 +0200 Subject: [PATCH 276/288] Use system-installed cJSON, if available (#6084) * Use system-installed cJSON, if available * Add warning if no system cJSON found --- CMakeLists.txt | 10 ++++++++++ outofcore/CMakeLists.txt | 10 ++++++++-- outofcore/include/pcl/outofcore/impl/octree_base.hpp | 5 +++++ .../include/pcl/outofcore/impl/octree_base_node.hpp | 5 +++++ outofcore/include/pcl/outofcore/outofcore_base_data.h | 5 +++++ outofcore/include/pcl/outofcore/outofcore_node_data.h | 5 +++++ pcl_config.h.in | 2 ++ 7 files changed, 40 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c898f02886d..67198899d0d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -432,6 +432,16 @@ if(WITH_SYSTEM_ZLIB) endif() endif() +option(WITH_SYSTEM_CJSON "Use system cJSON" TRUE) +if(WITH_SYSTEM_CJSON) + find_package(cJSON) + if(cJSON_FOUND) + set(HAVE_CJSON ON) + else() + message(WARNING "It is recommended to install an up-to-date version of cJSON on your system. CMake did not find one, and will instead use a cJSON version bundled with the PCL source code. However, that is an older version which may pose a risk and may be removed in a future PCL release.") + endif() +endif() + ### ---[ Create the config.h file set(pcl_config_h_in "${CMAKE_CURRENT_SOURCE_DIR}/pcl_config.h.in") set(pcl_config_h "${CMAKE_CURRENT_BINARY_DIR}/include/pcl/pcl_config.h") diff --git a/outofcore/CMakeLists.txt b/outofcore/CMakeLists.txt index eb71895d7c0..416669b8d98 100644 --- a/outofcore/CMakeLists.txt +++ b/outofcore/CMakeLists.txt @@ -19,7 +19,6 @@ if(NOT build) endif() set(srcs - src/cJSON.cpp src/outofcore_node_data.cpp src/outofcore_base_data.cpp ) @@ -32,7 +31,6 @@ set(incs "include/pcl/${SUBSYS_NAME}/outofcore_breadth_first_iterator.h" "include/pcl/${SUBSYS_NAME}/outofcore_depth_first_iterator.h" "include/pcl/${SUBSYS_NAME}/boost.h" - "include/pcl/${SUBSYS_NAME}/cJSON.h" "include/pcl/${SUBSYS_NAME}/octree_base.h" "include/pcl/${SUBSYS_NAME}/octree_base_node.h" "include/pcl/${SUBSYS_NAME}/octree_abstract_node_container.h" @@ -65,11 +63,19 @@ set(visualization_incs "include/pcl/${SUBSYS_NAME}/visualization/viewport.h" ) +if(NOT HAVE_CJSON) + list(APPEND srcs src/cJSON.cpp) + list(APPEND incs "include/pcl/${SUBSYS_NAME}/cJSON.h") +endif() + set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${visualization_incs}) #PCL_ADD_SSE_FLAGS("${LIB_NAME}") target_link_libraries("${LIB_NAME}" pcl_common pcl_visualization ${Boost_SYSTEM_LIBRARY}) +if(HAVE_CJSON) + target_link_libraries("${LIB_NAME}" ${CJSON_LIBRARIES}) +endif() PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC ${SUBSYS_DESC} PCL_DEPS ${SUBSYS_DEPS}) # Install include files diff --git a/outofcore/include/pcl/outofcore/impl/octree_base.hpp b/outofcore/include/pcl/outofcore/impl/octree_base.hpp index f3a8e6f3f0b..6ae31492bdc 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base.hpp @@ -44,7 +44,12 @@ #include // JSON +#include // for HAVE_CJSON +#if defined(HAVE_CJSON) +#include +#else #include +#endif #include #include diff --git a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp index 53778768ac8..b86c7d79a02 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_base_node.hpp @@ -57,7 +57,12 @@ #include // JSON +#include // for HAVE_CJSON +#if defined(HAVE_CJSON) +#include +#else #include +#endif namespace pcl { diff --git a/outofcore/include/pcl/outofcore/outofcore_base_data.h b/outofcore/include/pcl/outofcore/outofcore_base_data.h index 67f41e43134..16ef0a84ba4 100644 --- a/outofcore/include/pcl/outofcore/outofcore_base_data.h +++ b/outofcore/include/pcl/outofcore/outofcore_base_data.h @@ -40,7 +40,12 @@ #include #include +#include // for HAVE_CJSON +#if defined(HAVE_CJSON) +#include +#else #include +#endif #include diff --git a/outofcore/include/pcl/outofcore/outofcore_node_data.h b/outofcore/include/pcl/outofcore/outofcore_node_data.h index 09a85876e83..26997a96ec1 100644 --- a/outofcore/include/pcl/outofcore/outofcore_node_data.h +++ b/outofcore/include/pcl/outofcore/outofcore_node_data.h @@ -40,7 +40,12 @@ #include #include +#include // for HAVE_CJSON +#if defined(HAVE_CJSON) +#include +#else #include +#endif #include diff --git a/pcl_config.h.in b/pcl_config.h.in index 3277fa77b05..144ef144da5 100644 --- a/pcl_config.h.in +++ b/pcl_config.h.in @@ -54,6 +54,8 @@ #cmakedefine HAVE_ZLIB +#cmakedefine HAVE_CJSON + #cmakedefine PCL_PREFER_BOOST_FILESYSTEM /* Precompile for a minimal set of point types instead of all. */ From b92609ef8a71825785c74e7fc93bf81a966a193e Mon Sep 17 00:00:00 2001 From: Kai Wang Date: Mon, 12 Aug 2024 13:05:08 +0800 Subject: [PATCH 277/288] change `sprintf` to `snprintf` to suppress deprecated warning --- common/src/print.cpp | 56 ++++++++++++++++++++++---------------------- 1 file changed, 28 insertions(+), 28 deletions(-) diff --git a/common/src/print.cpp b/common/src/print.cpp index 5e99d8fbefd..0441649ccfd 100644 --- a/common/src/print.cpp +++ b/common/src/print.cpp @@ -52,7 +52,7 @@ # define COMMON_LVB_REVERSE_VIDEO 0 #endif -WORD +WORD convertAttributesColor (int attribute, int fg, int bg=0) { static WORD wAttributes[7] = { 0, // TT_RESET @@ -129,7 +129,7 @@ pcl::console::change_text_color (FILE *stream, int attribute, int fg, int bg) #else char command[40]; // Command is the control command to the terminal - sprintf (command, "%c[%d;%d;%dm", 0x1B, attribute, fg + 30, bg + 40); + snprintf (command, sizeof(command), "%c[%d;%d;%dm", 0x1B, attribute, fg + 30, bg + 40); fprintf (stream, "%s", command); #endif } @@ -146,7 +146,7 @@ pcl::console::change_text_color (FILE *stream, int attribute, int fg) #else char command[17]; // Command is the control command to the terminal - sprintf (command, "%c[%d;%dm", 0x1B, attribute, fg + 30); + snprintf (command, sizeof(command), "%c[%d;%dm", 0x1B, attribute, fg + 30); fprintf (stream, "%s", command); #endif } @@ -163,7 +163,7 @@ pcl::console::reset_text_color (FILE *stream) #else char command[13]; // Command is the control command to the terminal - sprintf (command, "%c[0;m", 0x1B); + snprintf (command, sizeof(command), "%c[0;m", 0x1B); fprintf (stream, "%s", command); #endif } @@ -178,7 +178,7 @@ pcl::console::print_color (FILE *stream, int attr, int fg, const char *format, . va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } @@ -186,7 +186,7 @@ pcl::console::print_color (FILE *stream, int attr, int fg, const char *format, . void pcl::console::print_info (const char *format, ...) { - if (!isVerbosityLevelEnabled (L_INFO)) return; + if (!isVerbosityLevelEnabled (L_INFO)) return; reset_text_color (stdout); @@ -258,7 +258,7 @@ pcl::console::print_error (const char *format, ...) va_start (ap, format); vfprintf (stderr, format, ap); va_end (ap); - + reset_text_color (stderr); } @@ -274,7 +274,7 @@ pcl::console::print_error (FILE *stream, const char *format, ...) va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } @@ -290,7 +290,7 @@ pcl::console::print_warn (const char *format, ...) va_start (ap, format); vfprintf (stderr, format, ap); va_end (ap); - + reset_text_color (stderr); } @@ -306,7 +306,7 @@ pcl::console::print_warn (FILE *stream, const char *format, ...) va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } @@ -322,7 +322,7 @@ pcl::console::print_value (const char *format, ...) va_start (ap, format); vfprintf (stdout, format, ap); va_end (ap); - + reset_text_color (stdout); } @@ -338,7 +338,7 @@ pcl::console::print_value (FILE *stream, const char *format, ...) va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } @@ -354,7 +354,7 @@ pcl::console::print_debug (const char *format, ...) va_start (ap, format); vfprintf (stdout, format, ap); va_end (ap); - + reset_text_color (stdout); } @@ -370,7 +370,7 @@ pcl::console::print_debug (FILE *stream, const char *format, ...) va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } @@ -381,7 +381,7 @@ namespace pcl { static bool s_NeedVerbosityInit = true; #ifdef VERBOSITY_LEVEL_ALWAYS - static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ALWAYS; + static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ALWAYS; #elif defined VERBOSITY_LEVEL_ERROR static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_ERROR; #elif defined VERBOSITY_LEVEL_WARN @@ -389,9 +389,9 @@ namespace pcl #elif defined VERBOSITY_LEVEL_DEBUG static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_DEBUG; #elif defined VERBOSITY_LEVEL_VERBOSE - static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_VERBOSE; -#else - static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_INFO; + static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_VERBOSE; +#else + static VERBOSITY_LEVEL s_VerbosityLevel = pcl::console::L_INFO; #endif } } @@ -416,15 +416,15 @@ bool pcl::console::isVerbosityLevelEnabled (pcl::console::VERBOSITY_LEVEL level) { if (s_NeedVerbosityInit) pcl::console::initVerbosityLevel (); - return level <= s_VerbosityLevel; + return level <= s_VerbosityLevel; } //////////////////////////////////////////////////////////////////////////////// -bool +bool pcl::console::initVerbosityLevel () { #ifdef VERBOSITY_LEVEL_ALWAYS - s_VerbosityLevel = pcl::console::L_ALWAYS; + s_VerbosityLevel = pcl::console::L_ALWAYS; #elif defined VERBOSITY_LEVEL_ERROR s_VerbosityLevel = pcl::console::L_ERROR; #elif defined VERBOSITY_LEVEL_WARN @@ -432,8 +432,8 @@ pcl::console::initVerbosityLevel () #elif defined VERBOSITY_LEVEL_DEBUG s_VerbosityLevel = pcl::console::L_DEBUG; #elif defined VERBOSITY_LEVEL_VERBOSE - s_VerbosityLevel = pcl::console::L_VERBOSE; -#else + s_VerbosityLevel = pcl::console::L_VERBOSE; +#else s_VerbosityLevel = pcl::console::L_INFO; // Default value #endif @@ -457,7 +457,7 @@ pcl::console::initVerbosityLevel () } //////////////////////////////////////////////////////////////////////////////// -void +void pcl::console::print (pcl::console::VERBOSITY_LEVEL level, FILE *stream, const char *format, ...) { if (!isVerbosityLevelEnabled (level)) return; @@ -484,12 +484,12 @@ pcl::console::print (pcl::console::VERBOSITY_LEVEL level, FILE *stream, const ch va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } //////////////////////////////////////////////////////////////////////////////// -void +void pcl::console::print (pcl::console::VERBOSITY_LEVEL level, const char *format, ...) { if (!isVerbosityLevelEnabled (level)) return; @@ -511,13 +511,13 @@ pcl::console::print (pcl::console::VERBOSITY_LEVEL level, const char *format, .. default: break; } - + va_list ap; va_start (ap, format); vfprintf (stream, format, ap); va_end (ap); - + reset_text_color (stream); } From 4885cf7917c005b13ff7aa6fd4862fcb3e5a43a6 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 17 Aug 2024 18:03:47 +0200 Subject: [PATCH 278/288] Remove warning in conversions.h Fixes https://github.com/PointCloudLibrary/pcl/issues/6092 --- common/include/pcl/conversions.h | 1 - 1 file changed, 1 deletion(-) diff --git a/common/include/pcl/conversions.h b/common/include/pcl/conversions.h index 80bba0491bf..9e1972d4c59 100644 --- a/common/include/pcl/conversions.h +++ b/common/include/pcl/conversions.h @@ -241,7 +241,6 @@ namespace pcl // check if there is data to copy if (msg.width * msg.height == 0) { - PCL_WARN("[pcl::fromPCLPointCloud2] No data to copy.\n"); return; } From 0ddeb32706499cab75b34b6e211384f043084a73 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 17 Aug 2024 14:19:21 +0200 Subject: [PATCH 279/288] =?UTF-8?q?Small=20fix=20in=20OpenMP=20for=20loop?= =?UTF-8?q?=20One=20compiler=20complained=20that=20"=E2=80=98kdtree?= =?UTF-8?q?=E2=80=99=20is=20predetermined=20=E2=80=98shared=E2=80=99=20for?= =?UTF-8?q?=20=E2=80=98shared=E2=80=99".=20kdtree=20is=20a=20const=20varia?= =?UTF-8?q?ble,=20which=20are=20always=20shared.=20The=20solution=20is=20t?= =?UTF-8?q?o=20remove=20kdtree=20from=20the=20shared=20clause=20(not=20exp?= =?UTF-8?q?licitly=20declare=20it=20as=20shared=20again).=20Then=20we=20al?= =?UTF-8?q?so=20have=20to=20remove=20`default(none)`=20because=20otherwise?= =?UTF-8?q?=20other=20compilers=20complain=20that=20the=20data=20sharing?= =?UTF-8?q?=20attribute=20is=20not=20explicitly=20defined=20for=20kdtree.?= =?UTF-8?q?=20Normally,=20`default(none)`=20is=20recommended=20because=20i?= =?UTF-8?q?t=20forces=20the=20programmer=20to=20consider=20which=20variabl?= =?UTF-8?q?es=20should=20be=20shared=20and=20which=20ones=20private.=20But?= =?UTF-8?q?=20since=20the=20code=20is=20finished,=20it=20is=20okay=20to=20?= =?UTF-8?q?remove=20`default(none)`.=20Basically,=20this=20solution=20(no?= =?UTF-8?q?=20`default(none)`=20and=20don't=20explicitly=20define=20the=20?= =?UTF-8?q?const=20`kdtree`=20as=20shared)=20is=20the=20only=20one=20that?= =?UTF-8?q?=20works=20with=20all=20compilers.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- registration/include/pcl/registration/impl/gicp.hpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/registration/include/pcl/registration/impl/gicp.hpp b/registration/include/pcl/registration/impl/gicp.hpp index 0688ef90195..93fb7c8198b 100644 --- a/registration/include/pcl/registration/impl/gicp.hpp +++ b/registration/include/pcl/registration/impl/gicp.hpp @@ -92,9 +92,8 @@ GeneralizedIterativeClosestPoint::computeCovar if (cloud_covariances.size() < cloud->size()) cloud_covariances.resize(cloud->size()); -#pragma omp parallel for default(none) num_threads(threads_) schedule(dynamic, 32) \ - shared(cloud, cloud_covariances, kdtree) \ - firstprivate(mean, cov, nn_indices, nn_dist_sq) +#pragma omp parallel for num_threads(threads_) schedule(dynamic, 32) \ + shared(cloud, cloud_covariances) firstprivate(mean, cov, nn_indices, nn_dist_sq) for (std::ptrdiff_t i = 0; i < static_cast(cloud->size()); ++i) { const PointT& query_point = (*cloud)[i]; // Zero out the cov and mean From 53aa9a7ecb862fc5b4bb923befc98c8831cb6281 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Sat, 17 Aug 2024 18:26:07 +0200 Subject: [PATCH 280/288] Update Windows x86 docker, install boost-cmake --- .ci/azure-pipelines/env.yml | 2 +- .dev/docker/windows/Dockerfile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/env.yml b/.ci/azure-pipelines/env.yml index 60d24e9eb73..58e8fdceda5 100644 --- a/.ci/azure-pipelines/env.yml +++ b/.ci/azure-pipelines/env.yml @@ -114,7 +114,7 @@ jobs: PLATFORM: x86 TAG: windows2022-x86 GENERATOR: "'Visual Studio 16 2019' -A Win32" - VCPKGCOMMIT: 8eb57355a4ffb410a2e94c07b4dca2dffbee8e50 + VCPKGCOMMIT: f7423ee180c4b7f40d43402c2feb3859161ef625 Winx64: PLATFORM: x64 TAG: windows2022-x64 diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index b8c5d0c64cc..b27c46af729 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -47,6 +47,6 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm RUN cd .\vcpkg; ` .\bootstrap-vcpkg.bat; ` - .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 cjson ` + .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid boost-cmake flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 cjson ` --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; From e2c94fb642bdaead3f5bee727cf603fedee5c6a2 Mon Sep 17 00:00:00 2001 From: qiuyilin Date: Tue, 13 Aug 2024 16:27:06 +0800 Subject: [PATCH 281/288] add border type setting in linemod guass step --- recognition/include/pcl/recognition/color_gradient_modality.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/recognition/include/pcl/recognition/color_gradient_modality.h b/recognition/include/pcl/recognition/color_gradient_modality.h index 89ca02cb49c..986b22b98aa 100644 --- a/recognition/include/pcl/recognition/color_gradient_modality.h +++ b/recognition/include/pcl/recognition/color_gradient_modality.h @@ -368,7 +368,7 @@ processInputData () convolution.setInputCloud (rgb_input_); convolution.setKernel (gaussian_kernel); - + convolution.setBordersPolicy(pcl::filters::Convolution::BORDERS_POLICY_DUPLICATE); convolution.convolve (*smoothed_input_); // extract color gradients From e4f766cea701fae359342813e8e9cd135a427a2a Mon Sep 17 00:00:00 2001 From: Ernesto Denicia Date: Tue, 20 Aug 2024 21:37:25 +0200 Subject: [PATCH 282/288] fix: Initialization with correct signedness (#6111) * fix: Initialization with correct signedness * fix: Deprecating max_label as not used anymore --------- Co-authored-by: uib54924 Co-authored-by: tricostume --- .../include/pcl/segmentation/extract_labeled_clusters.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index 39aab83b0fd..acdd3e9a71d 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -187,7 +187,8 @@ class LabeledEuclideanClusterExtraction : public PCLBase { /** \brief The maximum number of labels we can find in this pointcloud (default = * MAXINT)*/ - unsigned int max_label_{std::numeric_limits::max()}; + PCL_DEPRECATED(1, 18, "this member variable is unused") + unsigned int max_label_{std::numeric_limits::max()}; /** \brief Class getName method. */ virtual std::string From 4d0a15bb7bb85d304a7c1f7e2a4c5b5ca58cbb10 Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 15 Aug 2024 14:36:09 +0200 Subject: [PATCH 283/288] Allow building with Boost 1.86.0 --- outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp | 1 + outofcore/include/pcl/outofcore/octree_disk_container.h | 1 + 2 files changed, 2 insertions(+) diff --git a/outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp b/outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp index 28b25de7f51..642aced2853 100644 --- a/outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp +++ b/outofcore/include/pcl/outofcore/impl/octree_disk_container.hpp @@ -48,6 +48,7 @@ // Boost #include #include +#include // for boost::variate_generator #include // PCL diff --git a/outofcore/include/pcl/outofcore/octree_disk_container.h b/outofcore/include/pcl/outofcore/octree_disk_container.h index 0f9c0acf310..9ca3d5d99e0 100644 --- a/outofcore/include/pcl/outofcore/octree_disk_container.h +++ b/outofcore/include/pcl/outofcore/octree_disk_container.h @@ -44,6 +44,7 @@ #include // Boost +#include // for boost::mt19937 #include #include // pcl::utils::ignore From 0c8bf25e2a6d7e721983422f8513cdc177f8d1ab Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 15 Aug 2024 17:26:19 +0200 Subject: [PATCH 284/288] Require Boost 1.71.0, switch to BoostConfig.cmake --- PCLConfig.cmake.in | 5 +---- cmake/Modules/AdditionalBoostVersions.cmake | 7 ------- cmake/pcl_find_boost.cmake | 6 ++---- 3 files changed, 3 insertions(+), 15 deletions(-) delete mode 100644 cmake/Modules/AdditionalBoostVersions.cmake diff --git a/PCLConfig.cmake.in b/PCLConfig.cmake.in index a650af86fd7..b179a5d8b6e 100644 --- a/PCLConfig.cmake.in +++ b/PCLConfig.cmake.in @@ -94,10 +94,7 @@ macro(find_boost) set(BOOST_INCLUDEDIR "@Boost_INCLUDE_DIR@") endif() - include(${CMAKE_CURRENT_LIST_DIR}/Modules/AdditionalBoostVersions.cmake) - set(Boost_ADDITIONAL_VERSIONS "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@.@Boost_SUBMINOR_VERSION@" "@Boost_MAJOR_VERSION@.@Boost_MINOR_VERSION@" ${Boost_ADDITIONAL_VERSIONS}) - - find_package(Boost 1.65.0 ${QUIET_} COMPONENTS @PCLCONFIG_AVAILABLE_BOOST_MODULES@) + find_package(Boost 1.71.0 ${QUIET_} COMPONENTS @PCLCONFIG_AVAILABLE_BOOST_MODULES@ CONFIG) set(BOOST_FOUND ${Boost_FOUND}) set(BOOST_INCLUDE_DIRS "${Boost_INCLUDE_DIR}") diff --git a/cmake/Modules/AdditionalBoostVersions.cmake b/cmake/Modules/AdditionalBoostVersions.cmake deleted file mode 100644 index 0a06d08d0eb..00000000000 --- a/cmake/Modules/AdditionalBoostVersions.cmake +++ /dev/null @@ -1,7 +0,0 @@ - -set(Boost_ADDITIONAL_VERSIONS - "1.85.0" "1.85" - "1.84.0" "1.84" "1.83.0" "1.83" "1.82.0" "1.82" "1.81.0" "1.81" "1.80.0" "1.80" - "1.79.0" "1.79" "1.78.0" "1.78" "1.77.0" "1.77" "1.76.0" "1.76" "1.75.0" "1.75" - "1.74.0" "1.74" "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" - "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65") diff --git a/cmake/pcl_find_boost.cmake b/cmake/pcl_find_boost.cmake index f9e0b28d12c..5d5c7859e0a 100644 --- a/cmake/pcl_find_boost.cmake +++ b/cmake/pcl_find_boost.cmake @@ -13,8 +13,6 @@ else() endif() endif() -include(${CMAKE_CURRENT_LIST_DIR}/Modules/AdditionalBoostVersions.cmake) - if(CMAKE_CXX_STANDARD MATCHES "14") # Optional boost modules set(BOOST_OPTIONAL_MODULES serialization mpi) @@ -27,8 +25,8 @@ else() set(BOOST_REQUIRED_MODULES iostreams system) endif() -find_package(Boost 1.65.0 QUIET COMPONENTS ${BOOST_OPTIONAL_MODULES}) -find_package(Boost 1.65.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES}) +find_package(Boost 1.71.0 QUIET COMPONENTS ${BOOST_OPTIONAL_MODULES} CONFIG) +find_package(Boost 1.71.0 REQUIRED COMPONENTS ${BOOST_REQUIRED_MODULES} CONFIG) if(Boost_FOUND) set(BOOST_FOUND TRUE) From bfd615accc30b5789fc042bd557aed616e2b4ef5 Mon Sep 17 00:00:00 2001 From: Reini Urban Date: Wed, 21 Aug 2024 11:48:46 +0200 Subject: [PATCH 285/288] compile missing tools/bilateral_upsampling --- tools/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/tools/CMakeLists.txt b/tools/CMakeLists.txt index 3362164f66c..dd1f34f9912 100644 --- a/tools/CMakeLists.txt +++ b/tools/CMakeLists.txt @@ -184,6 +184,8 @@ if(TARGET pcl_filters) PCL_ADD_EXECUTABLE(pcl_mls_smoothing COMPONENT ${SUBSYS_NAME} SOURCES mls_smoothing.cpp) target_link_libraries (pcl_mls_smoothing pcl_common pcl_io pcl_surface pcl_filters) + PCL_ADD_EXECUTABLE(pcl_bilateral_upsampling COMPONENT ${SUBSYS_NAME} SOURCES bilateral_upsampling.cpp) + target_link_libraries(pcl_bilateral_upsampling pcl_common pcl_io pcl_surface) endif() if(TARGET pcl_keypoints) From 13d437bf04ccc4716545582a1c191eb8161a2b0a Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Thu, 22 Aug 2024 11:13:58 +0200 Subject: [PATCH 286/288] Remove global includes and use target include for GPU/CUDA (#6010) * Change to use target_include_directories. Rearranged files between gpu_utils and gpu_containers, to break cyclic includes. * Remove unncessary .cpp file. * Revert moving of files. * Copy error function to safe_call. Added deprecated headers for notice to users. * Revert include paths. * Add missing include * Added empty cu file. * Add include to gpu people. --- cuda/apps/CMakeLists.txt | 1 - cuda/common/CMakeLists.txt | 1 - cuda/features/CMakeLists.txt | 1 - cuda/io/CMakeLists.txt | 1 - cuda/sample_consensus/CMakeLists.txt | 1 - cuda/segmentation/CMakeLists.txt | 1 - gpu/containers/CMakeLists.txt | 9 +- .../pcl/gpu/containers/impl/repacks.hpp | 154 ++++++++++++++++++ .../gpu/containers/impl/texture_binder.hpp | 93 +++++++++++ gpu/{utils => containers}/src/repacks.cu | 6 +- gpu/features/CMakeLists.txt | 1 - gpu/features/test/CMakeLists.txt | 20 +-- gpu/kinfu/CMakeLists.txt | 6 +- gpu/kinfu/tools/CMakeLists.txt | 3 - gpu/kinfu_large_scale/CMakeLists.txt | 4 +- gpu/kinfu_large_scale/tools/CMakeLists.txt | 3 - gpu/octree/CMakeLists.txt | 2 +- gpu/octree/src/cuda/octree_host.cu | 4 +- gpu/octree/src/octree.cpp | 1 + gpu/people/CMakeLists.txt | 15 +- gpu/people/src/cuda/elec.cu | 2 +- gpu/people/src/cuda/multi_tree.cu | 2 +- gpu/people/src/cuda/prob.cu | 2 +- gpu/people/src/cuda/utils.cu | 3 +- gpu/people/tools/CMakeLists.txt | 3 - gpu/segmentation/CMakeLists.txt | 1 - gpu/surface/CMakeLists.txt | 4 +- gpu/surface/test/CMakeLists.txt | 12 -- gpu/tracking/CMakeLists.txt | 4 +- gpu/utils/CMakeLists.txt | 5 +- gpu/utils/include/pcl/gpu/utils/repacks.hpp | 92 +---------- gpu/utils/include/pcl/gpu/utils/safe_call.hpp | 45 +++-- .../include/pcl/gpu/utils/texture_binder.hpp | 55 +------ gpu/utils/src/empty.cu | 1 + gpu/utils/src/internal.hpp | 7 +- gpu/utils/src/repacks.cpp | 41 ----- 36 files changed, 318 insertions(+), 288 deletions(-) create mode 100644 gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp create mode 100644 gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp rename gpu/{utils => containers}/src/repacks.cu (98%) create mode 100644 gpu/utils/src/empty.cu delete mode 100644 gpu/utils/src/repacks.cpp diff --git a/cuda/apps/CMakeLists.txt b/cuda/apps/CMakeLists.txt index a8190839eb6..f15ad276572 100644 --- a/cuda/apps/CMakeLists.txt +++ b/cuda/apps/CMakeLists.txt @@ -10,7 +10,6 @@ if(NOT VTK_FOUND) else() set(DEFAULT TRUE) set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") endif() PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ${DEFAULT} "${REASON}") diff --git a/cuda/common/CMakeLists.txt b/cuda/common/CMakeLists.txt index 164c3a8ef13..186f5b7212f 100644 --- a/cuda/common/CMakeLists.txt +++ b/cuda/common/CMakeLists.txt @@ -27,7 +27,6 @@ set(common_incs include/pcl/cuda/common/point_type_rgb.h ) -include_directories(./include) set(LIB_NAME "pcl_${SUBSYS_NAME}") set(EXT_DEPS CUDA) PCL_MAKE_PKGCONFIG(${LIB_NAME} COMPONENT ${SUBSYS_NAME} DESC "${SUBSYS_DESC}" diff --git a/cuda/features/CMakeLists.txt b/cuda/features/CMakeLists.txt index a40975d2a99..018a3058024 100644 --- a/cuda/features/CMakeLists.txt +++ b/cuda/features/CMakeLists.txt @@ -23,7 +23,6 @@ set(incs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) target_link_libraries(${LIB_NAME} pcl_common) diff --git a/cuda/io/CMakeLists.txt b/cuda/io/CMakeLists.txt index 5ddfc90b1b4..3c25360ac2c 100644 --- a/cuda/io/CMakeLists.txt +++ b/cuda/io/CMakeLists.txt @@ -34,7 +34,6 @@ set(incs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) target_link_libraries(${LIB_NAME} pcl_common) diff --git a/cuda/sample_consensus/CMakeLists.txt b/cuda/sample_consensus/CMakeLists.txt index 537c10efae2..59455e4228f 100644 --- a/cuda/sample_consensus/CMakeLists.txt +++ b/cuda/sample_consensus/CMakeLists.txt @@ -32,7 +32,6 @@ set(incs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) target_link_libraries("${LIB_NAME}" pcl_cuda_features) diff --git a/cuda/segmentation/CMakeLists.txt b/cuda/segmentation/CMakeLists.txt index ce73fb8260f..5354513e040 100644 --- a/cuda/segmentation/CMakeLists.txt +++ b/cuda/segmentation/CMakeLists.txt @@ -24,7 +24,6 @@ set(srcs ) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) target_link_libraries(${LIB_NAME} pcl_common) diff --git a/gpu/containers/CMakeLists.txt b/gpu/containers/CMakeLists.txt index f81db10a309..a07418e0fd4 100644 --- a/gpu/containers/CMakeLists.txt +++ b/gpu/containers/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME gpu_containers) set(SUBSYS_PATH gpu/containers) set(SUBSYS_DESC "Containers with reference counting for GPU memory. This module can be compiled without Cuda Toolkit.") -set(SUBSYS_DEPS common) +set(SUBSYS_DEPS common gpu_utils) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) @@ -12,19 +12,16 @@ if(NOT build) return() endif() -file(GLOB srcs src/*.cpp src/*.hpp) +file(GLOB srcs src/*.cpp src/*.cu src/*.hpp) file(GLOB incs include/pcl/gpu/containers/*.h) file(GLOB incs_impl include/pcl/gpu/containers/impl/*.hpp) source_group("Header Files\\impl" FILES ${incs_impl}) list(APPEND incs ${incs_impl}) -get_filename_component(UTILS_INC "${CMAKE_CURRENT_SOURCE_DIR}/../utils/include" REALPATH) - set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" ${UTILS_INC}) PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) -target_link_libraries(${LIB_NAME} pcl_common) +target_link_libraries(${LIB_NAME} pcl_common pcl_gpu_utils) #Ensures that CUDA is added and the project can compile as it uses cuda calls. set_source_files_properties(src/device_memory.cpp PROPERTIES LANGUAGE CUDA) diff --git a/gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp b/gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp new file mode 100644 index 00000000000..db9c7f29356 --- /dev/null +++ b/gpu/containers/include/pcl/gpu/containers/impl/repacks.hpp @@ -0,0 +1,154 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 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. + * + * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) + */ + +#ifndef __PCL_GPU_UTILS_REPACKS_HPP__ +#define __PCL_GPU_UTILS_REPACKS_HPP__ + +#include +#include +#include + +namespace pcl { +namespace gpu { +/////////////////////////////////////// +/// This is an experimental code /// +/////////////////////////////////////// + +const int NoCP = 0xFFFFFFFF; + +/** \brief Returns field copy operation code. */ +inline int +cp(int from, int to) +{ + return ((to & 0xF) << 4) + (from & 0xF); +} + +/* Combines several field copy operations to one int (called rule) */ +inline int +rule(int cp1, int cp2 = NoCP, int cp3 = NoCP, int cp4 = NoCP) +{ + return (cp1 & 0xFF) + ((cp2 & 0xFF) << 8) + ((cp3 & 0xFF) << 16) + + ((cp4 & 0xFF) << 24); +} + +/* Combines performs all field copy operations in given rule array (can be 0, 1, or 16 + * copies) */ +void +copyFieldsImpl( + int in_size, int out_size, int rules[4], int size, const void* input, void* output); + +template +void +copyFieldsEx(const DeviceArray& src, + DeviceArray& dst, + int rule1, + int rule2 = NoCP, + int rule3 = NoCP, + int rule4 = NoCP) +{ + int rules[4] = {rule1, rule2, rule3, rule4}; + dst.create(src.size()); + copyFieldsImpl(sizeof(PointIn) / sizeof(int), + sizeof(PointOut) / sizeof(int), + rules, + (int)src.size(), + src.ptr(), + dst.ptr()); +} + +void +copyFields(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZ.x (0) -> PointNormal.x (0) + // PointXYZ.y (1) -> PointNormal.y (1) + // PointXYZ.z (2) -> PointNormal.z (2) + copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); +}; + +void +copyFields(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZ.normal_x (0) -> PointNormal.normal_x (4) + // PointXYZ.normal_y (1) -> PointNormal.normal_y (5) + // PointXYZ.normal_z (2) -> PointNormal.normal_z (6) + // PointXYZ.curvature (4) -> PointNormal.curvature (8) + copyFieldsEx(src, dst, rule(cp(0, 4), cp(1, 5), cp(2, 6), cp(4, 8))); +}; + +void +copyFields(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZRGBL.x (0) -> PointXYZ.x (0) + // PointXYZRGBL.y (1) -> PointXYZ.y (1) + // PointXYZRGBL.z (2) -> PointXYZ.z (2) + copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); +}; + +void +copyFields(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZRGB.x (0) -> PointXYZ.x (0) + // PointXYZRGB.y (1) -> PointXYZ.y (1) + // PointXYZRGB.z (2) -> PointXYZ.z (2) + copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); +}; + +void +copyFields(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZRGBA.x (0) -> PointXYZ.x (0) + // PointXYZRGBA.y (1) -> PointXYZ.y (1) + // PointXYZRGBA.z (2) -> PointXYZ.z (2) + copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); +}; + +void +copyFieldsZ(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZRGBL.z (2) -> float (1) + copyFieldsEx(src, dst, rule(cp(2, 0))); +}; + +void +copyFieldsZ(const DeviceArray& src, DeviceArray& dst) +{ + // PointXYZRGBL.z (2) -> float (1) + copyFieldsEx(src, dst, rule(cp(2, 0))); +}; +} // namespace gpu +} // namespace pcl + +#endif /* __PCL_GPU_UTILS_REPACKS_HPP__ */ diff --git a/gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp b/gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp new file mode 100644 index 00000000000..16dede926cb --- /dev/null +++ b/gpu/containers/include/pcl/gpu/containers/impl/texture_binder.hpp @@ -0,0 +1,93 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 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. + * + * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) + */ + +#ifndef PCL_GPU_UTILS_TEXTURE_BINDER_HPP_ +#define PCL_GPU_UTILS_TEXTURE_BINDER_HPP_ + +#include +#include + +namespace pcl { +namespace gpu { +class TextureBinder { +public: + template + TextureBinder(const DeviceArray2D& arr, const struct texture& tex) + : texref(&tex) + { + cudaChannelFormatDesc desc = cudaCreateChannelDesc(); + cudaSafeCall( + cudaBindTexture2D(0, tex, arr.ptr(), desc, arr.cols(), arr.rows(), arr.step())); + } + + template + TextureBinder(const DeviceArray& arr, const struct texture& tex) + : texref(&tex) + { + cudaChannelFormatDesc desc = cudaCreateChannelDesc(); + cudaSafeCall(cudaBindTexture(0, tex, arr.ptr(), desc, arr.sizeBytes())); + } + + template + TextureBinder(const PtrStepSz& arr, const struct texture& tex) + : texref(&tex) + { + cudaChannelFormatDesc desc = cudaCreateChannelDesc(); + cudaSafeCall( + cudaBindTexture2D(0, tex, arr.data, desc, arr.cols, arr.rows, arr.step)); + } + + template + TextureBinder(const PtrSz& arr, const struct texture& tex) + : texref(&tex) + { + cudaChannelFormatDesc desc = cudaCreateChannelDesc(); + cudaSafeCall(cudaBindTexture(0, tex, arr.data, desc, arr.size * arr.elemSize())); + } + + ~TextureBinder() { cudaSafeCall(cudaUnbindTexture(texref)); } + +private: + const struct textureReference* texref; +}; +} // namespace gpu + +namespace device { +using pcl::gpu::TextureBinder; +} +} // namespace pcl + +#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/ \ No newline at end of file diff --git a/gpu/utils/src/repacks.cu b/gpu/containers/src/repacks.cu similarity index 98% rename from gpu/utils/src/repacks.cu rename to gpu/containers/src/repacks.cu index 2467bf9b9d8..e99956a7500 100644 --- a/gpu/utils/src/repacks.cu +++ b/gpu/containers/src/repacks.cu @@ -1,7 +1,7 @@ -#include "internal.hpp" +#include +#include + #include -#include "pcl/gpu/utils/safe_call.hpp" -#include "pcl/pcl_exports.h" namespace pcl { diff --git a/gpu/features/CMakeLists.txt b/gpu/features/CMakeLists.txt index ebc1a6cd829..4eecde02fc0 100644 --- a/gpu/features/CMakeLists.txt +++ b/gpu/features/CMakeLists.txt @@ -24,7 +24,6 @@ file(GLOB srcs_utils src/utils/*.hpp) source_group("Source Files\\utils" FILES ${srcs_utils}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${cuda} ${srcs_utils} ${dev_incs}) target_link_libraries("${LIB_NAME}" pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree) diff --git a/gpu/features/test/CMakeLists.txt b/gpu/features/test/CMakeLists.txt index 7d81b67e799..3ae9e04f104 100644 --- a/gpu/features/test/CMakeLists.txt +++ b/gpu/features/test/CMakeLists.txt @@ -2,26 +2,8 @@ if(NOT BUILD_TESTS) return() endif() -include_directories( - "${PCL_SOURCE_DIR}/test/gtest-1.6.0/include" - "${PCL_SOURCE_DIR}/test/gtest-1.6.0" -) - -set(pcl_gtest_sources "${PCL_SOURCE_DIR}/test/gtest-1.6.0/src/gtest-all.cc") - set(the_test_target test_gpu_features) -get_filename_component(DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) -get_filename_component(INC1 "${DIR}/../../../io/include" REALPATH) -get_filename_component(INC2 "${DIR}/../../../features/include" REALPATH) -get_filename_component(INC3 "${DIR}/../../../kdtree/include" REALPATH) -get_filename_component(INC4 "${DIR}/../../../visualization/include" REALPATH) -get_filename_component(INC5 "${DIR}/../../../common/include" REALPATH) -get_filename_component(INC6 "${DIR}/../../../search/include" REALPATH) -get_filename_component(INC7 "${DIR}/../../../octree/include" REALPATH) - - file(GLOB test_src *.cpp *.hpp) list(APPEND test_src ${pcl_gtest_sources}) -include_directories("${INC1}" "${INC2}" "${INC3}" "${INC4}" "${INC5}" "${INC6}" "${INC7}") -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) + diff --git a/gpu/kinfu/CMakeLists.txt b/gpu/kinfu/CMakeLists.txt index 723604a7557..2ba88e0c1d8 100644 --- a/gpu/kinfu/CMakeLists.txt +++ b/gpu/kinfu/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME gpu_kinfu) set(SUBSYS_PATH gpu/kinfu) set(SUBSYS_DESC "Kinect Fusion implementation") -set(SUBSYS_DEPS common io gpu_containers geometry search) +set(SUBSYS_DEPS common io gpu_utils gpu_containers geometry search) if(${CUDA_VERSION_STRING} VERSION_GREATER_EQUAL "12.0") set(DEFAULT FALSE) set(REASON "Kinfu uses textures which was removed in CUDA 12") @@ -26,10 +26,10 @@ source_group("Source Files\\cuda" FILES ${cuda}) source_group("Source Files" FILES ${srcs}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${cuda}) -target_link_libraries(${LIB_NAME} pcl_gpu_containers) +target_link_libraries(${LIB_NAME} pcl_gpu_utils pcl_gpu_containers) +target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src) target_compile_options(${LIB_NAME} PRIVATE $<$:--ftz=true;--prec-div=false;--prec-sqrt=false>) diff --git a/gpu/kinfu/tools/CMakeLists.txt b/gpu/kinfu/tools/CMakeLists.txt index 2477f8669bf..4a52d7833a1 100644 --- a/gpu/kinfu/tools/CMakeLists.txt +++ b/gpu/kinfu/tools/CMakeLists.txt @@ -13,10 +13,7 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - file(GLOB hdrs "*.h*") -include_directories(SYSTEM ${OPENNI_INCLUDE_DIRS}) ## KINECT FUSION set(the_target pcl_kinfu_app) diff --git a/gpu/kinfu_large_scale/CMakeLists.txt b/gpu/kinfu_large_scale/CMakeLists.txt index a84950dc7fc..da956a2770e 100644 --- a/gpu/kinfu_large_scale/CMakeLists.txt +++ b/gpu/kinfu_large_scale/CMakeLists.txt @@ -29,11 +29,9 @@ source_group("Source Files\\cuda" FILES ${cuda}) source_group("Source Files" FILES ${srcs}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src") - PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs} ${impl_incs} ${cuda}) - target_link_libraries(${LIB_NAME} pcl_common pcl_io pcl_gpu_utils pcl_gpu_containers pcl_gpu_octree pcl_octree pcl_filters) +target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src) target_compile_options(${LIB_NAME} PRIVATE $<$:--ftz=true;--prec-div=false;--prec-sqrt=false>) diff --git a/gpu/kinfu_large_scale/tools/CMakeLists.txt b/gpu/kinfu_large_scale/tools/CMakeLists.txt index 017a1907f54..30fbebe248d 100644 --- a/gpu/kinfu_large_scale/tools/CMakeLists.txt +++ b/gpu/kinfu_large_scale/tools/CMakeLists.txt @@ -13,10 +13,7 @@ if(NOT build) return() endif() -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") - file(GLOB hdrs "*.h*") -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) ## STANDALONE TEXTURE MAPPING set(the_target pcl_kinfu_largeScale_texture_output) diff --git a/gpu/octree/CMakeLists.txt b/gpu/octree/CMakeLists.txt index ddc043276bb..2c2f67e9813 100644 --- a/gpu/octree/CMakeLists.txt +++ b/gpu/octree/CMakeLists.txt @@ -25,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda}) list(APPEND srcs ${utils} ${cuda}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) target_link_libraries("${LIB_NAME}" pcl_gpu_containers) +target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/gpu/octree/src/cuda/octree_host.cu b/gpu/octree/src/cuda/octree_host.cu index 2230ab3e2e2..8e8782c34f9 100644 --- a/gpu/octree/src/cuda/octree_host.cu +++ b/gpu/octree/src/cuda/octree_host.cu @@ -34,8 +34,8 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ -#include "pcl/gpu/utils/timers_cuda.hpp" -#include "pcl/gpu/utils/safe_call.hpp" +#include +#include #include "internal.hpp" #include "utils/approx_nearest_utils.hpp" diff --git a/gpu/octree/src/octree.cpp b/gpu/octree/src/octree.cpp index 63a7e738360..e5b06391aab 100644 --- a/gpu/octree/src/octree.cpp +++ b/gpu/octree/src/octree.cpp @@ -34,6 +34,7 @@ * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) */ +#include #include #include #include diff --git a/gpu/people/CMakeLists.txt b/gpu/people/CMakeLists.txt index dcc2040f4eb..6c9c3abad16 100644 --- a/gpu/people/CMakeLists.txt +++ b/gpu/people/CMakeLists.txt @@ -46,17 +46,18 @@ file(GLOB hdrs_cuda src/cuda/nvidia/*.h*) source_group("Source files\\cuda" FILES ${srcs_cuda}) source_group("Source files" FILES ${srcs}) -include_directories( - "${CMAKE_CURRENT_SOURCE_DIR}/include" - "${CMAKE_CURRENT_SOURCE_DIR}/src" - "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda" - "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda/nvidia" -) - set(LIB_NAME "pcl_${SUBSYS_NAME}") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${hdrs} ${srcs_cuda}) target_link_libraries(${LIB_NAME} pcl_common pcl_search pcl_surface pcl_segmentation pcl_features pcl_sample_consensus pcl_gpu_utils pcl_gpu_containers ${CUDA_CUDART_LIBRARY} ${CUDA_npp_LIBRARY}) +target_include_directories( + ${LIB_NAME} + PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/src + ${CMAKE_CURRENT_SOURCE_DIR}/src/cuda + PUBLIC + ${CMAKE_CURRENT_SOURCE_DIR}/src/cuda/nvidia +) if(UNIX OR APPLE) target_compile_options(${LIB_NAME} INTERFACE $<$:"-Xcompiler=-fPIC">) diff --git a/gpu/people/src/cuda/elec.cu b/gpu/people/src/cuda/elec.cu index 0cacdf9f0e1..2b3cd85a60b 100644 --- a/gpu/people/src/cuda/elec.cu +++ b/gpu/people/src/cuda/elec.cu @@ -1,6 +1,6 @@ #include "internal.h" -#include +#include #include #include diff --git a/gpu/people/src/cuda/multi_tree.cu b/gpu/people/src/cuda/multi_tree.cu index 5abc443d580..df256264b1a 100644 --- a/gpu/people/src/cuda/multi_tree.cu +++ b/gpu/people/src/cuda/multi_tree.cu @@ -41,7 +41,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/gpu/people/src/cuda/prob.cu b/gpu/people/src/cuda/prob.cu index b9cf5524dfc..52c89a5e62e 100644 --- a/gpu/people/src/cuda/prob.cu +++ b/gpu/people/src/cuda/prob.cu @@ -41,7 +41,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/gpu/people/src/cuda/utils.cu b/gpu/people/src/cuda/utils.cu index 834de9283d9..5f29d5c61af 100644 --- a/gpu/people/src/cuda/utils.cu +++ b/gpu/people/src/cuda/utils.cu @@ -2,7 +2,8 @@ #include "internal.h" #include -#include +#include +#include #include "npp.h" #include diff --git a/gpu/people/tools/CMakeLists.txt b/gpu/people/tools/CMakeLists.txt index 6cd7e7f9931..68e9b6e3ffe 100644 --- a/gpu/people/tools/CMakeLists.txt +++ b/gpu/people/tools/CMakeLists.txt @@ -6,13 +6,10 @@ if(NOT VTK_FOUND) else() set(DEFAULT TRUE) set(REASON) - include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") endif() set(the_target people_tracking) -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) - #PCL_ADD_EXECUTABLE(${the_target} "${SUBSYS_NAME}" people_tracking.cpp) #target_link_libraries("${the_target}" pcl_common pcl_kdtree pcl_gpu_people pcl_io pcl_visualization) diff --git a/gpu/segmentation/CMakeLists.txt b/gpu/segmentation/CMakeLists.txt index 42cb57850cc..8bc3992c298 100644 --- a/gpu/segmentation/CMakeLists.txt +++ b/gpu/segmentation/CMakeLists.txt @@ -31,7 +31,6 @@ 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_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}) diff --git a/gpu/surface/CMakeLists.txt b/gpu/surface/CMakeLists.txt index 64eea2ae17e..22a84d72a98 100644 --- a/gpu/surface/CMakeLists.txt +++ b/gpu/surface/CMakeLists.txt @@ -25,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda}) list(APPEND srcs ${utils} ${cuda}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) -target_link_libraries("${LIB_NAME}" pcl_gpu_containers) +target_link_libraries(${LIB_NAME} pcl_gpu_containers) +target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/gpu/surface/test/CMakeLists.txt b/gpu/surface/test/CMakeLists.txt index 83f912d9310..96f6600d247 100644 --- a/gpu/surface/test/CMakeLists.txt +++ b/gpu/surface/test/CMakeLists.txt @@ -4,18 +4,6 @@ endif() set(the_test_target test_gpu_surface) -get_filename_component(DIR "${CMAKE_CURRENT_LIST_FILE}" PATH) -get_filename_component(INC_SURF "${DIR}/../../surface/include" REALPATH) -get_filename_component(INC_IO "${DIR}/../../../io/include" REALPATH) -get_filename_component(INC_VIZ "${DIR}/../../../visualization/include" REALPATH) -get_filename_component(INC_GEO "${DIR}/../../../geometry/include" REALPATH) -get_filename_component(INC_SURF_CPU "${DIR}/../../../surface/include" REALPATH) -get_filename_component(INC_SEA "${DIR}/../../../search/include" REALPATH) -get_filename_component(INC_KD "${DIR}/../../../kdtree/include" REALPATH) -get_filename_component(INC_OCT "${DIR}/../../../octree/include" REALPATH) -include_directories("${INC_SURF}" "${INC_IO}" "${INC_VIZ}" "${INC_GEO}" "${INC_SURF_CPU}" "${INC_SEA}" "${INC_KD}" "${INC_OCT}") -include_directories(SYSTEM ${VTK_INCLUDE_DIRS}) - file(GLOB test_src *.cpp *.hpp) #PCL_ADD_TEST(a_gpu_surface_test ${the_test_target} FILES ${test_src} LINK_WITH pcl_io pcl_gpu_containers pcl_gpu_surface pcl_visualization pcl_surface pcl_octree pcl_kdtree pcl_search) #add_dependencies(${the_test_target} pcl_io pcl_gpu_containes pcl_gpu_surface pcl_visualization) diff --git a/gpu/tracking/CMakeLists.txt b/gpu/tracking/CMakeLists.txt index 3b8221208dd..651c1718d9c 100644 --- a/gpu/tracking/CMakeLists.txt +++ b/gpu/tracking/CMakeLists.txt @@ -25,9 +25,9 @@ source_group("Source Files\\cuda" FILES ${cuda}) list(APPEND srcs ${utils} ${cuda}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include" "${CMAKE_CURRENT_SOURCE_DIR}/src" "${CMAKE_CURRENT_SOURCE_DIR}/src/cuda") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${srcs} ${incs}) -target_link_libraries("${LIB_NAME}" pcl_gpu_containers) +target_link_libraries(${LIB_NAME} pcl_gpu_containers) +target_include_directories(${LIB_NAME} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/src) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/gpu/utils/CMakeLists.txt b/gpu/utils/CMakeLists.txt index 6f0aac6a22a..e0f4ccfb020 100644 --- a/gpu/utils/CMakeLists.txt +++ b/gpu/utils/CMakeLists.txt @@ -1,7 +1,7 @@ set(SUBSYS_NAME gpu_utils) set(SUBSYS_PATH gpu/utils) set(SUBSYS_DESC "Device layer functions.") -set(SUBSYS_DEPS common gpu_containers) +set(SUBSYS_DEPS common) PCL_SUBSYS_OPTION(build "${SUBSYS_NAME}" "${SUBSYS_DESC}" ON) PCL_SUBSYS_DEPEND(build NAME ${SUBSYS_NAME} DEPS ${SUBSYS_DEPS}) @@ -19,9 +19,8 @@ source_group("Header Files\\device" FILES ${dev_incs}) source_group("Source Files" FILES ${srcs}) set(LIB_NAME "pcl_${SUBSYS_NAME}") -include_directories("${CMAKE_CURRENT_SOURCE_DIR}/include") PCL_CUDA_ADD_LIBRARY(${LIB_NAME} COMPONENT ${SUBSYS_NAME} SOURCES ${dev_incs} ${incs} ${srcs}) -target_link_libraries("${LIB_NAME}" pcl_gpu_containers) +target_link_libraries("${LIB_NAME}" pcl_common) set(EXT_DEPS "") #set(EXT_DEPS CUDA) diff --git a/gpu/utils/include/pcl/gpu/utils/repacks.hpp b/gpu/utils/include/pcl/gpu/utils/repacks.hpp index ce1e2d221dd..217fa321db8 100644 --- a/gpu/utils/include/pcl/gpu/utils/repacks.hpp +++ b/gpu/utils/include/pcl/gpu/utils/repacks.hpp @@ -37,97 +37,7 @@ #ifndef __PCL_GPU_UTILS_REPACKS_HPP__ #define __PCL_GPU_UTILS_REPACKS_HPP__ -#include -#include +PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated, please include it from pcl/gpu/containers.") -#include - -namespace pcl -{ - namespace gpu - { - /////////////////////////////////////// - /// This is an experimental code /// - /////////////////////////////////////// - - const int NoCP = 0xFFFFFFFF; - - /** \brief Returns field copy operation code. */ - inline int cp(int from, int to) - { - return ((to & 0xF) << 4) + (from & 0xF); - } - - /* Combines several field copy operations to one int (called rule) */ - inline int rule(int cp1, int cp2 = NoCP, int cp3 = NoCP, int cp4 = NoCP) - { - return (cp1 & 0xFF) + ((cp2 & 0xFF) << 8) + ((cp3 & 0xFF) << 16) + ((cp4 & 0xFF) << 24); - } - - /* Combines performs all field copy operations in given rule array (can be 0, 1, or 16 copies) */ - void copyFieldsImpl(int in_size, int out_size, int rules[4], int size, const void* input, void* output); - - template - void copyFieldsEx(const DeviceArray& src, DeviceArray& dst, int rule1, int rule2 = NoCP, int rule3 = NoCP, int rule4 = NoCP) - { - int rules[4] = { rule1, rule2, rule3, rule4 }; - dst.create(src.size()); - copyFieldsImpl(sizeof(PointIn)/sizeof(int), sizeof(PointOut)/sizeof(int), rules, (int)src.size(), src.ptr(), dst.ptr()); - } - - void copyFields(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZ.x (0) -> PointNormal.x (0) - //PointXYZ.y (1) -> PointNormal.y (1) - //PointXYZ.z (2) -> PointNormal.z (2) - copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); - }; - - void copyFields(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZ.normal_x (0) -> PointNormal.normal_x (4) - //PointXYZ.normal_y (1) -> PointNormal.normal_y (5) - //PointXYZ.normal_z (2) -> PointNormal.normal_z (6) - //PointXYZ.curvature (4) -> PointNormal.curvature (8) - copyFieldsEx(src, dst, rule(cp(0, 4), cp(1, 5), cp(2, 6), cp(4,8))); - }; - - void copyFields(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZRGBL.x (0) -> PointXYZ.x (0) - //PointXYZRGBL.y (1) -> PointXYZ.y (1) - //PointXYZRGBL.z (2) -> PointXYZ.z (2) - copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); - }; - - void copyFields(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZRGB.x (0) -> PointXYZ.x (0) - //PointXYZRGB.y (1) -> PointXYZ.y (1) - //PointXYZRGB.z (2) -> PointXYZ.z (2) - copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); - }; - - void copyFields(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZRGBA.x (0) -> PointXYZ.x (0) - //PointXYZRGBA.y (1) -> PointXYZ.y (1) - //PointXYZRGBA.z (2) -> PointXYZ.z (2) - copyFieldsEx(src, dst, rule(cp(0, 0), cp(1, 1), cp(2, 2))); - }; - - void copyFieldsZ(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZRGBL.z (2) -> float (1) - copyFieldsEx(src, dst, rule(cp(2, 0))); - }; - - void copyFieldsZ(const DeviceArray& src, DeviceArray& dst) - { - //PointXYZRGBL.z (2) -> float (1) - copyFieldsEx(src, dst, rule(cp(2, 0))); - }; - } -} #endif /* __PCL_GPU_UTILS_REPACKS_HPP__ */ diff --git a/gpu/utils/include/pcl/gpu/utils/safe_call.hpp b/gpu/utils/include/pcl/gpu/utils/safe_call.hpp index 2a2e844d72e..0c0b8373956 100644 --- a/gpu/utils/include/pcl/gpu/utils/safe_call.hpp +++ b/gpu/utils/include/pcl/gpu/utils/safe_call.hpp @@ -38,32 +38,41 @@ #define __PCL_CUDA_SAFE_CALL_HPP__ #include -#include + +#include #if defined(__GNUC__) - #define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__, __func__) +#define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__, __func__) #else /* defined(__CUDACC__) || defined(__MSVC__) */ - #define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__) +#define cudaSafeCall(expr) pcl::gpu::___cudaSafeCall(expr, __FILE__, __LINE__) #endif -namespace pcl -{ - namespace gpu - { - static inline void ___cudaSafeCall(cudaError_t err, const char *file, const int line, const char *func = "") - { - if (cudaSuccess != err) - error(cudaGetErrorString(err), file, line, func); - } +namespace pcl { +namespace gpu { - static inline int divUp(int total, int grain) { return (total + grain - 1) / grain; } - } +static inline void +___cudaSafeCall(cudaError_t err, + const char* file, + const int line, + const char* func = "") +{ + if (cudaSuccess != err) { + std::cout << "Error: " << cudaGetErrorString(err) << "\t" << file << ":" << line + << ":" << func << std::endl; + exit(EXIT_FAILURE); + } +} - namespace device - { - using pcl::gpu::divUp; - } +static inline int +divUp(int total, int grain) +{ + return (total + grain - 1) / grain; } +} // namespace gpu +namespace device { +using pcl::gpu::divUp; +} +} // namespace pcl #endif /* __PCL_CUDA_SAFE_CALL_HPP__ */ diff --git a/gpu/utils/include/pcl/gpu/utils/texture_binder.hpp b/gpu/utils/include/pcl/gpu/utils/texture_binder.hpp index 772392e042b..a52799fe3ab 100644 --- a/gpu/utils/include/pcl/gpu/utils/texture_binder.hpp +++ b/gpu/utils/include/pcl/gpu/utils/texture_binder.hpp @@ -37,57 +37,6 @@ #ifndef PCL_GPU_UTILS_TEXTURE_BINDER_HPP_ #define PCL_GPU_UTILS_TEXTURE_BINDER_HPP_ -#include -#include +PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated, please include it from pcl/gpu/containers.") -namespace pcl -{ - namespace gpu - { - class TextureBinder - { - public: - template - TextureBinder(const DeviceArray2D& arr, const struct texture& tex) : texref(&tex) - { - cudaChannelFormatDesc desc = cudaCreateChannelDesc(); - cudaSafeCall( cudaBindTexture2D(0, tex, arr.ptr(), desc, arr.cols(), arr.rows(), arr.step()) ); - } - - template - TextureBinder(const DeviceArray& arr, const struct texture &tex) : texref(&tex) - { - cudaChannelFormatDesc desc = cudaCreateChannelDesc(); - cudaSafeCall( cudaBindTexture(0, tex, arr.ptr(), desc, arr.sizeBytes()) ); - } - - template - TextureBinder(const PtrStepSz& arr, const struct texture& tex) : texref(&tex) - { - cudaChannelFormatDesc desc = cudaCreateChannelDesc(); - cudaSafeCall( cudaBindTexture2D(0, tex, arr.data, desc, arr.cols, arr.rows, arr.step) ); - } - - template - TextureBinder(const PtrSz& arr, const struct texture &tex) : texref(&tex) - { - cudaChannelFormatDesc desc = cudaCreateChannelDesc(); - cudaSafeCall( cudaBindTexture(0, tex, arr.data, desc, arr.size * arr.elemSize()) ); - } - - ~TextureBinder() - { - cudaSafeCall( cudaUnbindTexture(texref) ); - } - private: - const struct textureReference *texref; - }; - } - - namespace device - { - using pcl::gpu::TextureBinder; - } -} - -#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/ \ No newline at end of file +#endif /* PCL_GPU_UTILS_TEXTURE_BINDER_HPP_*/ diff --git a/gpu/utils/src/empty.cu b/gpu/utils/src/empty.cu new file mode 100644 index 00000000000..1de32816f93 --- /dev/null +++ b/gpu/utils/src/empty.cu @@ -0,0 +1 @@ +// added empty file for Cmake to determine link language. diff --git a/gpu/utils/src/internal.hpp b/gpu/utils/src/internal.hpp index 52245ca7f46..f1c2fbb6326 100644 --- a/gpu/utils/src/internal.hpp +++ b/gpu/utils/src/internal.hpp @@ -37,6 +37,11 @@ #ifndef PCL_GPU_UTILS_INTERNAL_HPP_ #define PCL_GPU_UTILS_INTERNAL_HPP_ +#include + +PCL_DEPRECATED_HEADER(1, 17, "This has been deprecated and will be removed.") + + namespace pcl { namespace device @@ -45,4 +50,4 @@ namespace pcl } } -#endif \ No newline at end of file +#endif diff --git a/gpu/utils/src/repacks.cpp b/gpu/utils/src/repacks.cpp deleted file mode 100644 index eae8e6081b5..00000000000 --- a/gpu/utils/src/repacks.cpp +++ /dev/null @@ -1,41 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 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. - * - * Author: Anatoly Baskeheev, Itseez Ltd, (myname.mysurname@mycompany.com) - */ - -#include - -#include -#include "internal.hpp" - From 5e8496907bccb20554789f997bffe85730d623cc Mon Sep 17 00:00:00 2001 From: Lars Glud Date: Mon, 26 Aug 2024 10:46:37 +0200 Subject: [PATCH 287/288] Install glew and glut. --- .ci/azure-pipelines/build/macos.yaml | 2 +- .dev/docker/env/Dockerfile | 1 + .dev/docker/windows/Dockerfile | 26 +++++++++++++++++++++++++- 3 files changed, 27 insertions(+), 2 deletions(-) diff --git a/.ci/azure-pipelines/build/macos.yaml b/.ci/azure-pipelines/build/macos.yaml index 08d07d45edd..30a328627c2 100644 --- a/.ci/azure-pipelines/build/macos.yaml +++ b/.ci/azure-pipelines/build/macos.yaml @@ -3,7 +3,7 @@ steps: # find the commit hash on a quick non-forced update too fetchDepth: 10 - script: | - brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew qt5 libpcap libomp google-benchmark cjson + brew install cmake pkg-config boost eigen flann glew libusb qhull vtk glew freeglut qt5 libpcap libomp google-benchmark cjson brew install brewsci/science/openni git clone https://github.com/abseil/googletest.git $GOOGLE_TEST_DIR # the official endpoint changed to abseil/googletest cd $GOOGLE_TEST_DIR && git checkout release-1.8.1 diff --git a/.dev/docker/env/Dockerfile b/.dev/docker/env/Dockerfile index d1f84fe8f3c..a8122a96cfb 100644 --- a/.dev/docker/env/Dockerfile +++ b/.dev/docker/env/Dockerfile @@ -37,6 +37,7 @@ RUN apt-get update \ libcjson-dev \ libflann-dev \ libglew-dev \ + freeglut3-dev \ libgtest-dev \ libomp-dev \ libopenni-dev \ diff --git a/.dev/docker/windows/Dockerfile b/.dev/docker/windows/Dockerfile index b27c46af729..902cc9a8c1a 100644 --- a/.dev/docker/windows/Dockerfile +++ b/.dev/docker/windows/Dockerfile @@ -47,6 +47,30 @@ COPY $PLATFORM'-windows-rel.cmake' 'c:\vcpkg\triplets\'$PLATFORM'-windows-rel.cm RUN cd .\vcpkg; ` .\bootstrap-vcpkg.bat; ` - .\vcpkg install boost-accumulators boost-asio boost-algorithm boost-filesystem boost-format boost-graph boost-interprocess boost-iostreams boost-math boost-ptr-container boost-signals2 boost-sort boost-uuid boost-cmake flann eigen3 qhull vtk[qt,opengl] gtest benchmark openni2 cjson ` + .\vcpkg install ` + boost-accumulators ` + boost-asio ` + boost-algorithm ` + boost-filesystem ` + boost-format ` + boost-graph ` + boost-interprocess ` + boost-iostreams ` + boost-math ` + boost-ptr-container ` + boost-signals2 ` + boost-sort ` + boost-uuid ` + boost-cmake ` + flann ` + eigen3 ` + qhull ` + glew ` + freeglut ` + vtk[qt,opengl] ` + gtest ` + benchmark ` + openni2 ` + cjson ` --triplet $Env:PLATFORM-windows-rel --host-triplet $Env:PLATFORM-windows-rel --clean-after-build --x-buildtrees-root=C:\b; From 6f1105a4c30416a55196db048ef9759e22cdd04e Mon Sep 17 00:00:00 2001 From: Markus Vieth Date: Thu, 22 Aug 2024 20:48:19 +0200 Subject: [PATCH 288/288] Compatibility with clang-19 --- .../registration/correspondence_rejection_features.h | 6 +++--- .../pcl/surface/3rdparty/poisson4/octree_poisson.hpp | 11 +++++++---- .../pcl/surface/3rdparty/poisson4/sparse_matrix.hpp | 10 +++++++--- 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/registration/include/pcl/registration/correspondence_rejection_features.h b/registration/include/pcl/registration/correspondence_rejection_features.h index 44835c379fc..f3bab8fef01 100644 --- a/registration/include/pcl/registration/correspondence_rejection_features.h +++ b/registration/include/pcl/registration/correspondence_rejection_features.h @@ -269,9 +269,9 @@ class PCL_EXPORTS CorrespondenceRejectorFeatures : public CorrespondenceRejector // Check if the representations are valid if (!feature_representation_->isValid(feat_src) || !feature_representation_->isValid(feat_tgt)) { - PCL_ERROR("[pcl::registration::%s::getCorrespondenceScore] Invalid feature " - "representation given!\n", - this->getClassName().c_str()); + PCL_ERROR( + "[pcl::registration::CorrespondenceRejectorFeatures::FeatureContainer::" + "getCorrespondenceScore] Invalid feature representation given!\n"); return (std::numeric_limits::max()); } diff --git a/surface/include/pcl/surface/3rdparty/poisson4/octree_poisson.hpp b/surface/include/pcl/surface/3rdparty/poisson4/octree_poisson.hpp index 7ed8aaf9d82..e7f45b650e9 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/octree_poisson.hpp +++ b/surface/include/pcl/surface/3rdparty/poisson4/octree_poisson.hpp @@ -746,7 +746,10 @@ namespace pcl Real temp,dist2; if(!children){return this;} for(int i=0;i child_center; + Real child_width; + children[i].centerAndWidth(child_center, child_width); + temp=SquareDistance(child_center,p); if(!i || tempoffset[i] = node.offset[i];} + for(i=0;ioff[i] = node.off[i];} if(node.children){ initChildren(); for(i=0;i int OctNode::CompareForwardDepths(const void* v1,const void* v2){ - return ((const OctNode*)v1)->depth-((const OctNode*)v2)->depth; + return ((const OctNode*)v1)->depth()-((const OctNode*)v2)->depth(); } template< class NodeData , class Real > @@ -874,7 +877,7 @@ namespace pcl template int OctNode::CompareBackwardDepths(const void* v1,const void* v2){ - return ((const OctNode*)v2)->depth-((const OctNode*)v1)->depth; + return ((const OctNode*)v2)->depth()-((const OctNode*)v1)->depth(); } template diff --git a/surface/include/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp b/surface/include/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp index 24f0a5402c5..5e54ac7862d 100644 --- a/surface/include/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp +++ b/surface/include/pcl/surface/3rdparty/poisson4/sparse_matrix.hpp @@ -228,14 +228,18 @@ namespace pcl template void SparseMatrix::SetZero() { - Resize(this->m_N, this->m_M); + // copied from operator *= + for (int i=0; i void SparseMatrix::SetIdentity() { SetZero(); - for(int ij=0; ij < Min( this->Rows(), this->Columns() ); ij++) + for(int ij=0; ij < std::min( rows, _maxEntriesPerRow ); ij++) (*this)(ij,ij) = T(1); } @@ -388,7 +392,7 @@ namespace pcl T alpha,beta,rDotR; int i; - solution.Resize(M.Columns()); + solution.Resize(bb.Dimensions()); solution.SetZero(); d=r=bb;