From a2e95151bd0c16764ab09b118d3087e39b220e04 Mon Sep 17 00:00:00 2001 From: Heiko Thiel Date: Thu, 6 Jun 2019 15:09:38 +0200 Subject: [PATCH] Changes are done by: run-clang-tidy -header-filter='.' -checks='-,modernize-use-using' -fix --- ...oximate_progressive_morphological_filter.h | 2 +- .../include/pcl/segmentation/comparator.h | 10 ++-- .../conditional_euclidean_clustering.h | 6 +-- .../pcl/segmentation/cpc_segmentation.h | 14 +++--- .../pcl/segmentation/crf_segmentation.h | 2 +- .../edge_aware_plane_comparator.h | 14 +++--- .../euclidean_cluster_comparator.h | 26 +++++----- .../euclidean_plane_coefficient_comparator.h | 14 +++--- .../pcl/segmentation/extract_clusters.h | 16 +++---- .../segmentation/extract_labeled_clusters.h | 16 +++---- .../extract_polygonal_prism_data.h | 10 ++-- .../pcl/segmentation/grabcut_segmentation.h | 22 ++++----- .../segmentation/ground_plane_comparator.h | 14 +++--- .../segmentation/impl/cpc_segmentation.hpp | 2 +- .../pcl/segmentation/impl/random_walker.hpp | 38 +++++++-------- .../pcl/segmentation/lccp_segmentation.h | 16 +++---- .../pcl/segmentation/min_cut_segmentation.h | 48 +++++++++---------- ...ganized_connected_component_segmentation.h | 18 +++---- .../organized_multi_plane_segmentation.h | 30 ++++++------ .../plane_coefficient_comparator.h | 14 +++--- .../plane_refinement_comparator.h | 20 ++++---- .../progressive_morphological_filter.h | 2 +- .../include/pcl/segmentation/region_growing.h | 10 ++-- .../rgb_plane_coefficient_comparator.h | 14 +++--- .../pcl/segmentation/sac_segmentation.h | 30 ++++++------ .../segmentation/seeded_hue_segmentation.h | 16 +++---- .../pcl/segmentation/segment_differences.h | 16 +++---- .../pcl/segmentation/supervoxel_clustering.h | 36 +++++++------- segmentation/src/supervoxel_clustering.cpp | 12 ++--- 29 files changed, 244 insertions(+), 244 deletions(-) diff --git a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h index c13691e7487..401175ef21d 100644 --- a/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/approximate_progressive_morphological_filter.h @@ -57,7 +57,7 @@ namespace pcl { public: - typedef pcl::PointCloud PointCloud; + using PointCloud = pcl::PointCloud; using PCLBase ::input_; using PCLBase ::indices_; diff --git a/segmentation/include/pcl/segmentation/comparator.h b/segmentation/include/pcl/segmentation/comparator.h index 3e2a9dc6be7..144ed3b8249 100644 --- a/segmentation/include/pcl/segmentation/comparator.h +++ b/segmentation/include/pcl/segmentation/comparator.h @@ -52,12 +52,12 @@ namespace pcl class Comparator { public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; /** \brief Empty constructor for comparator. */ Comparator () : input_ () diff --git a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h index d1904322481..2871e67641e 100644 --- a/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h +++ b/segmentation/include/pcl/segmentation/conditional_euclidean_clustering.h @@ -44,8 +44,8 @@ namespace pcl { - typedef std::vector IndicesClusters; - typedef boost::shared_ptr > IndicesClustersPtr; + using IndicesClusters = std::vector; + using IndicesClustersPtr = boost::shared_ptr >; /** \brief @b ConditionalEuclideanClustering performs segmentation based on Euclidean distance and a user-defined clustering condition. * \details The condition that need to hold is currently passed using a function pointer. @@ -82,7 +82,7 @@ namespace pcl class ConditionalEuclideanClustering : public PCLBase { protected: - typedef typename pcl::search::Search::Ptr SearcherPtr; + using SearcherPtr = typename pcl::search::Search::Ptr; using PCLBase::input_; using PCLBase::indices_; diff --git a/segmentation/include/pcl/segmentation/cpc_segmentation.h b/segmentation/include/pcl/segmentation/cpc_segmentation.h index 3ea534cca7a..ae474b9df97 100644 --- a/segmentation/include/pcl/segmentation/cpc_segmentation.h +++ b/segmentation/include/pcl/segmentation/cpc_segmentation.h @@ -66,11 +66,11 @@ namespace pcl template class CPCSegmentation : public LCCPSegmentation { - typedef PointXYZINormal WeightSACPointType; - typedef LCCPSegmentation LCCP; + using WeightSACPointType = PointXYZINormal; + using LCCP = LCCPSegmentation; // LCCP typedefs - typedef typename LCCP::EdgeID EdgeID; - typedef typename LCCP::EdgeIterator EdgeIterator; + using EdgeID = typename LCCP::EdgeID; + using EdgeIterator = typename LCCP::EdgeIterator; // LCCP methods using LCCP::calculateConvexConnections; using LCCP::applyKconvexity; @@ -174,11 +174,11 @@ namespace pcl class WeightedRandomSampleConsensus : public SampleConsensus { - typedef SampleConsensusModel::Ptr SampleConsensusModelPtr; + using SampleConsensusModelPtr = SampleConsensusModel::Ptr; public: - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; /** \brief WeightedRandomSampleConsensus (Weighted RAndom SAmple Consensus) main constructor * \param[in] model a Sample Consensus model diff --git a/segmentation/include/pcl/segmentation/crf_segmentation.h b/segmentation/include/pcl/segmentation/crf_segmentation.h index 6f166423d3d..c613561cfec 100644 --- a/segmentation/include/pcl/segmentation/crf_segmentation.h +++ b/segmentation/include/pcl/segmentation/crf_segmentation.h @@ -58,7 +58,7 @@ namespace pcl { public: - //typedef boost::shared_ptr > pcl::IndicesPtr; + //using pcl::IndicesPtr = boost::shared_ptr >; /** \brief Constructor that sets default values for member variables. */ diff --git a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h index 1463d43ec4e..9d8a2a0daba 100644 --- a/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h +++ b/segmentation/include/pcl/segmentation/edge_aware_plane_comparator.h @@ -54,15 +54,15 @@ namespace pcl class EdgeAwarePlaneComparator: public PlaneCoefficientComparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::PlaneCoefficientComparator::input_; using pcl::PlaneCoefficientComparator::normals_; diff --git a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h index d0e6ca269ef..4018dd66c6f 100644 --- a/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_cluster_comparator.h @@ -58,16 +58,16 @@ namespace pcl using typename Comparator::PointCloud; using typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudL; - typedef typename PointCloudL::Ptr PointCloudLPtr; - typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + using PointCloudL = pcl::PointCloud; + using PointCloudLPtr = typename PointCloudL::Ptr; + using PointCloudLConstPtr = typename PointCloudL::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; - typedef std::set ExcludeLabelSet; - typedef boost::shared_ptr ExcludeLabelSetPtr; - typedef boost::shared_ptr ExcludeLabelSetConstPtr; + using ExcludeLabelSet = std::set; + using ExcludeLabelSetPtr = boost::shared_ptr; + using ExcludeLabelSetConstPtr = boost::shared_ptr; /** \brief Default constructor for EuclideanClusterComparator. */ EuclideanClusterComparator () @@ -200,12 +200,12 @@ namespace pcl public: - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using experimental::EuclideanClusterComparator::setExcludeLabels; diff --git a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h index 02e5d3cbbc0..91d2a007b90 100644 --- a/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/euclidean_plane_coefficient_comparator.h @@ -54,14 +54,14 @@ namespace pcl class EuclideanPlaneCoefficientComparator: public PlaneCoefficientComparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::Comparator::input_; using pcl::PlaneCoefficientComparator::normals_; diff --git a/segmentation/include/pcl/segmentation/extract_clusters.h b/segmentation/include/pcl/segmentation/extract_clusters.h index 796d131b3a6..4b4033467c8 100644 --- a/segmentation/include/pcl/segmentation/extract_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_clusters.h @@ -293,18 +293,18 @@ namespace pcl template class EuclideanClusterExtraction: public PCLBase { - typedef PCLBase BasePCLBase; + using BasePCLBase = PCLBase; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; - typedef PointIndices::Ptr PointIndicesPtr; - typedef PointIndices::ConstPtr PointIndicesConstPtr; + using PointIndicesPtr = PointIndices::Ptr; + using PointIndicesConstPtr = PointIndices::ConstPtr; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ diff --git a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h index ae370eac7ab..e1a9b52220c 100644 --- a/segmentation/include/pcl/segmentation/extract_labeled_clusters.h +++ b/segmentation/include/pcl/segmentation/extract_labeled_clusters.h @@ -69,18 +69,18 @@ namespace pcl template class LabeledEuclideanClusterExtraction: public PCLBase { - typedef PCLBase BasePCLBase; + using BasePCLBase = PCLBase; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; - typedef PointIndices::Ptr PointIndicesPtr; - typedef PointIndices::ConstPtr PointIndicesConstPtr; + using PointIndicesPtr = PointIndices::Ptr; + using PointIndicesConstPtr = PointIndices::ConstPtr; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ diff --git a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h index 8319cfc8060..5465051ddb7 100644 --- a/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h +++ b/segmentation/include/pcl/segmentation/extract_polygonal_prism_data.h @@ -106,12 +106,12 @@ namespace pcl using PCLBase::deinitCompute; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef PointIndices::Ptr PointIndicesPtr; - typedef PointIndices::ConstPtr PointIndicesConstPtr; + using PointIndicesPtr = PointIndices::Ptr; + using PointIndicesConstPtr = PointIndices::ConstPtr; /** \brief Empty constructor. */ ExtractPolygonalPrismData () : planar_hull_ (), min_pts_hull_ (3), diff --git a/segmentation/include/pcl/segmentation/grabcut_segmentation.h b/segmentation/include/pcl/segmentation/grabcut_segmentation.h index a09cede8984..0c8beebdd5d 100644 --- a/segmentation/include/pcl/segmentation/grabcut_segmentation.h +++ b/segmentation/include/pcl/segmentation/grabcut_segmentation.h @@ -60,8 +60,8 @@ namespace pcl class PCL_EXPORTS BoykovKolmogorov { public: - typedef int vertex_descriptor; - typedef double edge_capacity_type; + using vertex_descriptor = int; + using edge_capacity_type = double; /// construct a maxflow/mincut problem with estimated max_nodes BoykovKolmogorov (std::size_t max_nodes = 0); @@ -113,11 +113,11 @@ namespace pcl protected: /// tree states - typedef enum { FREE = 0x00, SOURCE = 0x01, TARGET = 0x02 } nodestate; + enum nodestate { FREE = 0x00, SOURCE = 0x01, TARGET = 0x02 }; /// capacitated edge - typedef std::map capacitated_edge; + using capacitated_edge = std::map; /// edge pair - typedef std::pair edge_pair; + using edge_pair = std::pair; /// pre-augment s-u-t and s-u-v-t paths void preAugmentPaths (); @@ -184,7 +184,7 @@ namespace pcl float r, g, b; }; /// An Image is a point cloud of Color - typedef pcl::PointCloud Image; + using Image = pcl::PointCloud; /** \brief Compute squared distance between two colors * \param[in] c1 first color * \param[in] c2 second color @@ -317,10 +317,10 @@ namespace pcl class GrabCut : public pcl::PCLBase { public: - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; - typedef typename PCLBase::PointCloudConstPtr PointCloudConstPtr; - typedef typename PCLBase::PointCloudPtr PointCloudPtr; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; + using PointCloudConstPtr = typename PCLBase::PointCloudConstPtr; + using PointCloudPtr = typename PCLBase::PointCloudPtr; using PCLBase::input_; using PCLBase::indices_; using PCLBase::fake_indices_; @@ -405,7 +405,7 @@ namespace pcl }; bool initCompute (); - typedef pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor vertex_descriptor; + using vertex_descriptor = pcl::segmentation::grabcut::BoykovKolmogorov::vertex_descriptor; /// Compute beta from image void computeBetaOrganized (); diff --git a/segmentation/include/pcl/segmentation/ground_plane_comparator.h b/segmentation/include/pcl/segmentation/ground_plane_comparator.h index 58752c1502c..ce3455f3c13 100644 --- a/segmentation/include/pcl/segmentation/ground_plane_comparator.h +++ b/segmentation/include/pcl/segmentation/ground_plane_comparator.h @@ -54,15 +54,15 @@ namespace pcl class GroundPlaneComparator: public Comparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::Comparator::input_; diff --git a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp index 72572c0711e..8b97ca40922 100644 --- a/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp +++ b/segmentation/include/pcl/segmentation/impl/cpc_segmentation.hpp @@ -85,7 +85,7 @@ pcl::CPCSegmentation::segment () template void pcl::CPCSegmentation::applyCuttingPlane (uint32_t depth_levels_left) { - typedef std::map::Ptr> SegLabel2ClusterMap; + using SegLabel2ClusterMap = std::map::Ptr>; pcl::console::print_info ("Cutting at level %d (maximum %d)\n", max_cuts_ - depth_levels_left + 1, max_cuts_); // stop if we reached the 0 level diff --git a/segmentation/include/pcl/segmentation/impl/random_walker.hpp b/segmentation/include/pcl/segmentation/impl/random_walker.hpp index 9eac1335a12..a88a8bbd25d 100644 --- a/segmentation/include/pcl/segmentation/impl/random_walker.hpp +++ b/segmentation/include/pcl/segmentation/impl/random_walker.hpp @@ -67,19 +67,19 @@ namespace pcl public: - typedef typename boost::property_traits::value_type Color; - typedef typename boost::property_traits::value_type Weight; - typedef boost::graph_traits GraphTraits; - typedef typename GraphTraits::edge_descriptor EdgeDescriptor; - typedef typename GraphTraits::vertex_descriptor VertexDescriptor; - typedef typename GraphTraits::edge_iterator EdgeIterator; - typedef typename GraphTraits::out_edge_iterator OutEdgeIterator; - typedef typename GraphTraits::vertex_iterator VertexIterator; - typedef typename boost::property_map::type VertexIndexMap; - typedef boost::iterator_property_map::iterator, VertexIndexMap> VertexDegreeMap; - typedef Eigen::SparseMatrix SparseMatrix; - typedef Eigen::Matrix Matrix; - typedef Eigen::Matrix Vector; + using Color = typename boost::property_traits::value_type; + using Weight = typename boost::property_traits::value_type; + using GraphTraits = boost::graph_traits; + using EdgeDescriptor = typename GraphTraits::edge_descriptor; + using VertexDescriptor = typename GraphTraits::vertex_descriptor; + using EdgeIterator = typename GraphTraits::edge_iterator; + using OutEdgeIterator = typename GraphTraits::out_edge_iterator; + using VertexIterator = typename GraphTraits::vertex_iterator; + using VertexIndexMap = typename boost::property_map::type; + using VertexDegreeMap = boost::iterator_property_map::iterator, VertexIndexMap>; + using SparseMatrix = Eigen::SparseMatrix; + using Matrix = Eigen::Matrix; + using Vector = Eigen::Matrix; RandomWalker (Graph& g, EdgeWeightMap weights, VertexColorMap colors) : g_ (g) @@ -117,8 +117,8 @@ namespace pcl { using namespace boost; - typedef Eigen::Triplet T; - typedef std::vector Triplets; + using T = Eigen::Triplet; + using Triplets = std::vector; Triplets L_triplets; Triplets B_triplets; @@ -294,8 +294,8 @@ namespace pcl { using namespace boost; - typedef typename graph_traits::edge_descriptor EdgeDescriptor; - typedef typename graph_traits::vertex_descriptor VertexDescriptor; + using EdgeDescriptor = typename graph_traits::edge_descriptor; + using VertexDescriptor = typename graph_traits::vertex_descriptor; BOOST_CONCEPT_ASSERT ((VertexListGraphConcept)); // to have vertices(), num_vertices() BOOST_CONCEPT_ASSERT ((EdgeListGraphConcept)); // to have edges() @@ -322,8 +322,8 @@ namespace pcl { using namespace boost; - typedef typename graph_traits::edge_descriptor EdgeDescriptor; - typedef typename graph_traits::vertex_descriptor VertexDescriptor; + using EdgeDescriptor = typename graph_traits::edge_descriptor; + using VertexDescriptor = typename graph_traits::vertex_descriptor; BOOST_CONCEPT_ASSERT ((VertexListGraphConcept)); // to have vertices(), num_vertices() BOOST_CONCEPT_ASSERT ((EdgeListGraphConcept)); // to have edges() diff --git a/segmentation/include/pcl/segmentation/lccp_segmentation.h b/segmentation/include/pcl/segmentation/lccp_segmentation.h index 45699b4cbf7..f990d91c01d 100644 --- a/segmentation/include/pcl/segmentation/lccp_segmentation.h +++ b/segmentation/include/pcl/segmentation/lccp_segmentation.h @@ -81,14 +81,14 @@ namespace pcl public: // Adjacency list with nodes holding labels (uint32_t) and edges holding EdgeProperties. - typedef boost::adjacency_list SupervoxelAdjacencyList; - typedef typename boost::graph_traits::vertex_iterator VertexIterator; - typedef typename boost::graph_traits::adjacency_iterator AdjacencyIterator; - - typedef typename boost::graph_traits::vertex_descriptor VertexID; - typedef typename boost::graph_traits::edge_iterator EdgeIterator; - typedef typename boost::graph_traits::out_edge_iterator OutEdgeIterator; - typedef typename boost::graph_traits::edge_descriptor EdgeID; + using SupervoxelAdjacencyList = boost::adjacency_list; + using VertexIterator = typename boost::graph_traits::vertex_iterator; + using AdjacencyIterator = typename boost::graph_traits::adjacency_iterator; + + using VertexID = typename boost::graph_traits::vertex_descriptor; + using EdgeIterator = typename boost::graph_traits::edge_iterator; + using OutEdgeIterator = typename boost::graph_traits::out_edge_iterator; + using EdgeID = typename boost::graph_traits::edge_descriptor; LCCPSegmentation (); virtual diff --git a/segmentation/include/pcl/segmentation/min_cut_segmentation.h b/segmentation/include/pcl/segmentation/min_cut_segmentation.h index 4498baab232..7fb85c57304 100644 --- a/segmentation/include/pcl/segmentation/min_cut_segmentation.h +++ b/segmentation/include/pcl/segmentation/min_cut_segmentation.h @@ -58,10 +58,10 @@ namespace pcl { public: - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; - typedef pcl::PointCloud< PointT > PointCloud; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; + using PointCloud = pcl::PointCloud; + using PointCloudConstPtr = typename PointCloud::ConstPtr; using PCLBase ::input_; using PCLBase ::indices_; @@ -70,37 +70,37 @@ namespace pcl public: - typedef boost::adjacency_list_traits< boost::vecS, boost::vecS, boost::directedS > Traits; + using Traits = boost::adjacency_list_traits< boost::vecS, boost::vecS, boost::directedS >; - typedef boost::adjacency_list< boost::vecS, boost::vecS, boost::directedS, - boost::property< boost::vertex_name_t, std::string, - boost::property< boost::vertex_index_t, long, - boost::property< boost::vertex_color_t, boost::default_color_type, - boost::property< boost::vertex_distance_t, long, - boost::property< boost::vertex_predecessor_t, Traits::edge_descriptor > > > > >, - boost::property< boost::edge_capacity_t, double, - boost::property< boost::edge_residual_capacity_t, double, - boost::property< boost::edge_reverse_t, Traits::edge_descriptor > > > > mGraph; + using mGraph = boost::adjacency_list< boost::vecS, boost::vecS, boost::directedS, + boost::property< boost::vertex_name_t, std::string, + boost::property< boost::vertex_index_t, long, + boost::property< boost::vertex_color_t, boost::default_color_type, + boost::property< boost::vertex_distance_t, long, + boost::property< boost::vertex_predecessor_t, Traits::edge_descriptor > > > > >, + boost::property< boost::edge_capacity_t, double, + boost::property< boost::edge_residual_capacity_t, double, + boost::property< boost::edge_reverse_t, Traits::edge_descriptor > > > >; - typedef boost::property_map< mGraph, boost::edge_capacity_t >::type CapacityMap; + using CapacityMap = boost::property_map< mGraph, boost::edge_capacity_t >::type; - typedef boost::property_map< mGraph, boost::edge_reverse_t>::type ReverseEdgeMap; + using ReverseEdgeMap = boost::property_map< mGraph, boost::edge_reverse_t>::type; - typedef Traits::vertex_descriptor VertexDescriptor; + using VertexDescriptor = Traits::vertex_descriptor; - typedef boost::graph_traits< mGraph >::edge_descriptor EdgeDescriptor; + using EdgeDescriptor = boost::graph_traits::edge_descriptor; - typedef boost::graph_traits< mGraph >::out_edge_iterator OutEdgeIterator; + using OutEdgeIterator = boost::graph_traits::out_edge_iterator; - typedef boost::graph_traits< mGraph >::vertex_iterator VertexIterator; + using VertexIterator = boost::graph_traits::vertex_iterator; - typedef boost::property_map< mGraph, boost::edge_residual_capacity_t >::type ResidualCapacityMap; + using ResidualCapacityMap = boost::property_map< mGraph, boost::edge_residual_capacity_t >::type; - typedef boost::property_map< mGraph, boost::vertex_index_t >::type IndexMap; + using IndexMap = boost::property_map< mGraph, boost::vertex_index_t >::type; - typedef boost::graph_traits< mGraph >::in_edge_iterator InEdgeIterator; + using InEdgeIterator = boost::graph_traits::in_edge_iterator; - typedef boost::shared_ptr mGraphPtr; + using mGraphPtr = boost::shared_ptr; public: diff --git a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h index ac00c4b316b..99c452450ba 100644 --- a/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_connected_component_segmentation.h @@ -63,17 +63,17 @@ namespace pcl using PCLBase::deinitCompute; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::PointCloud PointCloudL; - typedef typename PointCloudL::Ptr PointCloudLPtr; - typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + using PointCloudL = pcl::PointCloud; + using PointCloudLPtr = typename PointCloudL::Ptr; + using PointCloudLConstPtr = typename PointCloudL::ConstPtr; - typedef pcl::Comparator Comparator; - typedef typename Comparator::Ptr ComparatorPtr; - typedef typename Comparator::ConstPtr ComparatorConstPtr; + using Comparator = pcl::Comparator; + using ComparatorPtr = typename Comparator::Ptr; + using ComparatorConstPtr = typename Comparator::ConstPtr; /** \brief Constructor for OrganizedConnectedComponentSegmentation * \param[in] compare A pointer to the comparator to be used for segmentation. Must be an instance of pcl::Comparator. diff --git a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h index 170bfb6e8b4..6a345102c46 100644 --- a/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h +++ b/segmentation/include/pcl/segmentation/organized_multi_plane_segmentation.h @@ -66,25 +66,25 @@ namespace pcl using PCLBase::deinitCompute; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef pcl::PointCloud PointCloudL; - typedef typename PointCloudL::Ptr PointCloudLPtr; - typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + using PointCloudL = pcl::PointCloud; + using PointCloudLPtr = typename PointCloudL::Ptr; + using PointCloudLConstPtr = typename PointCloudL::ConstPtr; - typedef pcl::PlaneCoefficientComparator PlaneComparator; - typedef typename PlaneComparator::Ptr PlaneComparatorPtr; - typedef typename PlaneComparator::ConstPtr PlaneComparatorConstPtr; + using PlaneComparator = pcl::PlaneCoefficientComparator; + using PlaneComparatorPtr = typename PlaneComparator::Ptr; + using PlaneComparatorConstPtr = typename PlaneComparator::ConstPtr; - typedef pcl::PlaneRefinementComparator PlaneRefinementComparator; - typedef typename PlaneRefinementComparator::Ptr PlaneRefinementComparatorPtr; - typedef typename PlaneRefinementComparator::ConstPtr PlaneRefinementComparatorConstPtr; + using PlaneRefinementComparator = pcl::PlaneRefinementComparator; + using PlaneRefinementComparatorPtr = typename PlaneRefinementComparator::Ptr; + using PlaneRefinementComparatorConstPtr = typename PlaneRefinementComparator::ConstPtr; /** \brief Constructor for OrganizedMultiPlaneSegmentation. */ OrganizedMultiPlaneSegmentation () : diff --git a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h index 64c10aa942b..bb3ec3333ee 100644 --- a/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/plane_coefficient_comparator.h @@ -54,15 +54,15 @@ namespace pcl class PlaneCoefficientComparator: public Comparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::Comparator::input_; diff --git a/segmentation/include/pcl/segmentation/plane_refinement_comparator.h b/segmentation/include/pcl/segmentation/plane_refinement_comparator.h index 74acf42d343..9dda12b9c37 100644 --- a/segmentation/include/pcl/segmentation/plane_refinement_comparator.h +++ b/segmentation/include/pcl/segmentation/plane_refinement_comparator.h @@ -54,19 +54,19 @@ namespace pcl class PlaneRefinementComparator: public PlaneCoefficientComparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef pcl::PointCloud PointCloudL; - typedef typename PointCloudL::Ptr PointCloudLPtr; - typedef typename PointCloudL::ConstPtr PointCloudLConstPtr; + using PointCloudL = pcl::PointCloud; + using PointCloudLPtr = typename PointCloudL::Ptr; + using PointCloudLConstPtr = typename PointCloudL::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::PlaneCoefficientComparator::input_; using pcl::PlaneCoefficientComparator::normals_; diff --git a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h index 59bf01a1990..d31b9f34838 100644 --- a/segmentation/include/pcl/segmentation/progressive_morphological_filter.h +++ b/segmentation/include/pcl/segmentation/progressive_morphological_filter.h @@ -57,7 +57,7 @@ namespace pcl { public: - typedef pcl::PointCloud PointCloud; + using PointCloud = pcl::PointCloud; using PCLBase ::input_; using PCLBase ::indices_; diff --git a/segmentation/include/pcl/segmentation/region_growing.h b/segmentation/include/pcl/segmentation/region_growing.h index e1fa4f0370c..6108239d97b 100644 --- a/segmentation/include/pcl/segmentation/region_growing.h +++ b/segmentation/include/pcl/segmentation/region_growing.h @@ -61,11 +61,11 @@ namespace pcl { public: - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; - typedef pcl::PointCloud Normal; - typedef typename Normal::Ptr NormalPtr; - typedef pcl::PointCloud PointCloud; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; + using Normal = pcl::PointCloud; + using NormalPtr = typename Normal::Ptr; + using PointCloud = pcl::PointCloud; using PCLBase ::input_; using PCLBase ::indices_; diff --git a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h index bc591442612..fbcae15721b 100644 --- a/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h +++ b/segmentation/include/pcl/segmentation/rgb_plane_coefficient_comparator.h @@ -54,15 +54,15 @@ namespace pcl class RGBPlaneCoefficientComparator: public PlaneCoefficientComparator { public: - typedef typename Comparator::PointCloud PointCloud; - typedef typename Comparator::PointCloudConstPtr PointCloudConstPtr; + using PointCloud = typename Comparator::PointCloud; + using PointCloudConstPtr = typename Comparator::PointCloudConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; using pcl::Comparator::input_; using pcl::PlaneCoefficientComparator::normals_; diff --git a/segmentation/include/pcl/segmentation/sac_segmentation.h b/segmentation/include/pcl/segmentation/sac_segmentation.h index 26423feb082..415fc46b2ee 100644 --- a/segmentation/include/pcl/segmentation/sac_segmentation.h +++ b/segmentation/include/pcl/segmentation/sac_segmentation.h @@ -70,13 +70,13 @@ namespace pcl using PCLBase::input_; using PCLBase::indices_; - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; - typedef typename pcl::search::Search::Ptr SearchPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; + using SearchPtr = typename pcl::search::Search::Ptr; - typedef typename SampleConsensus::Ptr SampleConsensusPtr; - typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; + using SampleConsensusPtr = typename SampleConsensus::Ptr; + using SampleConsensusModelPtr = typename SampleConsensusModel::Ptr; /** \brief Empty constructor. * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) @@ -321,17 +321,17 @@ namespace pcl using PCLBase::input_; using PCLBase::indices_; - typedef typename SACSegmentation::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = typename SACSegmentation::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::PointCloud PointCloudN; - typedef typename PointCloudN::Ptr PointCloudNPtr; - typedef typename PointCloudN::ConstPtr PointCloudNConstPtr; + using PointCloudN = pcl::PointCloud; + using PointCloudNPtr = typename PointCloudN::Ptr; + using PointCloudNConstPtr = typename PointCloudN::ConstPtr; - typedef typename SampleConsensus::Ptr SampleConsensusPtr; - typedef typename SampleConsensusModel::Ptr SampleConsensusModelPtr; - typedef typename SampleConsensusModelFromNormals::Ptr SampleConsensusModelFromNormalsPtr; + using SampleConsensusPtr = typename SampleConsensus::Ptr; + using SampleConsensusModelPtr = typename SampleConsensusModel::Ptr; + using SampleConsensusModelFromNormalsPtr = typename SampleConsensusModelFromNormals::Ptr; /** \brief Empty constructor. * \param[in] random if true set the random seed to the current time, else set to 12345 (default: false) diff --git a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h index 1f81346b850..e8cfa42643c 100644 --- a/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h +++ b/segmentation/include/pcl/segmentation/seeded_hue_segmentation.h @@ -92,18 +92,18 @@ namespace pcl */ class SeededHueSegmentation: public PCLBase { - typedef PCLBase BasePCLBase; + using BasePCLBase = PCLBase; public: - typedef pcl::PointCloud PointCloud; - typedef PointCloud::Ptr PointCloudPtr; - typedef PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = PointCloud::Ptr; + using PointCloudConstPtr = PointCloud::ConstPtr; - typedef pcl::search::Search KdTree; - typedef pcl::search::Search::Ptr KdTreePtr; + using KdTree = pcl::search::Search; + using KdTreePtr = pcl::search::Search::Ptr; - typedef PointIndices::Ptr PointIndicesPtr; - typedef PointIndices::ConstPtr PointIndicesConstPtr; + using PointIndicesPtr = PointIndices::Ptr; + using PointIndicesConstPtr = PointIndices::ConstPtr; ////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Empty constructor. */ diff --git a/segmentation/include/pcl/segmentation/segment_differences.h b/segmentation/include/pcl/segmentation/segment_differences.h index 96c5adea939..f822a7f8bc8 100755 --- a/segmentation/include/pcl/segmentation/segment_differences.h +++ b/segmentation/include/pcl/segmentation/segment_differences.h @@ -82,18 +82,18 @@ namespace pcl template class SegmentDifferences: public PCLBase { - typedef PCLBase BasePCLBase; + using BasePCLBase = PCLBase; public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef pcl::search::Search KdTree; - typedef typename KdTree::Ptr KdTreePtr; + using KdTree = pcl::search::Search; + using KdTreePtr = typename KdTree::Ptr; - typedef PointIndices::Ptr PointIndicesPtr; - typedef PointIndices::ConstPtr PointIndicesConstPtr; + using PointIndicesPtr = PointIndices::Ptr; + using PointIndicesConstPtr = PointIndices::ConstPtr; /** \brief Empty constructor. */ SegmentDifferences () : diff --git a/segmentation/include/pcl/segmentation/supervoxel_clustering.h b/segmentation/include/pcl/segmentation/supervoxel_clustering.h index d0cceedd73b..454e83fe388 100644 --- a/segmentation/include/pcl/segmentation/supervoxel_clustering.h +++ b/segmentation/include/pcl/segmentation/supervoxel_clustering.h @@ -70,8 +70,8 @@ namespace pcl normals_ (new pcl::PointCloud ()) { } - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; /** \brief Gets the centroid of the supervoxel * \param[out] centroid_arg centroid of the supervoxel @@ -165,23 +165,23 @@ namespace pcl EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; - typedef pcl::octree::OctreePointCloudAdjacencyContainer LeafContainerT; - typedef std::vector LeafVectorT; + using LeafContainerT = pcl::octree::OctreePointCloudAdjacencyContainer; + using LeafVectorT = std::vector; - typedef pcl::PointCloud PointCloudT; - typedef pcl::PointCloud NormalCloudT; - typedef pcl::octree::OctreePointCloudAdjacency OctreeAdjacencyT; - typedef pcl::octree::OctreePointCloudSearch OctreeSearchT; - typedef pcl::search::KdTree KdTreeT; - typedef boost::shared_ptr > IndicesPtr; + using PointCloudT = pcl::PointCloud; + using NormalCloudT = pcl::PointCloud; + using OctreeAdjacencyT = pcl::octree::OctreePointCloudAdjacency; + using OctreeSearchT = pcl::octree::OctreePointCloudSearch; + using KdTreeT = pcl::search::KdTree; + using IndicesPtr = boost::shared_ptr >; using PCLBase ::initCompute; using PCLBase ::deinitCompute; using PCLBase ::input_; - typedef boost::adjacency_list VoxelAdjacencyList; - typedef VoxelAdjacencyList::vertex_descriptor VoxelID; - typedef VoxelAdjacencyList::edge_descriptor EdgeID; + using VoxelAdjacencyList = boost::adjacency_list; + using VoxelID = VoxelAdjacencyList::vertex_descriptor; + using EdgeID = VoxelAdjacencyList::edge_descriptor; public: @@ -433,9 +433,9 @@ namespace pcl return leaf_data_left.idx_ < leaf_data_right.idx_; } }; - typedef std::set LeafSetT; - typedef typename LeafSetT::iterator iterator; - typedef typename LeafSetT::const_iterator const_iterator; + using LeafSetT = std::set; + using iterator = typename LeafSetT::iterator; + using const_iterator = typename LeafSetT::const_iterator; SupervoxelHelper (uint32_t label, SupervoxelClustering* parent_arg): label_ (label), @@ -466,7 +466,7 @@ namespace pcl void getNormals (typename pcl::PointCloud::Ptr &normals) const; - typedef float (SupervoxelClustering::*DistFuncPtr)(const VoxelData &v1, const VoxelData &v2); + using DistFuncPtr = float (SupervoxelClustering::*)(const VoxelData &, const VoxelData &); uint32_t getLabel () const @@ -532,7 +532,7 @@ namespace pcl friend void boost::checked_delete<> (const typename pcl::SupervoxelClustering::SupervoxelHelper *); #endif - typedef boost::ptr_list HelperListT; + using HelperListT = boost::ptr_list; HelperListT supervoxel_helpers_; //TODO DEBUG REMOVE diff --git a/segmentation/src/supervoxel_clustering.cpp b/segmentation/src/supervoxel_clustering.cpp index 41cad71fc93..f421acf638a 100644 --- a/segmentation/src/supervoxel_clustering.cpp +++ b/segmentation/src/supervoxel_clustering.cpp @@ -160,13 +160,13 @@ namespace pcl } } -typedef pcl::SupervoxelClustering::VoxelData VoxelDataT; -typedef pcl::SupervoxelClustering::VoxelData VoxelDataRGBT; -typedef pcl::SupervoxelClustering::VoxelData VoxelDataRGBAT; +using VoxelDataT = pcl::SupervoxelClustering::VoxelData; +using VoxelDataRGBT = pcl::SupervoxelClustering::VoxelData; +using VoxelDataRGBAT = pcl::SupervoxelClustering::VoxelData; -typedef pcl::octree::OctreePointCloudAdjacencyContainer AdjacencyContainerT; -typedef pcl::octree::OctreePointCloudAdjacencyContainer AdjacencyContainerRGBT; -typedef pcl::octree::OctreePointCloudAdjacencyContainer AdjacencyContainerRGBAT; +using AdjacencyContainerT = pcl::octree::OctreePointCloudAdjacencyContainer; +using AdjacencyContainerRGBT = pcl::octree::OctreePointCloudAdjacencyContainer; +using AdjacencyContainerRGBAT = pcl::octree::OctreePointCloudAdjacencyContainer; template class pcl::SupervoxelClustering; template class pcl::SupervoxelClustering;