Skip to content

Commit

Permalink
Converting from boost::shared_ptr to shared_ptr in namespace pcl
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi committed Jan 11, 2020
1 parent 6001478 commit 44cc8a9
Show file tree
Hide file tree
Showing 348 changed files with 924 additions and 924 deletions.
4 changes: 2 additions & 2 deletions 2d/include/pcl/2d/edge.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,8 @@ class Edge {
float tLow);

public:
using Ptr = boost::shared_ptr<Edge<PointInT, PointOutT>>;
using ConstPtr = boost::shared_ptr<const Edge<PointInT, PointOutT>>;
using Ptr = shared_ptr<Edge<PointInT, PointOutT>>;
using ConstPtr = shared_ptr<const Edge<PointInT, PointOutT>>;

enum OUTPUT_TYPE {
OUTPUT_Y,
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/ModelCoefficients.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ namespace pcl
std::vector<float> values;

public:
using Ptr = boost::shared_ptr< ::pcl::ModelCoefficients>;
using ConstPtr = boost::shared_ptr<const ::pcl::ModelCoefficients>;
using Ptr = shared_ptr< ::pcl::ModelCoefficients>;
using ConstPtr = shared_ptr<const ::pcl::ModelCoefficients>;
}; // struct ModelCoefficients

using ModelCoefficientsPtr = ModelCoefficients::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/PCLHeader.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@ namespace pcl
/** \brief Coordinate frame ID */
std::string frame_id;

using Ptr = boost::shared_ptr<PCLHeader>;
using ConstPtr = boost::shared_ptr<const PCLHeader>;
using Ptr = shared_ptr<PCLHeader>;
using ConstPtr = shared_ptr<const PCLHeader>;
}; // struct PCLHeader

using HeaderPtr = PCLHeader::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/PCLImage.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ namespace pcl

std::vector<std::uint8_t> data;

using Ptr = boost::shared_ptr< ::pcl::PCLImage>;
using ConstPtr = boost::shared_ptr<const ::pcl::PCLImage>;
using Ptr = shared_ptr< ::pcl::PCLImage>;
using ConstPtr = shared_ptr<const ::pcl::PCLImage>;
}; // struct PCLImage

using PCLImagePtr = PCLImage::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/PCLPointCloud2.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ namespace pcl
std::uint8_t is_dense = 0;

public:
using Ptr = boost::shared_ptr< ::pcl::PCLPointCloud2>;
using ConstPtr = boost::shared_ptr<const ::pcl::PCLPointCloud2>;
using Ptr = shared_ptr< ::pcl::PCLPointCloud2>;
using ConstPtr = shared_ptr<const ::pcl::PCLPointCloud2>;

//////////////////////////////////////////////////////////////////////////
/** \brief Inplace concatenate two pcl::PCLPointCloud2
Expand Down
5 changes: 2 additions & 3 deletions common/include/pcl/PCLPointField.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
#include <string>
#include <vector>
#include <ostream>
#include <boost/shared_ptr.hpp>
#include <pcl/pcl_macros.h>

namespace pcl
Expand All @@ -30,8 +29,8 @@ namespace pcl
FLOAT64 = 8 };

public:
using Ptr = boost::shared_ptr< ::pcl::PCLPointField>;
using ConstPtr = boost::shared_ptr<const ::pcl::PCLPointField>;
using Ptr = shared_ptr< ::pcl::PCLPointField>;
using ConstPtr = shared_ptr<const ::pcl::PCLPointField>;
}; // struct PCLPointField

using PCLPointFieldPtr = PCLPointField::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/PointIndices.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ namespace pcl
std::vector<int> indices;

public:
using Ptr = boost::shared_ptr< ::pcl::PointIndices>;
using ConstPtr = boost::shared_ptr<const ::pcl::PointIndices>;
using Ptr = shared_ptr< ::pcl::PointIndices>;
using ConstPtr = shared_ptr<const ::pcl::PointIndices>;
}; // struct PointIndices

using PointIndicesPtr = PointIndices::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/PolygonMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,8 @@ namespace pcl
}

public:
using Ptr = boost::shared_ptr< ::pcl::PolygonMesh>;
using ConstPtr = boost::shared_ptr<const ::pcl::PolygonMesh>;
using Ptr = shared_ptr< ::pcl::PolygonMesh>;
using ConstPtr = shared_ptr<const ::pcl::PolygonMesh>;
}; // struct PolygonMesh

using PolygonMeshPtr = PolygonMesh::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/TextureMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,8 @@ namespace pcl
std::vector<pcl::TexMaterial> tex_materials; // define texture material

public:
using Ptr = boost::shared_ptr<pcl::TextureMesh>;
using ConstPtr = boost::shared_ptr<const pcl::TextureMesh>;
using Ptr = shared_ptr<pcl::TextureMesh>;
using ConstPtr = shared_ptr<const pcl::TextureMesh>;
}; // struct TextureMesh

using TextureMeshPtr = TextureMesh::Ptr;
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/Vertices.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ namespace pcl
std::vector<std::uint32_t> vertices;

public:
using Ptr = boost::shared_ptr<Vertices>;
using ConstPtr = boost::shared_ptr<const Vertices>;
using Ptr = shared_ptr<Vertices>;
using ConstPtr = shared_ptr<const Vertices>;
}; // struct Vertices


Expand Down
6 changes: 3 additions & 3 deletions common/include/pcl/correspondence.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#pragma GCC system_header
#endif

#include <boost/shared_ptr.hpp>
#include <pcl/make_shared.h>
#include <Eigen/StdVector>
#include <Eigen/Geometry>
#include <pcl/pcl_exports.h>
Expand Down Expand Up @@ -86,8 +86,8 @@ namespace pcl
PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Correspondence& c);

using Correspondences = std::vector< pcl::Correspondence, Eigen::aligned_allocator<pcl::Correspondence> >;
using CorrespondencesPtr = boost::shared_ptr<Correspondences>;
using CorrespondencesConstPtr = boost::shared_ptr<const Correspondences >;
using CorrespondencesPtr = shared_ptr<Correspondences>;
using CorrespondencesConstPtr = shared_ptr<const Correspondences >;

/**
* \brief Get the query points of correspondences that are present in
Expand Down
12 changes: 6 additions & 6 deletions common/include/pcl/make_shared.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,30 +53,30 @@ namespace pcl
#ifdef DOXYGEN_ONLY

/**
* \brief Returns a boost::shared_ptr compliant with type T's allocation policy.
* \brief Returns a pcl::shared_ptr compliant with type T's allocation policy.
*
* boost::allocate_shared or boost::make_shared will be invoked in case T has or
* doesn't have a custom allocator, respectively.
*
* \see pcl::has_custom_allocator, PCL_MAKE_ALIGNED_OPERATOR_NEW
* \tparam T Type of the object to create a boost::shared_ptr of
* \tparam T Type of the object to create a pcl::shared_ptr of
* \tparam Args Types for the arguments to pcl::make_shared
* \param args List of arguments with which an instance of T will be constructed
* \return boost::shared_ptr of an instance of type T
* \return pcl::shared_ptr of an instance of type T
*/
template<typename T, typename ... Args>
boost::shared_ptr<T> make_shared(Args&&... args);
shared_ptr<T> make_shared(Args&&... args);

#else

template<typename T, typename ... Args>
std::enable_if_t<has_custom_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args&&... args)
std::enable_if_t<has_custom_allocator<T>::value, shared_ptr<T>> make_shared(Args&&... args)
{
return boost::allocate_shared<T>(Eigen::aligned_allocator<T>(), std::forward<Args> (args)...);
}

template<typename T, typename ... Args>
std::enable_if_t<!has_custom_allocator<T>::value, boost::shared_ptr<T>> make_shared(Args&&... args)
std::enable_if_t<!has_custom_allocator<T>::value, shared_ptr<T>> make_shared(Args&&... args)
{
return boost::make_shared<T>(std::forward<Args> (args)...);
}
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/pcl_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ namespace pcl
{
// definitions used everywhere
using Indices = std::vector<int>;
using IndicesPtr = boost::shared_ptr<Indices>;
using IndicesConstPtr = boost::shared_ptr<const Indices>;
using IndicesPtr = shared_ptr<Indices>;
using IndicesConstPtr = shared_ptr<const Indices>;

/////////////////////////////////////////////////////////////////////////////////////////
/** \brief PCL base class. Implements methods that are used by most PCL algorithms.
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -409,8 +409,8 @@ namespace pcl
using PointType = PointT; // Make the template class available from the outside
using VectorType = std::vector<PointT, Eigen::aligned_allocator<PointT> >;
using CloudVectorType = std::vector<PointCloud<PointT>, Eigen::aligned_allocator<PointCloud<PointT> > >;
using Ptr = boost::shared_ptr<PointCloud<PointT> >;
using ConstPtr = boost::shared_ptr<const PointCloud<PointT> >;
using Ptr = shared_ptr<PointCloud<PointT> >;
using ConstPtr = shared_ptr<const PointCloud<PointT> >;

// std container compatibility typedefs according to
// http://en.cppreference.com/w/cpp/concept/Container
Expand Down
16 changes: 8 additions & 8 deletions common/include/pcl/point_representation.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,8 @@ namespace pcl
bool trivial_ = false;

public:
using Ptr = boost::shared_ptr<PointRepresentation<PointT> >;
using ConstPtr = boost::shared_ptr<const PointRepresentation<PointT> >;
using Ptr = shared_ptr<PointRepresentation<PointT> >;
using ConstPtr = shared_ptr<const PointRepresentation<PointT> >;

/** \brief Empty destructor */
virtual ~PointRepresentation () = default;
Expand Down Expand Up @@ -181,8 +181,8 @@ namespace pcl

public:
// Boost shared pointers
using Ptr = boost::shared_ptr<DefaultPointRepresentation<PointDefault> >;
using ConstPtr = boost::shared_ptr<const DefaultPointRepresentation<PointDefault> >;
using Ptr = shared_ptr<DefaultPointRepresentation<PointDefault> >;
using ConstPtr = shared_ptr<const DefaultPointRepresentation<PointDefault> >;

DefaultPointRepresentation ()
{
Expand Down Expand Up @@ -288,8 +288,8 @@ namespace pcl

public:
// Boost shared pointers
using Ptr = boost::shared_ptr<DefaultFeatureRepresentation<PointDefault>>;
using ConstPtr = boost::shared_ptr<const DefaultFeatureRepresentation<PointDefault>>;
using Ptr = shared_ptr<DefaultFeatureRepresentation<PointDefault>>;
using ConstPtr = shared_ptr<const DefaultFeatureRepresentation<PointDefault>>;
using FieldList = typename pcl::traits::fieldList<PointDefault>::type;

DefaultFeatureRepresentation ()
Expand Down Expand Up @@ -534,8 +534,8 @@ namespace pcl

public:
// Boost shared pointers
using Ptr = boost::shared_ptr<CustomPointRepresentation<PointDefault> >;
using ConstPtr = boost::shared_ptr<const CustomPointRepresentation<PointDefault> >;
using Ptr = shared_ptr<CustomPointRepresentation<PointDefault> >;
using ConstPtr = shared_ptr<const CustomPointRepresentation<PointDefault> >;

/** \brief Constructor
* \param[in] max_dim the maximum number of dimensions to use
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/range_image/range_image.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ namespace pcl
// =====TYPEDEFS=====
using BaseClass = pcl::PointCloud<PointWithRange>;
using VectorOfEigenVector3f = std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> >;
using Ptr = boost::shared_ptr<RangeImage>;
using ConstPtr = boost::shared_ptr<const RangeImage>;
using Ptr = shared_ptr<RangeImage>;
using ConstPtr = shared_ptr<const RangeImage>;

enum CoordinateFrame
{
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/range_image/range_image_planar.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,8 @@ namespace pcl
public:
// =====TYPEDEFS=====
using BaseClass = RangeImage;
using Ptr = boost::shared_ptr<RangeImagePlanar>;
using ConstPtr = boost::shared_ptr<const RangeImagePlanar>;
using Ptr = shared_ptr<RangeImagePlanar>;
using ConstPtr = shared_ptr<const RangeImagePlanar>;

// =====CONSTRUCTOR & DESTRUCTOR=====
/** Constructor */
Expand Down
4 changes: 2 additions & 2 deletions common/include/pcl/range_image/range_image_spherical.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ namespace pcl
public:
// =====TYPEDEFS=====
using BaseClass = RangeImage;
using Ptr = boost::shared_ptr<RangeImageSpherical>;
using ConstPtr = boost::shared_ptr<const RangeImageSpherical>;
using Ptr = shared_ptr<RangeImageSpherical>;
using ConstPtr = shared_ptr<const RangeImageSpherical>;

// =====CONSTRUCTOR & DESTRUCTOR=====
/** Constructor */
Expand Down
4 changes: 2 additions & 2 deletions cuda/apps/src/kinect_normals_cuda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ class NormalEstimation

// we got a cloud in device..

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
float focallength = 580/2.0;
Expand Down Expand Up @@ -164,7 +164,7 @@ class NormalEstimation
d2c.compute<Storage> (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size);
//d2c.compute<Storage> (depth_image, image, constant, data, true, 2);

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
normals = computeFastPointNormals<Storage> (data);
Expand Down
2 changes: 1 addition & 1 deletion cuda/apps/src/kinect_planes_cuda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ class MultiRansac
d2c.compute<Storage> (depth_image, image, constant, data, true, 2, smoothing_nr_iterations, smoothing_filter_size);

// Compute normals
boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
//normals = computeFastPointNormals<Storage> (data);
Expand Down
4 changes: 2 additions & 2 deletions cuda/apps/src/kinect_segmentation_cuda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ class Segmentation

// we got a cloud in device..

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
constexpr float focallength = 580/2.0;
Expand Down Expand Up @@ -214,7 +214,7 @@ class Segmentation
d2c.compute<Storage> (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size);
}

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("Normal Estimation");
if (normal_method == 1)
Expand Down
4 changes: 2 additions & 2 deletions cuda/apps/src/kinect_segmentation_planes_cuda.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ class Segmentation

// we got a cloud in device..

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("TIMING: Normal Estimation");
constexpr float focallength = 580/2.0;
Expand Down Expand Up @@ -178,7 +178,7 @@ class Segmentation
// Compute the PointCloud on the device
d2c.compute<Storage> (depth_image, image, constant, data, true, 2);

boost::shared_ptr<typename Storage<float4>::type> normals;
shared_ptr<typename Storage<float4>::type> normals;
{
ScopeTimeCPU time ("TIMING: Normal Estimation");
normals = computeFastPointNormals<Storage> (data);
Expand Down
8 changes: 4 additions & 4 deletions cuda/common/include/pcl/cuda/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -196,8 +196,8 @@ namespace pcl
/** \brief True if no points are invalid (e.g., have NaN or Inf values). */
bool is_dense;

using Ptr = boost::shared_ptr<PointCloudAOS<Storage> >;
using ConstPtr = boost::shared_ptr<const PointCloudAOS<Storage> >;
using Ptr = shared_ptr<PointCloudAOS<Storage> >;
using ConstPtr = shared_ptr<const PointCloudAOS<Storage> >;
};

/** @b PointCloudSOA represents a SOA (Struct of Arrays) PointCloud
Expand Down Expand Up @@ -277,8 +277,8 @@ namespace pcl
/** \brief True if no points are invalid (e.g., have NaN or Inf values). */
bool is_dense;

using Ptr = boost::shared_ptr<PointCloudSOA<Storage> >;
using ConstPtr = boost::shared_ptr<const PointCloudSOA<Storage> >;
using Ptr = shared_ptr<PointCloudSOA<Storage> >;
using ConstPtr = shared_ptr<const PointCloudSOA<Storage> >;

//////////////////////////////////////////////////////////////////////////////////////
// Extras. Testing ZIP iterators
Expand Down
6 changes: 3 additions & 3 deletions cuda/features/include/pcl/cuda/features/normal_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,20 +51,20 @@ namespace pcl
void computePointNormals (InputIteratorT begin, InputIteratorT end, OutputIteratorT output, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);

template <template <typename> class Storage, typename InputIteratorT>
boost::shared_ptr<typename Storage<float4>::type> computePointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);
shared_ptr<typename Storage<float4>::type> computePointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);

// fast normal computations
template <typename OutputIteratorT, template <typename> class Storage>
void computeFastPointNormals (OutputIteratorT output, const typename PointCloudAOS<Storage>::ConstPtr &input);

template <template <typename> class Storage>
boost::shared_ptr<typename Storage<float4>::type> computeFastPointNormals (const typename PointCloudAOS<Storage>::ConstPtr &input);
shared_ptr<typename Storage<float4>::type> computeFastPointNormals (const typename PointCloudAOS<Storage>::ConstPtr &input);

// Weird normal estimation (normal deviations - more of an art project..)
template <typename InputIteratorT, typename OutputIteratorT, template <typename> class Storage>
void computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, OutputIteratorT output, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);

template <template <typename> class Storage, typename InputIteratorT>
boost::shared_ptr<typename Storage<float4>::type> computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);
shared_ptr<typename Storage<float4>::type> computeWeirdPointNormals (InputIteratorT begin, InputIteratorT end, float focallength, const typename PointCloudAOS<Storage>::ConstPtr &input, float radius, int desired_number_neighbors);
} // namespace
} // namespace
Loading

0 comments on commit 44cc8a9

Please sign in to comment.