Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use using instead of typedef [registration] #3124

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 6 additions & 6 deletions registration/include/pcl/registration/bfgs.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace Eigen
class PolynomialSolver<_Scalar,2> : public PolynomialSolverBase<_Scalar,2>
{
public:
typedef PolynomialSolverBase<_Scalar,2> PS_Base;
using PS_Base = PolynomialSolverBase<_Scalar,2>;
EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base )

public:
Expand Down Expand Up @@ -72,9 +72,9 @@ namespace Eigen
template<typename _Scalar, int NX=Eigen::Dynamic>
struct BFGSDummyFunctor
{
typedef _Scalar Scalar;
using Scalar = _Scalar;
enum { InputsAtCompileTime = NX };
typedef Eigen::Matrix<Scalar,InputsAtCompileTime,1> VectorType;
using VectorType = Eigen::Matrix<Scalar,InputsAtCompileTime,1>;

const int m_inputs;

Expand Down Expand Up @@ -113,13 +113,13 @@ template<typename FunctorType>
class BFGS
{
public:
typedef typename FunctorType::Scalar Scalar;
typedef typename FunctorType::VectorType FVectorType;
using Scalar = typename FunctorType::Scalar;
using FVectorType = typename FunctorType::VectorType;

BFGS(FunctorType &_functor)
: pnorm(0), g0norm(0), iter(-1), functor(_functor) { }

typedef Eigen::DenseIndex Index;
using Index = Eigen::DenseIndex;

struct Parameters {
Parameters()
Expand Down
12 changes: 6 additions & 6 deletions registration/include/pcl/registration/boost_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,13 @@ namespace boost
template <class ValueType>
struct container_gen<eigen_vecS, ValueType>
{
typedef std::vector<ValueType, Eigen::aligned_allocator<ValueType> > type;
using type = std::vector<ValueType, Eigen::aligned_allocator<ValueType> >;
};

template <>
struct parallel_edge_traits<eigen_vecS>
{
typedef allow_parallel_edge_tag type;
using type = allow_parallel_edge_tag;
};

namespace detail
Expand All @@ -68,7 +68,7 @@ namespace boost
struct is_random_access<eigen_vecS>
{
enum { value = true };
typedef mpl::true_ type;
using type = mpl::true_;
};
}

Expand All @@ -79,13 +79,13 @@ namespace boost
template <class ValueType>
struct container_gen<eigen_listS, ValueType>
{
typedef std::list<ValueType, Eigen::aligned_allocator<ValueType> > type;
using type = std::list<ValueType, Eigen::aligned_allocator<ValueType> >;
};

template <>
struct parallel_edge_traits<eigen_listS>
{
typedef allow_parallel_edge_tag type;
using type = allow_parallel_edge_tag;
};

namespace detail
Expand All @@ -94,7 +94,7 @@ namespace boost
struct is_random_access<eigen_listS>
{
enum { value = false };
typedef mpl::false_ type;
using type = mpl::false_;
};
}
}
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/convergence_criteria.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,8 @@ namespace pcl
class PCL_EXPORTS ConvergenceCriteria
{
public:
typedef boost::shared_ptr<ConvergenceCriteria> Ptr;
typedef boost::shared_ptr<const ConvergenceCriteria> ConstPtr;
using Ptr = boost::shared_ptr<ConvergenceCriteria>;
using ConstPtr = boost::shared_ptr<const ConvergenceCriteria>;

/** \brief Empty constructor. */
ConvergenceCriteria () {}
Expand Down
48 changes: 24 additions & 24 deletions registration/include/pcl/registration/correspondence_estimation.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,30 +62,30 @@ namespace pcl
class CorrespondenceEstimationBase: public PCLBase<PointSource>
{
public:
typedef boost::shared_ptr<CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> > Ptr;
typedef boost::shared_ptr<const CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> > ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> >;
using ConstPtr = boost::shared_ptr<const CorrespondenceEstimationBase<PointSource, PointTarget, Scalar> >;

// using PCLBase<PointSource>::initCompute;
using PCLBase<PointSource>::deinitCompute;
using PCLBase<PointSource>::input_;
using PCLBase<PointSource>::indices_;
using PCLBase<PointSource>::setIndices;

typedef pcl::search::KdTree<PointTarget> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
using KdTree = pcl::search::KdTree<PointTarget>;
using KdTreePtr = typename KdTree::Ptr;

typedef pcl::search::KdTree<PointSource> KdTreeReciprocal;
typedef typename KdTree::Ptr KdTreeReciprocalPtr;
using KdTreeReciprocal = pcl::search::KdTree<PointSource>;
using KdTreeReciprocalPtr = typename KdTree::Ptr;

typedef pcl::PointCloud<PointSource> PointCloudSource;
typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
using PointCloudSource = pcl::PointCloud<PointSource>;
using PointCloudSourcePtr = typename PointCloudSource::Ptr;
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;

typedef pcl::PointCloud<PointTarget> PointCloudTarget;
typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
using PointCloudTarget = pcl::PointCloud<PointTarget>;
using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;

typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr;
using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr;

/** \brief Empty constructor. */
CorrespondenceEstimationBase ()
Expand Down Expand Up @@ -361,8 +361,8 @@ namespace pcl
class CorrespondenceEstimation : public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>
{
public:
typedef boost::shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar> > Ptr;
typedef boost::shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar> > ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceEstimation<PointSource, PointTarget, Scalar> >;
using ConstPtr = boost::shared_ptr<const CorrespondenceEstimation<PointSource, PointTarget, Scalar> >;

using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_transformed_;
Expand All @@ -379,18 +379,18 @@ namespace pcl
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::input_fields_;
using PCLBase<PointSource>::deinitCompute;

typedef pcl::search::KdTree<PointTarget> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
using KdTree = pcl::search::KdTree<PointTarget>;
using KdTreePtr = typename KdTree::Ptr;

typedef pcl::PointCloud<PointSource> PointCloudSource;
typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
using PointCloudSource = pcl::PointCloud<PointSource>;
using PointCloudSourcePtr = typename PointCloudSource::Ptr;
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;

typedef pcl::PointCloud<PointTarget> PointCloudTarget;
typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
using PointCloudTarget = pcl::PointCloud<PointTarget>;
using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;

typedef typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr;
using PointRepresentationConstPtr = typename KdTree::PointRepresentationConstPtr;

/** \brief Empty constructor. */
CorrespondenceEstimation ()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ namespace pcl
class CorrespondenceEstimationBackProjection : public CorrespondenceEstimationBase <PointSource, PointTarget, Scalar>
{
public:
typedef boost::shared_ptr<CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> > Ptr;
typedef boost::shared_ptr<const CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> > ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> >;
using ConstPtr = boost::shared_ptr<const CorrespondenceEstimationBackProjection<PointSource, PointTarget, NormalT, Scalar> >;

using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeReciprocal;
Expand All @@ -68,20 +68,20 @@ namespace pcl
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;

typedef pcl::search::KdTree<PointTarget> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
using KdTree = pcl::search::KdTree<PointTarget>;
using KdTreePtr = typename KdTree::Ptr;

typedef pcl::PointCloud<PointSource> PointCloudSource;
typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
using PointCloudSource = pcl::PointCloud<PointSource>;
using PointCloudSourcePtr = typename PointCloudSource::Ptr;
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;

typedef pcl::PointCloud<PointTarget> PointCloudTarget;
typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
using PointCloudTarget = pcl::PointCloud<PointTarget>;
using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;

typedef pcl::PointCloud<NormalT> PointCloudNormals;
typedef typename PointCloudNormals::Ptr NormalsPtr;
typedef typename PointCloudNormals::ConstPtr NormalsConstPtr;
using PointCloudNormals = pcl::PointCloud<NormalT>;
using NormalsPtr = typename PointCloudNormals::Ptr;
using NormalsConstPtr = typename PointCloudNormals::ConstPtr;

/** \brief Empty constructor.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,8 @@ namespace pcl
class CorrespondenceEstimationNormalShooting : public CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>
{
public:
typedef boost::shared_ptr<CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > Ptr;
typedef boost::shared_ptr<const CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> > ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> >;
using ConstPtr = boost::shared_ptr<const CorrespondenceEstimationNormalShooting<PointSource, PointTarget, NormalT, Scalar> >;

using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initCompute;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::initComputeReciprocal;
Expand All @@ -90,20 +90,20 @@ namespace pcl
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_indices_;

typedef pcl::search::KdTree<PointTarget> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
using KdTree = pcl::search::KdTree<PointTarget>;
using KdTreePtr = typename KdTree::Ptr;

typedef pcl::PointCloud<PointSource> PointCloudSource;
typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
using PointCloudSource = pcl::PointCloud<PointSource>;
using PointCloudSourcePtr = typename PointCloudSource::Ptr;
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;

typedef pcl::PointCloud<PointTarget> PointCloudTarget;
typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
using PointCloudTarget = pcl::PointCloud<PointTarget>;
using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;

typedef pcl::PointCloud<NormalT> PointCloudNormals;
typedef typename PointCloudNormals::Ptr NormalsPtr;
typedef typename PointCloudNormals::ConstPtr NormalsConstPtr;
using PointCloudNormals = pcl::PointCloud<NormalT>;
using NormalsPtr = typename PointCloudNormals::Ptr;
using NormalsConstPtr = typename PointCloudNormals::ConstPtr;

/** \brief Empty constructor.
*
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -68,16 +68,16 @@ namespace pcl
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::point_representation_;
using CorrespondenceEstimationBase<PointSource, PointTarget, Scalar>::target_cloud_updated_;

typedef pcl::PointCloud<PointSource> PointCloudSource;
typedef typename PointCloudSource::Ptr PointCloudSourcePtr;
typedef typename PointCloudSource::ConstPtr PointCloudSourceConstPtr;
using PointCloudSource = pcl::PointCloud<PointSource>;
using PointCloudSourcePtr = typename PointCloudSource::Ptr;
using PointCloudSourceConstPtr = typename PointCloudSource::ConstPtr;

typedef pcl::PointCloud<PointTarget> PointCloudTarget;
typedef typename PointCloudTarget::Ptr PointCloudTargetPtr;
typedef typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr;
using PointCloudTarget = pcl::PointCloud<PointTarget>;
using PointCloudTargetPtr = typename PointCloudTarget::Ptr;
using PointCloudTargetConstPtr = typename PointCloudTarget::ConstPtr;

typedef boost::shared_ptr< CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > Ptr;
typedef boost::shared_ptr< const CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> > ConstPtr;
using Ptr = boost::shared_ptr< CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> >;
using ConstPtr = boost::shared_ptr< const CorrespondenceEstimationOrganizedProjection<PointSource, PointTarget, Scalar> >;



Expand Down
18 changes: 9 additions & 9 deletions registration/include/pcl/registration/correspondence_rejection.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ namespace pcl
class CorrespondenceRejector
{
public:
typedef boost::shared_ptr<CorrespondenceRejector> Ptr;
typedef boost::shared_ptr<const CorrespondenceRejector> ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceRejector>;
using ConstPtr = boost::shared_ptr<const CorrespondenceRejector>;

/** \brief Empty constructor. */
CorrespondenceRejector ()
Expand Down Expand Up @@ -212,15 +212,15 @@ namespace pcl
template <typename PointT, typename NormalT = pcl::PointNormal>
class DataContainer : public DataContainerInterface
{
typedef pcl::PointCloud<PointT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointT>;
using PointCloudPtr = typename PointCloud::Ptr;
using PointCloudConstPtr = typename PointCloud::ConstPtr;

typedef typename pcl::search::KdTree<PointT>::Ptr KdTreePtr;
using KdTreePtr = typename pcl::search::KdTree<PointT>::Ptr;

typedef pcl::PointCloud<NormalT> Normals;
typedef typename Normals::Ptr NormalsPtr;
typedef typename Normals::ConstPtr NormalsConstPtr;
using Normals = pcl::PointCloud<NormalT>;
using NormalsPtr = typename Normals::Ptr;
using NormalsConstPtr = typename Normals::ConstPtr;

public:

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,8 @@ namespace pcl
using CorrespondenceRejector::getClassName;

public:
typedef boost::shared_ptr<CorrespondenceRejectorDistance> Ptr;
typedef boost::shared_ptr<const CorrespondenceRejectorDistance> ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceRejectorDistance>;
using ConstPtr = boost::shared_ptr<const CorrespondenceRejectorDistance>;

/** \brief Empty constructor. */
CorrespondenceRejectorDistance () : max_distance_(std::numeric_limits<float>::max ())
Expand Down Expand Up @@ -195,7 +195,7 @@ namespace pcl
*/
float max_distance_;

typedef boost::shared_ptr<DataContainerInterface> DataContainerPtr;
using DataContainerPtr = boost::shared_ptr<DataContainerInterface>;

/** \brief A pointer to the DataContainer object containing the input and target point clouds */
DataContainerPtr data_container_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ namespace pcl
using CorrespondenceRejector::getClassName;

public:
typedef boost::shared_ptr<CorrespondenceRejectorFeatures> Ptr;
typedef boost::shared_ptr<const CorrespondenceRejectorFeatures> ConstPtr;
using Ptr = boost::shared_ptr<CorrespondenceRejectorFeatures>;
using ConstPtr = boost::shared_ptr<const CorrespondenceRejectorFeatures>;

/** \brief Empty constructor. */
CorrespondenceRejectorFeatures () : max_distance_ (std::numeric_limits<float>::max ())
Expand Down Expand Up @@ -162,10 +162,10 @@ namespace pcl
virtual double getCorrespondenceScore (int index) = 0;
virtual bool isCorrespondenceValid (int index) = 0;

typedef boost::shared_ptr<FeatureContainerInterface> Ptr;
using Ptr = boost::shared_ptr<FeatureContainerInterface>;
};

typedef std::unordered_map<std::string, FeatureContainerInterface::Ptr> FeaturesMap;
using FeaturesMap = std::unordered_map<std::string, FeatureContainerInterface::Ptr>;

/** \brief An STL map containing features to use when performing the correspondence search.*/
FeaturesMap features_map_;
Expand All @@ -180,11 +180,10 @@ namespace pcl
class FeatureContainer : public pcl::registration::CorrespondenceRejectorFeatures::FeatureContainerInterface
{
public:
typedef typename pcl::PointCloud<FeatureT>::ConstPtr FeatureCloudConstPtr;
typedef std::function<int (const pcl::PointCloud<FeatureT> &, int, std::vector<int> &,
std::vector<float> &)> SearchMethod;
using FeatureCloudConstPtr = typename pcl::PointCloud<FeatureT>::ConstPtr;
using SearchMethod = std::function<int (const pcl::PointCloud<FeatureT> &, int, std::vector<int> &, std::vector<float> &)>;

typedef typename pcl::PointRepresentation<FeatureT>::ConstPtr PointRepresentationConstPtr;
using PointRepresentationConstPtr = typename pcl::PointRepresentation<FeatureT>::ConstPtr;

FeatureContainer () : thresh_(std::numeric_limits<double>::max ()), feature_representation_()
{
Expand Down
Loading