Skip to content

Commit

Permalink
Merge pull request #2897 from taketwo/remove-typename-2
Browse files Browse the repository at this point in the history
Remove redundant typenames
  • Loading branch information
SergioRAgostinho authored Mar 10, 2019
2 parents 213da11 + 0dca1d1 commit 604af83
Show file tree
Hide file tree
Showing 25 changed files with 59 additions and 59 deletions.
12 changes: 6 additions & 6 deletions features/include/pcl/features/brisk_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,14 +70,14 @@ namespace pcl
typedef boost::shared_ptr<BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT> > Ptr;
typedef boost::shared_ptr<const BRISK2DEstimation<PointInT, PointOutT, KeypointT, IntensityT> > ConstPtr;

typedef typename pcl::PointCloud<PointInT> PointCloudInT;
typedef typename pcl::PointCloud<PointInT>::ConstPtr PointCloudInTConstPtr;
typedef pcl::PointCloud<PointInT> PointCloudInT;
typedef typename PointCloudInT::ConstPtr PointCloudInTConstPtr;

typedef typename pcl::PointCloud<KeypointT> KeypointPointCloudT;
typedef typename pcl::PointCloud<KeypointT>::Ptr KeypointPointCloudTPtr;
typedef typename pcl::PointCloud<KeypointT>::ConstPtr KeypointPointCloudTConstPtr;
typedef pcl::PointCloud<KeypointT> KeypointPointCloudT;
typedef typename KeypointPointCloudT::Ptr KeypointPointCloudTPtr;
typedef typename KeypointPointCloudT::ConstPtr KeypointPointCloudTConstPtr;

typedef typename pcl::PointCloud<PointOutT> PointCloudOutT;
typedef pcl::PointCloud<PointOutT> PointCloudOutT;

/** \brief Constructor. */
BRISK2DEstimation ();
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/cvfh.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ namespace pcl

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename pcl::search::Search<PointNormal>::Ptr KdTreePtr;
typedef typename pcl::VFHEstimation<PointInT, PointNT, pcl::VFHSignature308> VFHEstimator;
typedef pcl::VFHEstimation<PointInT, PointNT, pcl::VFHSignature308> VFHEstimator;

/** \brief Empty constructor. */
CVFHEstimation () :
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/don.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace pcl
using Feature<PointInT, PointOutT>::getClassName;
using Feature<PointInT, PointOutT>::feature_name_;
using PCLBase<PointInT>::input_;
typedef typename pcl::PointCloud<PointNT> PointCloudN;
typedef pcl::PointCloud<PointNT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/esf.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace pcl
using Feature<PointInT, PointOutT>::input_;
using Feature<PointInT, PointOutT>::surface_;

typedef typename pcl::PointCloud<PointInT> PointCloudIn;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;

/** \brief Empty constructor. */
Expand Down
8 changes: 4 additions & 4 deletions features/include/pcl/features/feature.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,8 @@ namespace pcl
typedef boost::shared_ptr< Feature<PointInT, PointOutT> > Ptr;
typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > ConstPtr;

typedef typename pcl::search::Search<PointInT> KdTree;
typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
typedef pcl::search::Search<PointInT> KdTree;
typedef typename KdTree::Ptr KdTreePtr;

typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
Expand Down Expand Up @@ -314,7 +314,7 @@ namespace pcl
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;

public:
typedef typename pcl::PointCloud<PointNT> PointCloudN;
typedef pcl::PointCloud<PointNT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

Expand Down Expand Up @@ -370,7 +370,7 @@ namespace pcl
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;

typedef typename pcl::PointCloud<PointLT> PointCloudL;
typedef pcl::PointCloud<PointLT> PointCloudL;
typedef typename PointCloudL::Ptr PointCloudNPtr;
typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;

Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/flare.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ namespace pcl

using typename Feature<PointInT, PointOutT>::KdTreePtr;

typedef typename pcl::PointCloud<SignedDistanceT> PointCloudSignedDistance;
typedef pcl::PointCloud<SignedDistanceT> PointCloudSignedDistance;
typedef typename PointCloudSignedDistance::Ptr PointCloudSignedDistancePtr;

typedef boost::shared_ptr<FLARELocalReferenceFrameEstimation<PointInT, PointNT, PointOutT> > Ptr;
Expand Down
2 changes: 1 addition & 1 deletion features/include/pcl/features/intensity_spin.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace pcl
using Feature<PointInT, PointOutT>::tree_;
using Feature<PointInT, PointOutT>::search_radius_;

typedef typename pcl::PointCloud<PointInT> PointCloudIn;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;

/** \brief Empty constructor. */
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/normal_based_signature.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ namespace pcl
using FeatureFromNormals<PointT, PointNT, PointFeature>::normals_;

typedef pcl::PointCloud<PointFeature> FeatureCloud;
typedef typename boost::shared_ptr<NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > Ptr;
typedef typename boost::shared_ptr<const NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > ConstPtr;
typedef boost::shared_ptr<NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > Ptr;
typedef boost::shared_ptr<const NormalBasedSignatureEstimation<PointT, PointNT, PointFeature> > ConstPtr;



Expand Down
20 changes: 10 additions & 10 deletions features/include/pcl/features/organized_edge_detection.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,11 +56,11 @@ namespace pcl
template <typename PointT, typename PointLT>
class OrganizedEdgeBase : public PCLBase<PointT>
{
typedef typename pcl::PointCloud<PointT> PointCloud;
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename pcl::PointCloud<PointLT> PointCloudL;
typedef pcl::PointCloud<PointLT> PointCloudL;
typedef typename PointCloudL::Ptr PointCloudLPtr;
typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;

Expand Down Expand Up @@ -181,11 +181,11 @@ namespace pcl
template <typename PointT, typename PointLT>
class OrganizedEdgeFromRGB : virtual public OrganizedEdgeBase<PointT, PointLT>
{
typedef typename pcl::PointCloud<PointT> PointCloud;
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename pcl::PointCloud<PointLT> PointCloudL;
typedef pcl::PointCloud<PointLT> PointCloudL;
typedef typename PointCloudL::Ptr PointCloudLPtr;
typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;

Expand Down Expand Up @@ -267,15 +267,15 @@ namespace pcl
template <typename PointT, typename PointNT, typename PointLT>
class OrganizedEdgeFromNormals : virtual public OrganizedEdgeBase<PointT, PointLT>
{
typedef typename pcl::PointCloud<PointT> PointCloud;
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename pcl::PointCloud<PointNT> PointCloudN;
typedef pcl::PointCloud<PointNT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

typedef typename pcl::PointCloud<PointLT> PointCloudL;
typedef pcl::PointCloud<PointLT> PointCloudL;
typedef typename PointCloudL::Ptr PointCloudLPtr;
typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;

Expand Down Expand Up @@ -377,15 +377,15 @@ namespace pcl
template <typename PointT, typename PointNT, typename PointLT>
class OrganizedEdgeFromRGBNormals : public OrganizedEdgeFromRGB<PointT, PointLT>, public OrganizedEdgeFromNormals<PointT, PointNT, PointLT>
{
typedef typename pcl::PointCloud<PointT> PointCloud;
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename pcl::PointCloud<PointNT> PointCloudN;
typedef pcl::PointCloud<PointNT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

typedef typename pcl::PointCloud<PointLT> PointCloudL;
typedef pcl::PointCloud<PointLT> PointCloudL;
typedef typename PointCloudL::Ptr PointCloudLPtr;
typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;

Expand Down
8 changes: 4 additions & 4 deletions features/include/pcl/features/rift.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,15 +68,15 @@ namespace pcl
using Feature<PointInT, PointOutT>::tree_;
using Feature<PointInT, PointOutT>::search_radius_;

typedef typename pcl::PointCloud<PointInT> PointCloudIn;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;

typedef typename pcl::PointCloud<GradientT> PointCloudGradient;
typedef pcl::PointCloud<GradientT> PointCloudGradient;
typedef typename PointCloudGradient::Ptr PointCloudGradientPtr;
typedef typename PointCloudGradient::ConstPtr PointCloudGradientConstPtr;

typedef typename boost::shared_ptr<RIFTEstimation<PointInT, GradientT, PointOutT> > Ptr;
typedef typename boost::shared_ptr<const RIFTEstimation<PointInT, GradientT, PointOutT> > ConstPtr;
typedef boost::shared_ptr<RIFTEstimation<PointInT, GradientT, PointOutT> > Ptr;
typedef boost::shared_ptr<const RIFTEstimation<PointInT, GradientT, PointOutT> > ConstPtr;


/** \brief Empty constructor. */
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/rsd.h
Original file line number Diff line number Diff line change
Expand Up @@ -160,8 +160,8 @@ namespace pcl
typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;

typedef typename boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > Ptr;
typedef typename boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
typedef boost::shared_ptr<RSDEstimation<PointInT, PointNT, PointOutT> > Ptr;
typedef boost::shared_ptr<const RSDEstimation<PointInT, PointNT, PointOutT> > ConstPtr;


/** \brief Empty constructor. */
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/spin_image.h
Original file line number Diff line number Diff line change
Expand Up @@ -100,11 +100,11 @@ namespace pcl

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;

typedef typename pcl::PointCloud<PointNT> PointCloudN;
typedef pcl::PointCloud<PointNT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

typedef typename pcl::PointCloud<PointInT> PointCloudIn;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,8 @@ namespace pcl
{
public:
typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
typedef typename boost::shared_ptr<StatisticalMultiscaleInterestRegionExtraction<PointT> > Ptr;
typedef typename boost::shared_ptr<const StatisticalMultiscaleInterestRegionExtraction<PointT> > ConstPtr;
typedef boost::shared_ptr<StatisticalMultiscaleInterestRegionExtraction<PointT> > Ptr;
typedef boost::shared_ptr<const StatisticalMultiscaleInterestRegionExtraction<PointT> > ConstPtr;


/** \brief Empty constructor */
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/usc.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ namespace pcl

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
typedef typename boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > Ptr;
typedef typename boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > ConstPtr;
typedef boost::shared_ptr<UniqueShapeContext<PointInT, PointOutT, PointRFT> > Ptr;
typedef boost::shared_ptr<const UniqueShapeContext<PointInT, PointOutT, PointRFT> > ConstPtr;


/** \brief Constructor. */
Expand Down
4 changes: 2 additions & 2 deletions features/include/pcl/features/vfh.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,8 +80,8 @@ namespace pcl
using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;

typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename boost::shared_ptr<VFHEstimation<PointInT, PointNT, PointOutT> > Ptr;
typedef typename boost::shared_ptr<const VFHEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
typedef boost::shared_ptr<VFHEstimation<PointInT, PointNT, PointOutT> > Ptr;
typedef boost::shared_ptr<const VFHEstimation<PointInT, PointNT, PointOutT> > ConstPtr;


/** \brief Empty constructor. */
Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/conditional_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -445,7 +445,7 @@ namespace pcl
class ConditionBase
{
public:
typedef typename pcl::ComparisonBase<PointT> ComparisonBase;
typedef pcl::ComparisonBase<PointT> ComparisonBase;
typedef typename ComparisonBase::Ptr ComparisonBasePtr;
typedef typename ComparisonBase::ConstPtr ComparisonBaseConstPtr;

Expand Down Expand Up @@ -605,7 +605,7 @@ namespace pcl
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

public:
typedef typename pcl::ConditionBase<PointT> ConditionBase;
typedef pcl::ConditionBase<PointT> ConditionBase;
typedef typename ConditionBase::Ptr ConditionBasePtr;
typedef typename ConditionBase::ConstPtr ConditionBaseConstPtr;

Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/convolution.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,10 @@ namespace pcl
class Convolution
{
public:
typedef typename pcl::PointCloud<PointIn> PointCloudIn;
typedef pcl::PointCloud<PointIn> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef typename pcl::PointCloud<PointOut> PointCloudOut;
typedef pcl::PointCloud<PointOut> PointCloudOut;
typedef boost::shared_ptr< Convolution<PointIn, PointOut> > Ptr;
typedef boost::shared_ptr< const Convolution<PointIn, PointOut> > ConstPtr;

Expand Down
8 changes: 4 additions & 4 deletions filters/include/pcl/filters/convolution_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -199,11 +199,11 @@ namespace pcl
class Convolution3D : public pcl::PCLBase <PointIn>
{
public:
typedef typename pcl::PointCloud<PointIn> PointCloudIn;
typedef pcl::PointCloud<PointIn> PointCloudIn;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef typename pcl::search::Search<PointIn> KdTree;
typedef typename pcl::search::Search<PointIn>::Ptr KdTreePtr;
typedef typename pcl::PointCloud<PointOut> PointCloudOut;
typedef pcl::search::Search<PointIn> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
typedef pcl::PointCloud<PointOut> PointCloudOut;
typedef boost::shared_ptr<Convolution3D<PointIn, PointOut, KernelT> > Ptr;
typedef boost::shared_ptr<Convolution3D<PointIn, PointOut, KernelT> > ConstPtr;

Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/model_outlier_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,8 +74,8 @@ namespace pcl
typedef typename SampleConsensusModel<PointT>::Ptr SampleConsensusModelPtr;

public:
typedef typename pcl::PointCloud<pcl::Normal>::Ptr PointCloudNPtr;
typedef typename pcl::PointCloud<pcl::Normal>::ConstPtr PointCloudNConstPtr;
typedef pcl::PointCloud<pcl::Normal>::Ptr PointCloudNPtr;
typedef pcl::PointCloud<pcl::Normal>::ConstPtr PointCloudNConstPtr;

/** \brief Constructor.
* \param[in] extract_removed_indices Set to true if you want to be able to extract the indices of points being removed (default = false).
Expand Down
2 changes: 1 addition & 1 deletion filters/include/pcl/filters/sampling_surface_normal.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ namespace pcl
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename Eigen::Matrix<float, Eigen::Dynamic, 1> Vector;
typedef Eigen::Matrix<float, Eigen::Dynamic, 1> Vector;

public:

Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/harris_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace pcl
typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;

typedef typename pcl::PointCloud<NormalT> PointCloudN;
typedef pcl::PointCloud<NormalT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/iss_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,11 +90,11 @@ namespace pcl
typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;

typedef typename pcl::PointCloud<NormalT> PointCloudN;
typedef pcl::PointCloud<NormalT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

typedef typename pcl::octree::OctreePointCloudSearch<PointInT> OctreeSearchIn;
typedef pcl::octree::OctreePointCloudSearch<PointInT> OctreeSearchIn;
typedef typename OctreeSearchIn::Ptr OctreeSearchInPtr;

using Keypoint<PointInT, PointOutT>::name_;
Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/keypoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,8 @@ namespace pcl
using PCLBase<PointInT>::input_;

typedef PCLBase<PointInT> BaseClass;
typedef typename pcl::search::Search<PointInT> KdTree;
typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
typedef pcl::search::Search<PointInT> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/susan.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ namespace pcl
typedef typename Keypoint<PointInT, PointOutT>::KdTree KdTree;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;

typedef typename pcl::PointCloud<NormalT> PointCloudN;
typedef pcl::PointCloud<NormalT> PointCloudN;
typedef typename PointCloudN::Ptr PointCloudNPtr;
typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;

Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/trajkovic_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace pcl
typedef typename Keypoint<PointInT, PointOutT>::PointCloudIn PointCloudIn;
typedef typename Keypoint<PointInT, PointOutT>::PointCloudOut PointCloudOut;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef typename pcl::PointCloud<NormalT> Normals;
typedef pcl::PointCloud<NormalT> Normals;
typedef typename Normals::Ptr NormalsPtr;
typedef typename Normals::ConstPtr NormalsConstPtr;

Expand Down

0 comments on commit 604af83

Please sign in to comment.