Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Misc small fixes and improvements #6179

Merged
merged 3 commits into from
Nov 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 0 additions & 4 deletions apps/include/pcl/apps/impl/dominant_plane_segmentation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_table_plane()

// Compute the plane coefficients
Eigen::Vector4f model_coefficients;
EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;

model_coefficients[0] = table_coefficients_->values[0];
model_coefficients[1] = table_coefficients_->values[1];
Expand Down Expand Up @@ -251,7 +250,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_fast(

// Compute the plane coefficients
Eigen::Vector4f model_coefficients;
EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;

model_coefficients[0] = table_coefficients_->values[0];
model_coefficients[1] = table_coefficients_->values[1];
Expand Down Expand Up @@ -626,7 +624,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute(

// Compute the plane coefficients
Eigen::Vector4f model_coefficients;
EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;

model_coefficients[0] = table_coefficients_->values[0];
model_coefficients[1] = table_coefficients_->values[1];
Expand Down Expand Up @@ -795,7 +792,6 @@ pcl::apps::DominantPlaneSegmentation<PointType>::compute_full(

// Compute the plane coefficients
Eigen::Vector4f model_coefficients;
EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;

model_coefficients[0] = table_coefficients_->values[0];
model_coefficients[1] = table_coefficients_->values[1];
Expand Down
8 changes: 4 additions & 4 deletions common/include/pcl/common/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@ namespace pcl
getMaxDistance (const pcl::PointCloud<PointT> &cloud, const Indices &indices,
const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt);

/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
* \param[in] cloud the point cloud data message
* \param[out] min_pt the resultant minimum bounds
* \param[out] max_pt the resultant maximum bounds
Expand All @@ -189,7 +189,7 @@ namespace pcl
template <typename PointT> inline void
getMinMax3D (const pcl::PointCloud<PointT> &cloud, PointT &min_pt, PointT &max_pt);

/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
* \param[in] cloud the point cloud data message
* \param[out] min_pt the resultant minimum bounds
* \param[out] max_pt the resultant maximum bounds
Expand All @@ -199,7 +199,7 @@ namespace pcl
getMinMax3D (const pcl::PointCloud<PointT> &cloud,
Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);

/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
* \param[in] cloud the point cloud data message
* \param[in] indices the vector of point indices to use from \a cloud
* \param[out] min_pt the resultant minimum bounds
Expand All @@ -210,7 +210,7 @@ namespace pcl
getMinMax3D (const pcl::PointCloud<PointT> &cloud, const Indices &indices,
Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);

/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud
/** \brief Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud. This is the axis aligned bounding box (AABB).
* \param[in] cloud the point cloud data message
* \param[in] indices the vector of point indices to use from \a cloud
* \param[out] min_pt the resultant minimum bounds
Expand Down
4 changes: 3 additions & 1 deletion common/include/pcl/pcl_macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,13 @@
#define _PCL_DEPRECATED_HEADER_IMPL(Message)
#endif

// NOLINTBEGIN(bugprone-macro-parentheses)
/**
* \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) ")"
// NOLINTEND(bugprone-macro-parentheses)

/**
* \brief Tests for Minor < PCL_MINOR_VERSION
Expand Down
1 change: 1 addition & 0 deletions features/include/pcl/features/impl/cppf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
#define PCL_FEATURES_IMPL_CPPF_H_

#include <pcl/features/cppf.h>
#include <pcl/search/kdtree.h> // for KdTree

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT>
Expand Down
1 change: 1 addition & 0 deletions features/include/pcl/features/impl/cvfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <pcl/features/cvfh.h>
#include <pcl/features/normal_3d.h>
#include <pcl/common/centroid.h>
#include <pcl/search/kdtree.h> // for KdTree

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointNT, typename PointOutT> void
Expand Down
2 changes: 2 additions & 0 deletions features/include/pcl/features/impl/flare.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@

#include <pcl/features/flare.h>
#include <pcl/common/geometry.h>
#include <pcl/search/kdtree.h> // for KdTree
#include <pcl/search/organized.h> // for OrganizedNeighbor

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointNT, typename PointOutT, typename SignedDistanceT> bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
*
*/
#pragma once
#include <pcl/common/eigen.h> // for eigen33
#include <pcl/features/integral_image_normal.h>

#include <algorithm>
Expand Down Expand Up @@ -491,7 +492,6 @@ pcl::IntegralImageNormalEstimation<PointInT, PointOutT>::computePointNormalMirro
Eigen::Vector3f center;
typename IntegralImage2D<float, 3>::SecondOrderType so_elements;
typename IntegralImage2D<float, 3>::ElementType tmp_center;
typename IntegralImage2D<float, 3>::SecondOrderType tmp_so_elements;

center[0] = 0;
center[1] = 0;
Expand Down
1 change: 1 addition & 0 deletions features/include/pcl/features/impl/intensity_gradient.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <pcl/features/intensity_gradient.h>

#include <pcl/common/point_tests.h> // for pcl::isFinite
#include <pcl/common/eigen.h> // for eigen33


//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/impl/our_cvfh.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
#include <pcl/common/io.h> // for copyPointCloud
#include <pcl/common/common.h> // for getMaxDistance
#include <pcl/common/transforms.h>
#include <pcl/search/kdtree.h> // for KdTree

//////////////////////////////////////////////////////////////////////////////////////////////
template<typename PointInT, typename PointNT, typename PointOutT> void
Expand Down Expand Up @@ -623,7 +624,6 @@ pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloud
{

pcl::PointIndices pi;
pcl::PointIndices pi_cvfh;
pcl::PointIndices pi_filtered;

clusters_.push_back (pi);
Expand Down
1 change: 1 addition & 0 deletions features/include/pcl/features/impl/ppf.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <pcl/features/ppf.h>
#include <pcl/features/pfh.h>
#include <pcl/features/pfh_tools.h> // for computePairFeatures
#include <pcl/search/kdtree.h> // for KdTree

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT>
Expand Down
1 change: 1 addition & 0 deletions features/include/pcl/features/impl/ppfrgb.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <pcl/features/ppfrgb.h>
#include <pcl/features/pfhrgb.h>
#include <pcl/search/kdtree.h> // for KdTree

//////////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <pcl/features/principal_curvatures.h>

#include <pcl/common/point_tests.h> // for pcl::isFinite
#include <pcl/common/eigen.h> // for eigen33

///////////////////////////////////////////////////////////////////////////////////////////
template <typename PointInT, typename PointNT, typename PointOutT> void
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/convolution_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,7 @@ namespace pcl
double search_radius_;

/** \brief number of threads */
unsigned int threads_;
unsigned int threads_{1};

/** \brief convlving kernel */
KernelT kernel_;
Expand Down
1 change: 1 addition & 0 deletions filters/include/pcl/filters/covariance_sampling.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ namespace pcl
* Based on the following publication:
* * "Geometrically Stable Sampling for the ICP Algorithm" - N. Gelfand, L. Ikemoto, S. Rusinkiewicz, M. Levoy
*
* \ingroup filters
* \author Alexandru E. Ichim, [email protected]
*/
template <typename PointT, typename PointNT>
Expand Down
4 changes: 4 additions & 0 deletions filters/include/pcl/filters/impl/random_sample.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,11 @@ pcl::RandomSample<PointT>::applyFilter (Indices &indices)
removed_indices_->resize (N - sample_size);

// Set random seed so derived indices are the same each time the filter runs
#ifdef __OpenBSD__
srand_deterministic (seed_); // OpenBSD only offers repeatable sequences with this function
#else
std::srand (seed_);
#endif // __OpenBSD__

// Algorithm S
std::size_t i = 0;
Expand Down
1 change: 1 addition & 0 deletions filters/include/pcl/filters/model_outlier_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ namespace pcl
* filter.filter (*cloud_out);

* \endcode
* \ingroup filters
*/
template <typename PointT>
class ModelOutlierRemoval : public FilterIndices<PointT>
Expand Down
1 change: 1 addition & 0 deletions filters/include/pcl/filters/radius_outlier_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ namespace pcl
* indices_rem = rorfilter.getRemovedIndices ();
* // The indices_rem array indexes all points of cloud_in that have 5 or more neighbors within the 0.1 search radius
* \endcode
* \sa StatisticalOutlierRemoval
* \author Radu Bogdan Rusu
* \ingroup filters
*/
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/sampling_surface_normal.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ namespace pcl
using PointCloudPtr = typename PointCloud::Ptr;
using PointCloudConstPtr = typename PointCloud::ConstPtr;

using Vector = Eigen::Matrix<float, Eigen::Dynamic, 1>;
using Vector = Eigen::Matrix<float, 3, 1>;

public:

Expand Down
1 change: 1 addition & 0 deletions filters/include/pcl/filters/statistical_outlier_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ namespace pcl
* indices_rem = sorfilter.getRemovedIndices ();
* // The indices_rem array indexes all points of cloud_in that are outliers
* \endcode
* \sa RadiusOutlierRemoval
* \author Radu Bogdan Rusu
* \ingroup filters
*/
Expand Down
4 changes: 4 additions & 0 deletions filters/src/random_sample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,11 @@ pcl::RandomSample<pcl::PCLPointCloud2>::applyFilter (Indices &indices)
removed_indices_->resize (N - sample_size);

// Set random seed so derived indices are the same each time the filter runs
#ifdef __OpenBSD__
srand_deterministic (seed_); // OpenBSD only offers repeatable sequences with this function
#else
std::srand (seed_);
#endif // __OpenBSD__

// Algorithm S
std::size_t i = 0;
Expand Down
12 changes: 10 additions & 2 deletions io/src/ply_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -409,8 +409,16 @@ void
pcl::PLYReader::vertexIntensityCallback (pcl::io::ply::uint8 intensity)
{
pcl::io::ply::float32 intensity_ (intensity);
cloud_->at<pcl::io::ply::float32>(vertex_count_, vertex_offset_before_) = intensity_;
vertex_offset_before_ += static_cast<int> (sizeof (pcl::io::ply::float32));
try
{
cloud_->at<pcl::io::ply::float32>(vertex_count_, vertex_offset_before_) = intensity_;
vertex_offset_before_ += static_cast<int> (sizeof (pcl::io::ply::float32));
}
catch(const std::out_of_range&)
{
PCL_WARN ("[pcl::PLYReader::vertexIntensityCallback] Incorrect data index specified (%lu)!\n", vertex_count_ * cloud_->point_step + vertex_offset_before_);
assert(false);
}
}

void
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,10 +107,10 @@ namespace pcl
if (!stack_.empty ())
{
std::pair<OutofcoreOctreeBaseNode<ContainerT, PointT>*, unsigned char>& stackEntry = stack_.back ();
stack_.pop_back ();

this->currentNode_ = stackEntry.first;
currentChildIdx_ = stackEntry.second;
stack_.pop_back (); // stackEntry is a reference, so pop_back after accessing it!

//don't do anything with the keys here...
this->currentOctreeDepth_--;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -299,8 +299,8 @@ PyramidFeatureHistogram<PointFeature>::compute()
if (!initializeHistogram())
return;

std::vector<float> feature_vector; // put here to reuse memory
for (const auto& point : *input_) {
std::vector<float> feature_vector;
// NaN is converted to very high number that gives out of bound exception.
if (!pcl::isFinite(point))
continue;
Expand Down
Loading
Loading