diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index 2d37c3954d4..504e31e905d 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -88,8 +88,8 @@ class Edge { float tLow); public: - using Ptr = boost::shared_ptr>; - using ConstPtr = boost::shared_ptr>; + using Ptr = shared_ptr>; + using ConstPtr = shared_ptr>; enum OUTPUT_TYPE { OUTPUT_Y, diff --git a/common/include/pcl/ModelCoefficients.h b/common/include/pcl/ModelCoefficients.h index 281e304cbf5..23fedbad33e 100644 --- a/common/include/pcl/ModelCoefficients.h +++ b/common/include/pcl/ModelCoefficients.h @@ -20,8 +20,8 @@ namespace pcl std::vector values; public: - using Ptr = boost::shared_ptr< ::pcl::ModelCoefficients>; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr< ::pcl::ModelCoefficients>; + using ConstPtr = shared_ptr; }; // struct ModelCoefficients using ModelCoefficientsPtr = ModelCoefficients::Ptr; diff --git a/common/include/pcl/PCLHeader.h b/common/include/pcl/PCLHeader.h index 5fe1072d6a2..20e28ed987b 100644 --- a/common/include/pcl/PCLHeader.h +++ b/common/include/pcl/PCLHeader.h @@ -24,8 +24,8 @@ namespace pcl /** \brief Coordinate frame ID */ std::string frame_id; - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; }; // struct PCLHeader using HeaderPtr = PCLHeader::Ptr; diff --git a/common/include/pcl/PCLImage.h b/common/include/pcl/PCLImage.h index 3c49dc13e21..a5d128c049b 100644 --- a/common/include/pcl/PCLImage.h +++ b/common/include/pcl/PCLImage.h @@ -26,8 +26,8 @@ namespace pcl std::vector data; - using Ptr = boost::shared_ptr< ::pcl::PCLImage>; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr< ::pcl::PCLImage>; + using ConstPtr = shared_ptr; }; // struct PCLImage using PCLImagePtr = PCLImage::Ptr; diff --git a/common/include/pcl/PCLPointCloud2.h b/common/include/pcl/PCLPointCloud2.h index 904a85fe49f..85ab2c1b71a 100644 --- a/common/include/pcl/PCLPointCloud2.h +++ b/common/include/pcl/PCLPointCloud2.h @@ -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; + using Ptr = shared_ptr< ::pcl::PCLPointCloud2>; + using ConstPtr = shared_ptr; ////////////////////////////////////////////////////////////////////////// /** \brief Inplace concatenate two pcl::PCLPointCloud2 diff --git a/common/include/pcl/PCLPointField.h b/common/include/pcl/PCLPointField.h index 336746e7353..b50d20cc022 100644 --- a/common/include/pcl/PCLPointField.h +++ b/common/include/pcl/PCLPointField.h @@ -7,7 +7,6 @@ #include #include #include -#include #include namespace pcl @@ -30,8 +29,8 @@ namespace pcl FLOAT64 = 8 }; public: - using Ptr = boost::shared_ptr< ::pcl::PCLPointField>; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr< ::pcl::PCLPointField>; + using ConstPtr = shared_ptr; }; // struct PCLPointField using PCLPointFieldPtr = PCLPointField::Ptr; diff --git a/common/include/pcl/PointIndices.h b/common/include/pcl/PointIndices.h index 85a99d41612..031699f64bd 100644 --- a/common/include/pcl/PointIndices.h +++ b/common/include/pcl/PointIndices.h @@ -19,8 +19,8 @@ namespace pcl std::vector indices; public: - using Ptr = boost::shared_ptr< ::pcl::PointIndices>; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr< ::pcl::PointIndices>; + using ConstPtr = shared_ptr; }; // struct PointIndices using PointIndicesPtr = PointIndices::Ptr; diff --git a/common/include/pcl/PolygonMesh.h b/common/include/pcl/PolygonMesh.h index 48e746c9c3f..f62d7b3455a 100644 --- a/common/include/pcl/PolygonMesh.h +++ b/common/include/pcl/PolygonMesh.h @@ -94,8 +94,8 @@ namespace pcl } public: - using Ptr = boost::shared_ptr< ::pcl::PolygonMesh>; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr< ::pcl::PolygonMesh>; + using ConstPtr = shared_ptr; }; // struct PolygonMesh using PolygonMeshPtr = PolygonMesh::Ptr; diff --git a/common/include/pcl/TextureMesh.h b/common/include/pcl/TextureMesh.h index 00daaca38b8..88119906f6f 100644 --- a/common/include/pcl/TextureMesh.h +++ b/common/include/pcl/TextureMesh.h @@ -96,8 +96,8 @@ namespace pcl std::vector tex_materials; // define texture material public: - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; }; // struct TextureMesh using TextureMeshPtr = TextureMesh::Ptr; diff --git a/common/include/pcl/Vertices.h b/common/include/pcl/Vertices.h index 97c38d8c9e7..cf6ab9fce9d 100644 --- a/common/include/pcl/Vertices.h +++ b/common/include/pcl/Vertices.h @@ -19,8 +19,8 @@ namespace pcl std::vector vertices; public: - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; }; // struct Vertices diff --git a/common/include/pcl/correspondence.h b/common/include/pcl/correspondence.h index ebfb89822f7..ed7976361e0 100644 --- a/common/include/pcl/correspondence.h +++ b/common/include/pcl/correspondence.h @@ -42,7 +42,7 @@ #pragma GCC system_header #endif -#include +#include #include #include #include @@ -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 >; - using CorrespondencesPtr = boost::shared_ptr; - using CorrespondencesConstPtr = boost::shared_ptr; + using CorrespondencesPtr = shared_ptr; + using CorrespondencesConstPtr = shared_ptr; /** * \brief Get the query points of correspondences that are present in diff --git a/common/include/pcl/make_shared.h b/common/include/pcl/make_shared.h index 737a73a9c2a..30f6451038e 100644 --- a/common/include/pcl/make_shared.h +++ b/common/include/pcl/make_shared.h @@ -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 -boost::shared_ptr make_shared(Args&&... args); +shared_ptr make_shared(Args&&... args); #else template -std::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) +std::enable_if_t::value, shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } template -std::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) +std::enable_if_t::value, shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } diff --git a/common/include/pcl/pcl_base.h b/common/include/pcl/pcl_base.h index ae8a856e1fb..ac13ca34486 100644 --- a/common/include/pcl/pcl_base.h +++ b/common/include/pcl/pcl_base.h @@ -58,8 +58,8 @@ namespace pcl { // definitions used everywhere using Indices = std::vector; - using IndicesPtr = boost::shared_ptr; - using IndicesConstPtr = boost::shared_ptr; + using IndicesPtr = shared_ptr; + using IndicesConstPtr = shared_ptr; ///////////////////////////////////////////////////////////////////////////////////////// /** \brief PCL base class. Implements methods that are used by most PCL algorithms. diff --git a/common/include/pcl/point_cloud.h b/common/include/pcl/point_cloud.h index 04abea1ea78..7c95321e913 100644 --- a/common/include/pcl/point_cloud.h +++ b/common/include/pcl/point_cloud.h @@ -409,8 +409,8 @@ namespace pcl using PointType = PointT; // Make the template class available from the outside using VectorType = std::vector >; using CloudVectorType = std::vector, Eigen::aligned_allocator > >; - using Ptr = boost::shared_ptr >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; // std container compatibility typedefs according to // http://en.cppreference.com/w/cpp/concept/Container diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 36384478be3..b5064a84fae 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -73,8 +73,8 @@ namespace pcl bool trivial_ = false; public: - using Ptr = boost::shared_ptr >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; /** \brief Empty destructor */ virtual ~PointRepresentation () = default; @@ -181,8 +181,8 @@ namespace pcl public: // Boost shared pointers - using Ptr = boost::shared_ptr >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; DefaultPointRepresentation () { @@ -288,8 +288,8 @@ namespace pcl public: // Boost shared pointers - using Ptr = boost::shared_ptr>; - using ConstPtr = boost::shared_ptr>; + using Ptr = shared_ptr>; + using ConstPtr = shared_ptr>; using FieldList = typename pcl::traits::fieldList::type; DefaultFeatureRepresentation () @@ -534,8 +534,8 @@ namespace pcl public: // Boost shared pointers - using Ptr = boost::shared_ptr >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; /** \brief Constructor * \param[in] max_dim the maximum number of dimensions to use diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 88b5a0c5122..106188b7a43 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -57,8 +57,8 @@ namespace pcl // =====TYPEDEFS===== using BaseClass = pcl::PointCloud; using VectorOfEigenVector3f = std::vector >; - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; enum CoordinateFrame { diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index 7db0583cdaf..a09511880cf 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -53,8 +53,8 @@ namespace pcl public: // =====TYPEDEFS===== using BaseClass = RangeImage; - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ diff --git a/common/include/pcl/range_image/range_image_spherical.h b/common/include/pcl/range_image/range_image_spherical.h index da2b061b016..c2ffc601637 100644 --- a/common/include/pcl/range_image/range_image_spherical.h +++ b/common/include/pcl/range_image/range_image_spherical.h @@ -52,8 +52,8 @@ namespace pcl public: // =====TYPEDEFS===== using BaseClass = RangeImage; - using Ptr = boost::shared_ptr; - using ConstPtr = boost::shared_ptr; + using Ptr = shared_ptr; + using ConstPtr = shared_ptr; // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ diff --git a/cuda/apps/src/kinect_normals_cuda.cpp b/cuda/apps/src/kinect_normals_cuda.cpp index 60a5e18f961..e36b1fc9a48 100644 --- a/cuda/apps/src/kinect_normals_cuda.cpp +++ b/cuda/apps/src/kinect_normals_cuda.cpp @@ -120,7 +120,7 @@ class NormalEstimation // we got a cloud in device.. - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); float focallength = 580/2.0; @@ -164,7 +164,7 @@ class NormalEstimation d2c.compute (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size); //d2c.compute (depth_image, image, constant, data, true, 2); - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); normals = computeFastPointNormals (data); diff --git a/cuda/apps/src/kinect_planes_cuda.cpp b/cuda/apps/src/kinect_planes_cuda.cpp index 95f09228836..728593f5ca0 100644 --- a/cuda/apps/src/kinect_planes_cuda.cpp +++ b/cuda/apps/src/kinect_planes_cuda.cpp @@ -145,7 +145,7 @@ class MultiRansac d2c.compute (depth_image, image, constant, data, true, 2, smoothing_nr_iterations, smoothing_filter_size); // Compute normals - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); //normals = computeFastPointNormals (data); diff --git a/cuda/apps/src/kinect_segmentation_cuda.cpp b/cuda/apps/src/kinect_segmentation_cuda.cpp index a1489749082..36c57d3e5d7 100644 --- a/cuda/apps/src/kinect_segmentation_cuda.cpp +++ b/cuda/apps/src/kinect_segmentation_cuda.cpp @@ -167,7 +167,7 @@ class Segmentation // we got a cloud in device.. - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); constexpr float focallength = 580/2.0; @@ -214,7 +214,7 @@ class Segmentation d2c.compute (depth_image, image, constant, data, false, 1, smoothing_nr_iterations, smoothing_filter_size); } - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("Normal Estimation"); if (normal_method == 1) diff --git a/cuda/apps/src/kinect_segmentation_planes_cuda.cpp b/cuda/apps/src/kinect_segmentation_planes_cuda.cpp index c9b8c908fbf..8f4ca7de404 100644 --- a/cuda/apps/src/kinect_segmentation_planes_cuda.cpp +++ b/cuda/apps/src/kinect_segmentation_planes_cuda.cpp @@ -141,7 +141,7 @@ class Segmentation // we got a cloud in device.. - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("TIMING: Normal Estimation"); constexpr float focallength = 580/2.0; @@ -178,7 +178,7 @@ class Segmentation // Compute the PointCloud on the device d2c.compute (depth_image, image, constant, data, true, 2); - boost::shared_ptr::type> normals; + shared_ptr::type> normals; { ScopeTimeCPU time ("TIMING: Normal Estimation"); normals = computeFastPointNormals (data); diff --git a/cuda/common/include/pcl/cuda/point_cloud.h b/cuda/common/include/pcl/cuda/point_cloud.h index 1c63c4ad1a6..8aee4375e92 100644 --- a/cuda/common/include/pcl/cuda/point_cloud.h +++ b/cuda/common/include/pcl/cuda/point_cloud.h @@ -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 >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; }; /** @b PointCloudSOA represents a SOA (Struct of Arrays) PointCloud @@ -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 >; - using ConstPtr = boost::shared_ptr >; + using Ptr = shared_ptr >; + using ConstPtr = shared_ptr >; ////////////////////////////////////////////////////////////////////////////////////// // Extras. Testing ZIP iterators diff --git a/cuda/features/include/pcl/cuda/features/normal_3d.h b/cuda/features/include/pcl/cuda/features/normal_3d.h index 43b08ca48e1..b28fa13f227 100644 --- a/cuda/features/include/pcl/cuda/features/normal_3d.h +++ b/cuda/features/include/pcl/cuda/features/normal_3d.h @@ -51,20 +51,20 @@ namespace pcl void computePointNormals (InputIteratorT begin, InputIteratorT end, OutputIteratorT output, float focallength, const typename PointCloudAOS::ConstPtr &input, float radius, int desired_number_neighbors); template