Skip to content

Commit

Permalink
Prefer pcl::make_shared to new
Browse files Browse the repository at this point in the history
  • Loading branch information
PeterBowman committed Jun 20, 2024
1 parent 7034bfa commit 85aa23d
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 54 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
30 changes: 11 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 Down Expand Up @@ -321,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 Down Expand Up @@ -356,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 @@ -394,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 @@ -515,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 @@ -579,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 @@ -602,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 @@ -630,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 @@ -743,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 @@ -831,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 Down
9 changes: 3 additions & 6 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 @@ -317,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 @@ -336,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 @@ -390,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
20 changes: 10 additions & 10 deletions libraries/YarpCloudUtils/YarpCloudUtils-pcl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ inline auto cloud_container::initializeCloudPointer(const typename pcl::PointClo
throw std::runtime_error("illegal conversion from " + name_lhs + " to " + name_rhs);
}

typename pcl::PointCloud<T2>::Ptr out(new pcl::PointCloud<T2>());
auto out = pcl::make_shared<pcl::PointCloud<T2>>();
pcl::copyPointCloud(*in, *out);
return out;
}
Expand Down Expand Up @@ -114,49 +114,49 @@ typename pcl::PointCloud<T>::ConstPtr cloud_container::getCloud() const
template <>
pcl::PointCloud<pcl::PointXYZ>::Ptr & cloud_container::setCloud<pcl::PointXYZ>()
{
xyz.reset(new pcl::PointCloud<pcl::PointXYZ>());
xyz = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>();
return xyz;
}

template <>
pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud_container::setCloud<pcl::PointXYZRGB>()
{
xyz_rgb.reset(new pcl::PointCloud<pcl::PointXYZRGB>());
xyz_rgb = pcl::make_shared<pcl::PointCloud<pcl::PointXYZRGB>>();
return xyz_rgb;
}

template <>
pcl::PointCloud<pcl::PointXYZI>::Ptr & cloud_container::setCloud<pcl::PointXYZI>()
{
xyzi.reset(new pcl::PointCloud<pcl::PointXYZI>());
xyzi = pcl::make_shared<pcl::PointCloud<pcl::PointXYZI>>();
return xyzi;
}

template <>
pcl::PointCloud<pcl::InterestPoint>::Ptr & cloud_container::setCloud<pcl::InterestPoint>()
{
xyz_interest.reset(new pcl::PointCloud<pcl::InterestPoint>());
xyz_interest = pcl::make_shared<pcl::PointCloud<pcl::InterestPoint>>();
return xyz_interest;
}

template <>
pcl::PointCloud<pcl::PointNormal>::Ptr & cloud_container::setCloud<pcl::PointNormal>()
{
xyz_normal.reset(new pcl::PointCloud<pcl::PointNormal>());
xyz_normal = pcl::make_shared<pcl::PointCloud<pcl::PointNormal>>();
return xyz_normal;
}

template <>
pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr & cloud_container::setCloud<pcl::PointXYZRGBNormal>()
{
xyz_rgb_normal.reset(new pcl::PointCloud<pcl::PointXYZRGBNormal>());
xyz_rgb_normal = pcl::make_shared<pcl::PointCloud<pcl::PointXYZRGBNormal>>();
return xyz_rgb_normal;
}

template <>
pcl::PointCloud<pcl::PointXYZINormal>::Ptr & cloud_container::setCloud<pcl::PointXYZINormal>()
{
xyzi_normal.reset(new pcl::PointCloud<pcl::PointXYZINormal>());
xyzi_normal = pcl::make_shared<pcl::PointCloud<pcl::PointXYZINormal>>();
return xyzi_normal;
}

Expand Down Expand Up @@ -210,7 +210,7 @@ inline pcl::PolygonMesh::ConstPtr cloud_container::getMesh() const
{
if (mesh)
{
return mesh;
return mesh; // a ctor is called here (Ptr is turned into ConstPtr)
}
else
{
Expand All @@ -220,7 +220,7 @@ inline pcl::PolygonMesh::ConstPtr cloud_container::getMesh() const

inline pcl::PolygonMesh::Ptr & cloud_container::setMesh()
{
mesh.reset(new pcl::PolygonMesh());
mesh = pcl::make_shared<pcl::PolygonMesh>();
return mesh;
}

Expand Down
9 changes: 0 additions & 9 deletions programs/pointAtObjectServer/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,6 @@ cmake_dependent_option(ENABLE_pointAtObjectServer "Enable/disable pointAtObjectS

if(ENABLE_pointAtObjectServer)

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_executable(pointAtObjectServer main.cpp
PointAtObjectServer.hpp
PointAtObjectServer.cpp
Expand Down

0 comments on commit 85aa23d

Please sign in to comment.