Skip to content

Commit

Permalink
Merge pull request #2896 from taketwo/remove-typename-1
Browse files Browse the repository at this point in the history
Remove redundant typenames
  • Loading branch information
SergioRAgostinho authored Mar 10, 2019
2 parents 7da04aa + 06b1a96 commit 213da11
Show file tree
Hide file tree
Showing 24 changed files with 45 additions and 47 deletions.
2 changes: 1 addition & 1 deletion 2d/include/pcl/2d/edge.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace pcl
class Edge
{
private:
typedef typename pcl::PointCloud<PointInT> PointCloudIn;
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;

PointCloudInPtr input_;
Expand Down
2 changes: 1 addition & 1 deletion 2d/include/pcl/2d/morphology.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace pcl
class Morphology : public PCLBase<PointT>
{
private:
typedef typename pcl::PointCloud<PointT> PointCloudIn;
typedef pcl::PointCloud<PointT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;

PointCloudInPtr structuring_element_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ namespace pcl

crh_histograms_.resize(signatures.size());

typedef typename pcl::CRHEstimation<PointInT, pcl::Normal, pcl::Histogram<90> > CRHEstimation;
typedef pcl::CRHEstimation<PointInT, pcl::Normal, pcl::Histogram<90> > CRHEstimation;
CRHEstimation crh;
crh.setInputCloud(processed);
crh.setInputNormals(normals_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ namespace pcl
/*normals_.reset(new pcl::PointCloud<pcl::Normal>);
normal_estimator_->estimate (in, processed, normals_);*/

typedef typename pcl::CVFHEstimation<PointInT, pcl::Normal, FeatureT> CVFHEstimation;
typedef pcl::CVFHEstimation<PointInT, pcl::Normal, FeatureT> CVFHEstimation;
pcl::PointCloud<FeatureT> cvfh_signatures;
typename pcl::search::KdTree<PointInT>::Ptr cvfh_tree (new pcl::search::KdTree<PointInT>);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace pcl
std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > & centroids) override
{

typedef typename pcl::ESFEstimation<PointInT, FeatureT> ESFEstimation;
typedef pcl::ESFEstimation<PointInT, FeatureT> ESFEstimation;
pcl::PointCloud<FeatureT> ESF_signature;

ESFEstimation esf;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ namespace pcl
/*normals_.reset(new pcl::PointCloud<pcl::Normal>);
normal_estimator_->estimate (in, processed, normals_);*/

typedef typename pcl::OURCVFHEstimation<PointInT, pcl::Normal, pcl::VFHSignature308> OURCVFHEstimation;
typedef pcl::OURCVFHEstimation<PointInT, pcl::Normal, pcl::VFHSignature308> OURCVFHEstimation;
pcl::PointCloud<pcl::VFHSignature308> cvfh_signatures;
typename pcl::search::KdTree<PointInT>::Ptr cvfh_tree (new pcl::search::KdTree<PointInT>);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ namespace pcl
normals_.reset(new pcl::PointCloud<pcl::Normal>);
normal_estimator_->estimate (in, processed, normals_);

typedef typename pcl::VFHEstimation<PointInT, pcl::Normal, FeatureT> VFHEstimation;
typedef pcl::VFHEstimation<PointInT, pcl::Normal, FeatureT> VFHEstimation;
pcl::PointCloud<FeatureT> vfh_signature;

VFHEstimation vfh;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ namespace pcl
}

//compute signatures
typedef typename pcl::SHOTColorEstimation<PointInT, pcl::Normal, pcl::SHOT1344> SHOTEstimator;
typedef pcl::SHOTColorEstimation<PointInT, pcl::Normal, pcl::SHOT1344> SHOTEstimator;
typename pcl::search::KdTree<PointInT>::Ptr tree (new pcl::search::KdTree<PointInT>);

pcl::PointCloud<pcl::SHOT1344>::Ptr shots (new pcl::PointCloud<pcl::SHOT1344>);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace pcl
assert (processed->points.size () == normals->points.size ());

//compute signatures
typedef typename pcl::FPFHEstimation<PointInT, pcl::Normal, pcl::FPFHSignature33> FPFHEstimator;
typedef pcl::FPFHEstimation<PointInT, pcl::Normal, pcl::FPFHSignature33> FPFHEstimator;
typename pcl::search::KdTree<PointInT>::Ptr tree (new pcl::search::KdTree<PointInT>);

pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs (new pcl::PointCloud<pcl::FPFHSignature33>);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ namespace pcl
assert (processed->points.size () == normals->points.size ());

//compute signatures
typedef typename pcl::FPFHEstimationOMP<PointInT, pcl::Normal, pcl::FPFHSignature33> FPFHEstimator;
typedef pcl::FPFHEstimationOMP<PointInT, pcl::Normal, pcl::FPFHSignature33> FPFHEstimator;
typename pcl::search::KdTree<PointInT>::Ptr tree (new pcl::search::KdTree<PointInT>);

pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs (new pcl::PointCloud<pcl::FPFHSignature33>);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ namespace pcl

std::cout << keypoints->points.size() << " " << normals->points.size() << " " << processed->points.size() << std::endl;
//compute signatures
typedef typename pcl::SHOTEstimation<PointInT, pcl::Normal, pcl::SHOT352> SHOTEstimator;
typedef pcl::SHOTEstimation<PointInT, pcl::Normal, pcl::SHOT352> SHOTEstimator;
typename pcl::search::KdTree<PointInT>::Ptr tree (new pcl::search::KdTree<PointInT>);

pcl::PointCloud<pcl::SHOT352>::Ptr shots (new pcl::PointCloud<pcl::SHOT352>);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ namespace pcl
}

//compute signatures
typedef typename pcl::SHOTEstimationOMP<PointInT, pcl::Normal, pcl::SHOT352> SHOTEstimator;
typedef pcl::SHOTEstimationOMP<PointInT, pcl::Normal, pcl::SHOT352> SHOTEstimator;
typename pcl::search::KdTree<PointInT>::Ptr tree (new pcl::search::KdTree<PointInT>);
tree->setInputCloud (processed);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,8 +183,7 @@ namespace pcl

if (out->isOrganized ())
{
typedef typename pcl::IntegralImageNormalEstimation<PointInT, pcl::Normal> NormalEstimator_;
NormalEstimator_ n3d;
pcl::IntegralImageNormalEstimation<PointInT, pcl::Normal> n3d;
n3d.setNormalEstimationMethod (n3d.COVARIANCE_MATRIX);
//n3d.setNormalEstimationMethod (n3d.AVERAGE_3D_GRADIENT);
n3d.setInputCloud (out);
Expand Down Expand Up @@ -223,8 +222,7 @@ namespace pcl
out->height = 1;
}

typedef typename pcl::NormalEstimation<PointInT, pcl::Normal> NormalEstimator_;
NormalEstimator_ n3d;
pcl::NormalEstimation<PointInT, pcl::Normal> n3d;
typename pcl::search::KdTree<PointInT>::Ptr normals_tree (new pcl::search::KdTree<PointInT>);
normals_tree->setInputCloud (out);
n3d.setRadiusSearch (radius);
Expand Down
8 changes: 4 additions & 4 deletions apps/src/openni_tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,16 +116,16 @@ class OpenNISegmentTracking

typedef pcl::PointCloud<PointType> Cloud;
typedef pcl::PointCloud<RefPointType> RefCloud;
typedef typename RefCloud::Ptr RefCloudPtr;
typedef typename RefCloud::ConstPtr RefCloudConstPtr;
typedef RefCloud::Ptr RefCloudPtr;
typedef RefCloud::ConstPtr RefCloudConstPtr;
typedef typename Cloud::Ptr CloudPtr;
typedef typename Cloud::ConstPtr CloudConstPtr;
//typedef KLDAdaptiveParticleFilterTracker<RefPointType, ParticleT> ParticleFilter;
//typedef KLDAdaptiveParticleFilterOMPTracker<RefPointType, ParticleT> ParticleFilter;
//typedef ParticleFilterOMPTracker<RefPointType, ParticleT> ParticleFilter;
typedef ParticleFilterTracker<RefPointType, ParticleT> ParticleFilter;
typedef typename ParticleFilter::CoherencePtr CoherencePtr;
typedef typename pcl::search::KdTree<PointType> KdTree;
typedef ParticleFilter::CoherencePtr CoherencePtr;
typedef pcl::search::KdTree<PointType> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
OpenNISegmentTracking (const std::string& device_id, int thread_nr, double downsampling_grid_size,
bool use_convex_hull,
Expand Down
4 changes: 2 additions & 2 deletions cuda/common/include/pcl/cuda/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ namespace pcl
struct Host
{
// vector type
typedef typename thrust::host_vector<T> type;
typedef thrust::host_vector<T> type;

// // iterator type
// typedef thrust::detail::normal_iterator<T*> type;
Expand Down Expand Up @@ -93,7 +93,7 @@ namespace pcl
struct Device
{
// vector type
typedef typename thrust::device_vector<T> type;
typedef thrust::device_vector<T> type;

// // iterator type
// typedef thrust::detail::normal_iterator<thrust::device_ptr<T> > iterator_type;
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/hdl_grabber.rst
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ So let's look at the code. The following represents a simplified version of *vis
{
public:
typedef pcl::PointCloud<pcl::PointXYZI> Cloud;
typedef typename Cloud::ConstPtr CloudConstPtr;
typedef Cloud::ConstPtr CloudConstPtr;
SimpleHDLViewer (Grabber& grabber,
pcl::visualization::PointCloudColorHandler<pcl::PointXYZI> &handler) :
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ template <typename PointT>
class ConditionThresholdHSV : public pcl::ConditionBase<PointT>
{
public:
typedef typename boost::shared_ptr<ConditionThresholdHSV<PointT> > Ptr;
typedef boost::shared_ptr<ConditionThresholdHSV<PointT> > Ptr;

ConditionThresholdHSV (float min_h, float max_h, float min_s, float max_s, float min_v, float max_v) :
min_h_(min_h), max_h_(max_h), min_s_(min_s), max_s_(max_s), min_v_(min_v), max_v_(max_v)
Expand Down
2 changes: 1 addition & 1 deletion gpu/kinfu/tools/kinfu_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ namespace pcl
using PointCloudColorHandler<PointT>::cloud_;

typedef typename PointCloudColorHandler<PointT>::PointCloud::ConstPtr PointCloudConstPtr;
typedef typename pcl::PointCloud<RGB>::ConstPtr RgbCloudConstPtr;
typedef pcl::PointCloud<RGB>::ConstPtr RgbCloudConstPtr;

public:
typedef boost::shared_ptr<PointCloudColorHandlerRGBCloud<PointT> > Ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ namespace pcl
class StandaloneMarchingCubes
{
public:
typedef typename pcl::PointCloud<PointT> PointCloud;
typedef typename pcl::PointCloud<PointT>::Ptr PointCloudPtr;
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef boost::shared_ptr<pcl::PolygonMesh> MeshPtr;

/** \brief Constructor
Expand Down
4 changes: 2 additions & 2 deletions gpu/kinfu_large_scale/tools/color_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ namespace pcl
using PointCloudColorHandler<PointT>::capable_;
using PointCloudColorHandler<PointT>::cloud_;

typedef typename PointCloudColorHandler<PointT>::PointCloud::ConstPtr PointCloudConstPtr;
typedef typename pcl::PointCloud<RGB>::ConstPtr RgbCloudConstPtr;
typedef typename PointCloudColorHandler<PointT>::PointCloud::ConstPtr PointCloudConstPtr;
typedef pcl::PointCloud<RGB>::ConstPtr RgbCloudConstPtr;

public:
typedef boost::shared_ptr<PointCloudColorHandlerRGBHack<PointT> > Ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,11 +54,11 @@ namespace pcl
class OutofcoreBreadthFirstIterator : public OutofcoreIteratorBase<PointT, ContainerT>
{
public:
typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;
typedef pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;

typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> LeafNode;
typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> BranchNode;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> LeafNode;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> BranchNode;


explicit
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,11 @@ namespace pcl
class OutofcoreDepthFirstIterator : public OutofcoreIteratorBase<PointT, ContainerT>
{
public:
typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;
typedef pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;

typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> LeafNode;
typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> BranchNode;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> LeafNode;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> BranchNode;

explicit
OutofcoreDepthFirstIterator (OctreeDisk& octree_arg);
Expand Down
4 changes: 2 additions & 2 deletions outofcore/include/pcl/outofcore/outofcore_iterator_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,8 @@ namespace pcl
const OutofcoreOctreeBaseNode<ContainerT, PointT>&>/*Reference type*/
{
public:
typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef typename pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;
typedef pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT> OctreeDisk;
typedef pcl::outofcore::OutofcoreOctreeBaseNode<ContainerT, PointT> OctreeDiskNode;

typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT>::BranchNode BranchNode;
typedef typename pcl::outofcore::OutofcoreOctreeBase<ContainerT, PointT>::LeafNode LeafNode;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,8 @@ namespace pcl
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename boost::shared_ptr<PointCloudGeometryHandler<PointT> > Ptr;
typedef typename boost::shared_ptr<const PointCloudGeometryHandler<PointT> > ConstPtr;
typedef boost::shared_ptr<PointCloudGeometryHandler<PointT> > Ptr;
typedef boost::shared_ptr<const PointCloudGeometryHandler<PointT> > ConstPtr;

/** \brief Constructor. */
PointCloudGeometryHandler (const PointCloudConstPtr &cloud) :
Expand Down Expand Up @@ -143,8 +143,8 @@ namespace pcl
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointT> > Ptr;
typedef typename boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointT> > ConstPtr;
typedef boost::shared_ptr<PointCloudGeometryHandlerXYZ<PointT> > Ptr;
typedef boost::shared_ptr<const PointCloudGeometryHandlerXYZ<PointT> > ConstPtr;

/** \brief Constructor. */
PointCloudGeometryHandlerXYZ (const PointCloudConstPtr &cloud);
Expand Down Expand Up @@ -191,8 +191,8 @@ namespace pcl
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointT> > Ptr;
typedef typename boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointT> > ConstPtr;
typedef boost::shared_ptr<PointCloudGeometryHandlerSurfaceNormal<PointT> > Ptr;
typedef boost::shared_ptr<const PointCloudGeometryHandlerSurfaceNormal<PointT> > ConstPtr;

/** \brief Constructor. */
PointCloudGeometryHandlerSurfaceNormal (const PointCloudConstPtr &cloud);
Expand Down Expand Up @@ -236,8 +236,8 @@ namespace pcl
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;

typedef typename boost::shared_ptr<PointCloudGeometryHandlerCustom<PointT> > Ptr;
typedef typename boost::shared_ptr<const PointCloudGeometryHandlerCustom<PointT> > ConstPtr;
typedef boost::shared_ptr<PointCloudGeometryHandlerCustom<PointT> > Ptr;
typedef boost::shared_ptr<const PointCloudGeometryHandlerCustom<PointT> > ConstPtr;

/** \brief Constructor. */
PointCloudGeometryHandlerCustom (const PointCloudConstPtr &cloud,
Expand Down

0 comments on commit 213da11

Please sign in to comment.