Skip to content

Commit

Permalink
Misc small fixes and improvements
Browse files Browse the repository at this point in the history
- remove unused variables in dominant_plane_segmentation.hpp, integral_image_normal.hpp, our_cvfh.hpp
- remove unnecessary parenthesis in pcl_macros.h (otherwise the deprecation messages are "It will be removed in PCL (1).15")
- ply_io.cpp: catch exception when parsing bad ply files
- add includes for KdTree, OrganizedNeighbor, eigen33 (the files use these classes/functions, so the headers should be included; currently they rely on transitive includes)
- in random_sample.h: use srand_deterministic on OpenBSD to properly use seed and fix failing test on OpenBSD
- in pcl_visualizer.cpp: replace 5 with better value. The Boost doc only says that digest_type is at least 16 bytes large (in the current code it is 20 bytes large). Additionally, there is no guarantee that unsigned int is 4 bytes large (even if that is the most common situation)
  • Loading branch information
mvieth committed Nov 29, 2024
1 parent 75ef8c5 commit 9185bc8
Show file tree
Hide file tree
Showing 25 changed files with 47 additions and 36 deletions.
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
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
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
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
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
2 changes: 1 addition & 1 deletion registration/include/pcl/registration/ndt.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ class NormalDistributionsTransform
// Prevents unnecessary voxel initiations
if (resolution_ != resolution) {
resolution_ = resolution;
if (input_) {
if (target_) { // init() needs target_
init();
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -451,10 +451,9 @@ pcl::SampleConsensusModelEllipse3D<PointT>::optimizeModelCoefficients (
OptimizationFunctor functor(this, inliers);
Eigen::NumericalDiff<OptimizationFunctor> num_diff(functor);
Eigen::LevenbergMarquardt<Eigen::NumericalDiff<OptimizationFunctor>, double> lm(num_diff);
Eigen::VectorXd coeff;
Eigen::VectorXd coeff = model_coefficients.cast<double>();
int info = lm.minimize(coeff);
for (Eigen::Index i = 0; i < coeff.size (); ++i)
optimized_coefficients[i] = static_cast<float> (coeff[i]);
optimized_coefficients = coeff.cast<float>();

// 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\nFinal solution: %g %g %g %g %g %g %g %g %g %g %g\n",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ pcl::SampleConsensusModelTorus<PointT, PointNT>::isSampleGood(

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
float
crossDot(Eigen::Vector3f v1, Eigen::Vector3f v2, Eigen::Vector3f v3)
crossDot(const Eigen::Vector3f& v1, const Eigen::Vector3f& v2, const Eigen::Vector3f& v3)
{
return v1.cross(v2).dot(v3);
}
Expand Down
4 changes: 1 addition & 3 deletions surface/include/pcl/surface/impl/grid_projection.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -630,9 +630,7 @@ pcl::GridProjection<PointNT>::reconstructPolygons (std::vector<pcl::Vertices> &p
for (pcl::index_t cp = 0; cp < static_cast<pcl::index_t> (data_->size ()); ++cp)
{
// Check if the point is invalid
if (!std::isfinite ((*data_)[cp].x) ||
!std::isfinite ((*data_)[cp].y) ||
!std::isfinite ((*data_)[cp].z))
if (!pcl::isXYZFinite((*data_)[cp]))
continue;

Eigen::Vector3i index_3d;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -259,9 +259,7 @@ pcl::visualization::PCLVisualizer::convertPointCloudToVTKPolyData (
for (vtkIdType i = 0; i < nr_points; ++i)
{
// Check if the point is invalid
if (!std::isfinite ((*cloud)[i].x) ||
!std::isfinite ((*cloud)[i].y) ||
!std::isfinite ((*cloud)[i].z))
if (!pcl::isXYZFinite((*cloud)[i]))
continue;

std::copy (&(*cloud)[i].x, &(*cloud)[i].x + 3, &data[ptr]);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,9 +171,7 @@ PointCloudColorHandlerRGBField<PointT>::getColor () const
for (vtkIdType cp = 0; cp < nr_points; ++cp)
{
// Copy the value at the specified field
if (!std::isfinite ((*cloud_)[cp].x) ||
!std::isfinite ((*cloud_)[cp].y) ||
!std::isfinite ((*cloud_)[cp].z))
if (!pcl::isXYZFinite((*cloud_)[cp]))
continue;
memcpy (&rgb, (reinterpret_cast<const char *> (&(*cloud_)[cp])) + rgba_offset, sizeof (pcl::RGB));
colors[j ] = rgb.r;
Expand Down Expand Up @@ -256,9 +254,7 @@ PointCloudColorHandlerHSVField<PointT>::getColor () const
for (vtkIdType cp = 0; cp < nr_points; ++cp)
{
// Copy the value at the specified field
if (!std::isfinite ((*cloud_)[cp].x) ||
!std::isfinite ((*cloud_)[cp].y) ||
!std::isfinite ((*cloud_)[cp].z))
if (!pcl::isXYZFinite((*cloud_)[cp]))
continue;

///@todo do this with the point_types_conversion in common, first template it!
Expand Down Expand Up @@ -409,7 +405,7 @@ PointCloudColorHandlerGenericField<PointT>::getColor () const
for (vtkIdType cp = 0; cp < nr_points; ++cp)
{
// Copy the value at the specified field
if (!std::isfinite ((*cloud_)[cp].x) || !std::isfinite ((*cloud_)[cp].y) || !std::isfinite ((*cloud_)[cp].z))
if (!pcl::isXYZFinite((*cloud_)[cp]))
continue;

const std::uint8_t* pt_data = reinterpret_cast<const std::uint8_t*> (&(*cloud_)[cp]);
Expand Down Expand Up @@ -479,9 +475,7 @@ PointCloudColorHandlerRGBAField<PointT>::getColor () const
for (vtkIdType cp = 0; cp < nr_points; ++cp)
{
// Copy the value at the specified field
if (!std::isfinite ((*cloud_)[cp].x) ||
!std::isfinite ((*cloud_)[cp].y) ||
!std::isfinite ((*cloud_)[cp].z))
if (!pcl::isXYZFinite((*cloud_)[cp]))
continue;

colors[j ] = (*cloud_)[cp].r;
Expand Down
4 changes: 2 additions & 2 deletions visualization/src/pcl_visualizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4358,7 +4358,7 @@ int
pcl::visualization::PCLVisualizer::getGeometryHandlerIndex (const std::string &id)
{
auto am_it = style_->getCloudActorMap ()->find (id);
if (am_it != cloud_actor_map_->end ())
if (am_it == cloud_actor_map_->end ())
return (-1);

return (am_it->second.geometry_handler_index_);
Expand Down Expand Up @@ -4593,7 +4593,7 @@ pcl::visualization::PCLVisualizer::getUniqueCameraFile (int argc, char **argv)
boost::uuids::detail::sha1::digest_type digest;
sha1.get_digest (digest);
sstream << ".";
for (int i = 0; i < 5; ++i) {
for (int i = 0; i < static_cast<int>(sizeof(digest)/sizeof(unsigned int)); ++i) {
sstream << std::hex << *(reinterpret_cast<unsigned int*>(&digest[0]) + i);
}
sstream << ".cam";
Expand Down

0 comments on commit 9185bc8

Please sign in to comment.