Skip to content

Commit

Permalink
Merge branch 'pcl'
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Jun 20, 2024
2 parents 787e117 + 85aa23d commit e12e4af
Show file tree
Hide file tree
Showing 7 changed files with 54 additions and 68 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ find_package(YARP 3.8 REQUIRED COMPONENTS os dev sig

# Soft dependencies.
find_package(OpenCV QUIET)
find_package(PCL 1.8 QUIET COMPONENTS common features filters search surface)
find_package(PCL 1.10 QUIET COMPONENTS common features filters search surface)
find_package(GTestSources 1.8 QUIET)
find_package(SWIG QUIET)
find_package(Doxygen QUIET)
Expand Down
9 changes: 0 additions & 9 deletions libraries/YarpCloudUtils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,6 @@ option(ENABLE_YarpCloudUtils "Enable/disable YarpCloudUtils" ON)

if(ENABLE_YarpCloudUtils)

if(PCL_VERSION VERSION_LESS 1.9)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})

# workaround for PCL 1.8 (Ubuntu 18.04), exclude empty/blank strings as compile defs
list(FILTER PCL_DEFINITIONS EXCLUDE REGEX "^ +$")
add_definitions(${PCL_DEFINITIONS})
endif()

add_library(YarpCloudUtils SHARED YarpCloudUtils.hpp
YarpCloudUtils-ply-export.cpp
YarpCloudUtils-ply-import.cpp
Expand Down
55 changes: 36 additions & 19 deletions libraries/YarpCloudUtils/YarpCloudUtils-pcl-impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,9 +43,7 @@
#include <pcl/surface/grid_projection.h>
#include <pcl/surface/marching_cubes_hoppe.h>
#include <pcl/surface/marching_cubes_rbf.h>
#if PCL_VERSION_COMPARE(>=, 1, 9, 0)
#include <pcl/surface/mls.h>
#endif
#include <pcl/surface/organized_fast_mesh.h>
#include <pcl/surface/poisson.h>
#include <pcl/surface/simplification_remove_unused_vertices.h>
Expand Down Expand Up @@ -146,7 +144,7 @@ void doBilateralFilter(const typename pcl::PointCloud<T>::ConstPtr & in, const t
auto halfSize = options.check("halfSize", yarp::os::Value(0.0)).asFloat64();
auto stdDev = options.check("stdDev", yarp::os::Value(std::numeric_limits<double>::max())).asFloat64();

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::BilateralFilter<T> filter;
Expand Down Expand Up @@ -277,7 +275,7 @@ void doGreedyProjectionTriangulation(const typename pcl::PointCloud<T>::ConstPtr
auto normalConsistency = options.check("normalConsistency", yarp::os::Value(false)).asBool();
auto searchRadius = options.check("searchRadius", yarp::os::Value(0.0)).asFloat64();

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::GreedyProjectionTriangulation<T> gp3;
Expand All @@ -299,10 +297,17 @@ void doGreedyProjectionTriangulation(const typename pcl::PointCloud<T>::ConstPtr
template <typename T>
void doGridMinimum(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
auto resolution = options.check("resolution", yarp::os::Value(0.0f)).asFloat32();

pcl::GridMinimum<T> grid(resolution);

grid.setInputCloud(in);
grid.setKeepOrganized(keepOrganized);
grid.setNegative(negative);
grid.filter(*out);

checkOutput<T>(out, "GridMinimum");
}

Expand All @@ -314,7 +319,7 @@ void doGridProjection(const typename pcl::PointCloud<T>::ConstPtr & in, const pc
auto paddingSize = options.check("paddingSize", yarp::os::Value(3)).asInt32();
auto resolution = options.check("resolution", yarp::os::Value(0.001)).asFloat64();

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::GridProjection<T> gp;
Expand All @@ -332,11 +337,13 @@ void doGridProjection(const typename pcl::PointCloud<T>::ConstPtr & in, const pc
template <typename T>
void doLocalMaximum(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
auto radius = options.check("radius", yarp::os::Value(1.0f)).asFloat32();

pcl::LocalMaximum<T> local;
local.setInputCloud(in);
local.setKeepOrganized(keepOrganized);
local.setNegative(negative);
local.setRadius(radius);
local.filter(*out);
Expand All @@ -347,23 +354,19 @@ void doLocalMaximum(const typename pcl::PointCloud<T>::ConstPtr & in, const type
template <typename T>
void doMarchingCubesHoppe(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::PolygonMesh::Ptr & out, const yarp::os::Searchable & options)
{
#if PCL_VERSION_COMPARE(>=, 1, 9, 0)
auto distanceIgnore = options.check("distanceIgnore", yarp::os::Value(-1.0f)).asFloat32();
#endif
auto gridResolution = options.check("gridResolution", yarp::os::Value(32)).asInt32();
auto gridResolutionX = options.check("gridResolutionX", yarp::os::Value(gridResolution)).asInt32();
auto gridResolutionY = options.check("gridResolutionY", yarp::os::Value(gridResolution)).asInt32();
auto gridResolutionZ = options.check("gridResolutionZ", yarp::os::Value(gridResolution)).asInt32();
auto isoLevel = options.check("isoLevel", yarp::os::Value(0.0f)).asFloat32();
auto percentageExtendGrid = options.check("percentageExtendGrid", yarp::os::Value(0.0f)).asFloat32();

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::MarchingCubesHoppe<T> hoppe;
#if PCL_VERSION_COMPARE(>=, 1, 9, 0)
hoppe.setDistanceIgnore(distanceIgnore);
#endif
hoppe.setGridResolution(gridResolutionX, gridResolutionY, gridResolutionZ);
hoppe.setInputCloud(in);
hoppe.setIsoLevel(isoLevel);
Expand All @@ -385,7 +388,7 @@ void doMarchingCubesRBF(const typename pcl::PointCloud<T>::ConstPtr & in, const
auto offSurfaceDisplacement = options.check("offSurfaceDisplacement", yarp::os::Value(0.1f)).asFloat32();
auto percentageExtendGrid = options.check("percentageExtendGrid", yarp::os::Value(0.0f)).asFloat32();

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::MarchingCubesRBF<T> rbf;
Expand Down Expand Up @@ -506,7 +509,6 @@ void doMeshSubdivisionVTK(const pcl::PolygonMesh::ConstPtr & in, const pcl::Poly
checkOutput(out, "MeshSubdivisionVTK");
}

#if PCL_VERSION_COMPARE(>=, 1, 9, 0)
template <typename T1, typename T2 = T1>
void doMovingLeastSquares(const typename pcl::PointCloud<T1>::ConstPtr & in, const typename pcl::PointCloud<T2>::Ptr & out, const yarp::os::Searchable & options)
{
Expand Down Expand Up @@ -570,7 +572,7 @@ void doMovingLeastSquares(const typename pcl::PointCloud<T1>::ConstPtr & in, con
throw std::invalid_argument("unknown upsampling method: " + upsamplingMethodStr);
}

typename pcl::search::KdTree<T1>::Ptr tree(new pcl::search::KdTree<T1>());
auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
tree->setInputCloud(in);

pcl::MovingLeastSquares<T1, T2> mls;
Expand All @@ -593,15 +595,14 @@ void doMovingLeastSquares(const typename pcl::PointCloud<T1>::ConstPtr & in, con

checkOutput<T2>(out, "MovingLeastSquares");
}
#endif

template <typename T1, typename T2>
void doNormalEstimation(const typename pcl::PointCloud<T1>::ConstPtr & in, const typename pcl::PointCloud<T2>::Ptr & out, const yarp::os::Searchable & options)
{
auto kSearch = options.check("kSearch", yarp::os::Value(0)).asInt32();
auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();

typename pcl::search::KdTree<T1>::Ptr tree(new pcl::search::KdTree<T1>());
auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
tree->setInputCloud(in);

pcl::NormalEstimation<T1, T2> estimator;
Expand All @@ -621,7 +622,7 @@ void doNormalEstimationOMP(const typename pcl::PointCloud<T1>::ConstPtr & in, co
auto numberOfThreads = options.check("numberOfThreads", yarp::os::Value(0)).asInt32();
auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();

typename pcl::search::KdTree<T1>::Ptr tree(new pcl::search::KdTree<T1>());
auto tree = pcl::make_shared<pcl::search::KdTree<T1>>();
tree->setInputCloud(in);

pcl::NormalEstimationOMP<T1, T2> estimator;
Expand Down Expand Up @@ -702,12 +703,14 @@ void doPassThrough(const typename pcl::PointCloud<T>::ConstPtr & in, const typen
auto filterFieldName = options.check("filterFieldName", yarp::os::Value("")).asString();
auto filterLimitMax = options.check("filterLimitMax", yarp::os::Value(std::numeric_limits<float>::max())).asFloat32();
auto filterLimitMin = options.check("filterLimitMin", yarp::os::Value(std::numeric_limits<float>::min())).asFloat32();
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();

pcl::PassThrough<T> pass;
pass.setFilterFieldName(filterFieldName);
pass.setFilterLimits(filterLimitMin, filterLimitMax);
pass.setInputCloud(in);
pass.setKeepOrganized(keepOrganized);
pass.setNegative(negative);
pass.filter(*out);

Expand All @@ -732,7 +735,7 @@ void doPoisson(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::Poly
auto threads = options.check("threads", yarp::os::Value(1)).asInt32();
#endif

typename pcl::search::KdTree<T>::Ptr tree(new pcl::search::KdTree<T>());
auto tree = pcl::make_shared<pcl::search::KdTree<T>>();
tree->setInputCloud(in);

pcl::Poisson<T> poisson;
Expand Down Expand Up @@ -760,12 +763,14 @@ void doPoisson(const typename pcl::PointCloud<T>::ConstPtr & in, const pcl::Poly
template <typename T>
void doRadiusOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto minNeighborsInRadius = options.check("minNeighborsInRadius", yarp::os::Value(1)).asInt32();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();

pcl::RadiusOutlierRemoval<T> remover;
remover.setInputCloud(in);
remover.setKeepOrganized(keepOrganized);
remover.setMinNeighborsInRadius(minNeighborsInRadius);
remover.setNegative(negative);
remover.setRadiusSearch(radiusSearch);
Expand All @@ -777,12 +782,14 @@ void doRadiusOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & in, co
template <typename T>
void doRandomSample(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
auto sample = options.check("sample", yarp::os::Value(std::numeric_limits<int>::max())).asInt64(); // note the shortening conversion
auto seed = options.check("seed", yarp::os::Value(static_cast<int>(std::time(nullptr)))).asInt64(); // note the shortening conversion

pcl::RandomSample<T> random;
random.setInputCloud(in);
random.setKeepOrganized(keepOrganized);
random.setNegative(negative);
random.setSample(sample);
random.setSeed(seed);
Expand Down Expand Up @@ -816,9 +823,9 @@ void doShadowPoints(const typename pcl::PointCloud<T>::ConstPtr & in, const type
auto threshold = options.check("threshold", yarp::os::Value(0.1f)).asFloat32();

#if PCL_VERSION_COMPARE(>=, 1, 11, 0)
typename pcl::PointCloud<T>::Ptr temp = std::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
auto temp = std::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
#else
typename pcl::PointCloud<T>::Ptr temp = boost::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
auto temp = boost::const_pointer_cast<pcl::PointCloud<T>>(in); // cast away constness
#endif

pcl::ShadowPoints<T, T> shadow;
Expand All @@ -842,12 +849,14 @@ void doSimplificationRemoveUnusedVertices(const pcl::PolygonMesh::ConstPtr & in,
template <typename T>
void doStatisticalOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto meanK = options.check("meanK", yarp::os::Value(1)).asInt32();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
auto stddevMulThresh = options.check("stddevMulThresh", yarp::os::Value(0.0)).asFloat64();

pcl::StatisticalOutlierRemoval<T> remover;
remover.setInputCloud(in);
remover.setKeepOrganized(keepOrganized);
remover.setMeanK(meanK);
remover.setNegative(negative);
remover.setStddevMulThresh(stddevMulThresh);
Expand All @@ -859,10 +868,18 @@ void doStatisticalOutlierRemoval(const typename pcl::PointCloud<T>::ConstPtr & i
template <typename T>
void doUniformSampling(const typename pcl::PointCloud<T>::ConstPtr & in, const typename pcl::PointCloud<T>::Ptr & out, const yarp::os::Searchable & options)
{
#if PCL_VERSION_COMPARE(>=, 1, 15, 0)
auto keepOrganized = options.check("keepOrganized", yarp::os::Value(false)).asBool();
auto negative = options.check("negative", yarp::os::Value(false)).asBool();
#endif
auto radiusSearch = options.check("radiusSearch", yarp::os::Value(0.0)).asFloat64();

pcl::UniformSampling<T> uniform;
uniform.setInputCloud(in);
#if PCL_VERSION_COMPARE(>=, 1, 15, 0)
uniform.setKeepOrganized(keepOrganized);
uniform.setNegative(negative);
#endif
uniform.setRadiusSearch(radiusSearch);
uniform.filter(*out);

Expand Down
9 changes: 2 additions & 7 deletions libraries/YarpCloudUtils/YarpCloudUtils-pcl-inst.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,7 @@
template bool processCloud(const in &, out &, const yarp::sig::VectorOf<yarp::os::Property> &); \
template bool processCloud(const in &, out &, const yarp::os::Searchable &, const std::string &);

namespace roboticslab
{

namespace YarpCloudUtils
namespace roboticslab::YarpCloudUtils
{

YCU_PCL_SIGNATURES(yarp::sig::PointCloudXY, yarp::sig::PointCloudXY)
Expand Down Expand Up @@ -93,8 +90,6 @@ YCU_PCL_SIGNATURES(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudInte
YCU_PCL_SIGNATURES(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZNormal)
YCU_PCL_SIGNATURES(yarp::sig::PointCloudXYZNormalRGBA, yarp::sig::PointCloudXYZNormalRGBA)

} // YarpCloudUtils

} // namespace roboticslab
} // namespace roboticslab::YarpCloudUtils

#endif // __YARP_CLOUD_UTILS_PCL_INST_HPP__
18 changes: 5 additions & 13 deletions libraries/YarpCloudUtils/YarpCloudUtils-pcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@

#ifdef YCU_HAVE_PCL
#include <yarp/pcl/Pcl.h>
#include <yarp/conf/version.h>

#include <cstdint>

Expand Down Expand Up @@ -141,14 +140,12 @@ namespace
case "MeshSubdivisionVTK"_hash:
doMeshSubdivisionVTK(prev.getMesh(), curr.setMesh(), options);
break;
#if PCL_VERSION_COMPARE(>=, 1, 9, 0)
case "MovingLeastSquares"_hash:
if (options.check("computeNormals"), yarp::os::Value(false).asBool())
doMovingLeastSquares<any_xyz_t, normal_t>(prev.getCloud<any_xyz_t>(), curr.setCloud<normal_t>(), options);
else
doMovingLeastSquares<any_xyz_t>(prev.getCloud<any_xyz_t>(), curr.setCloud<any_xyz_t>(), options);
break;
#endif
case "NormalEstimation"_hash:
pcl::copyPointCloud(*prev.getCloud<any_xyz_t>(), *curr.setCloud<normal_t>());
doNormalEstimation<any_xyz_t, normal_t>(prev.getCloud<any_xyz_t>(), curr.useCloud<normal_t>(), options);
Expand Down Expand Up @@ -280,10 +277,7 @@ namespace
}
}

namespace roboticslab
{

namespace YarpCloudUtils
namespace roboticslab::YarpCloudUtils
{

template <typename T1, typename T2>
Expand Down Expand Up @@ -320,7 +314,7 @@ bool meshFromCloud(const yarp::sig::PointCloud<T1> & cloud,
return false;
}

typename pcl::PointCloud<pcl_input_type>::Ptr pclCloud(new pcl::PointCloud<pcl_input_type>());
auto pclCloud = pcl::make_shared<pcl::PointCloud<pcl_input_type>>();;

// Convert YARP cloud to PCL cloud.
yarp::pcl::toPCL(cloud, *pclCloud);
Expand All @@ -339,7 +333,7 @@ bool meshFromCloud(const yarp::sig::PointCloud<T1> & cloud,
}

// Extract point cloud of vertices from mesh.
typename pcl::PointCloud<pcl_output_type>::Ptr pclMeshPoints(new pcl::PointCloud<pcl_output_type>());
auto pclMeshPoints = pcl::make_shared<pcl::PointCloud<pcl_output_type>>();
pcl::fromPCLPointCloud2(pclMesh->cloud, *pclMeshPoints);

// Convert PCL mesh to YARP cloud and vector of indices.
Expand Down Expand Up @@ -393,7 +387,7 @@ bool processCloud(const yarp::sig::PointCloud<T1> & in,
return false;
}

typename pcl::PointCloud<pcl_input_type>::Ptr pclCloudIn(new pcl::PointCloud<pcl_input_type>());
auto pclCloudIn = pcl::make_shared<pcl::PointCloud<pcl_input_type>>();

// Convert YARP cloud to PCL cloud.
yarp::pcl::toPCL(in, *pclCloudIn);
Expand Down Expand Up @@ -430,9 +424,7 @@ bool processCloud(const yarp::sig::PointCloud<T1> & in,
return processCloud(in, out, makeFromConfig(config, collection));
}

} // namespace YarpCloudUtils

} // namespace roboticslab
} // namespace roboticslab::YarpCloudUtils

// explicit instantiations
#include "YarpCloudUtils-pcl-inst.hpp"
Loading

0 comments on commit e12e4af

Please sign in to comment.