Skip to content

Commit

Permalink
Merge pull request #3129 from SunBlack/modernize-use-using_simulation…
Browse files Browse the repository at this point in the history
…_stereo_surface

Use using instead of typedef [simulation, stereo, surface ]
  • Loading branch information
taketwo authored Jun 12, 2019
2 parents 0acfeed + 8849555 commit 560810b
Show file tree
Hide file tree
Showing 29 changed files with 127 additions and 127 deletions.
4 changes: 2 additions & 2 deletions simulation/include/pcl/simulation/camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,8 @@ namespace pcl
class PCL_EXPORTS Camera
{
public:
typedef boost::shared_ptr<Camera> Ptr;
typedef boost::shared_ptr<const Camera> ConstPtr;
using Ptr = boost::shared_ptr<Camera>;
using ConstPtr = boost::shared_ptr<const Camera>;

Camera () : x_ (0), y_ (0), z_ (0), roll_ (0), pitch_ (0), yaw_ (0)
{
Expand Down
4 changes: 2 additions & 2 deletions simulation/include/pcl/simulation/glsl_shader.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ namespace pcl
class PCL_EXPORTS Program
{
public:
typedef boost::shared_ptr<Program> Ptr;
typedef boost::shared_ptr<const Program> ConstPtr;
using Ptr = boost::shared_ptr<Program>;
using ConstPtr = boost::shared_ptr<const Program>;

/**
* Construct an empty shader program.
Expand Down
28 changes: 14 additions & 14 deletions simulation/include/pcl/simulation/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,13 @@ namespace pcl
{
namespace simulation
{
typedef struct _SinglePoly
struct SinglePoly
{
float* vertices_;
float* colors_;
GLenum mode_;
GLuint nvertices_;
} SinglePoly;
};

struct Vertex
{
Expand All @@ -56,23 +56,23 @@ namespace pcl
Eigen::Vector3f norm;
};

typedef std::vector<Vertex> Vertices;
typedef std::vector<GLuint> Indices;
using Vertices = std::vector<Vertex>;
using Indices = std::vector<GLuint>;

class Model
{
public:
virtual void draw () = 0;

typedef boost::shared_ptr<Model> Ptr;
typedef boost::shared_ptr<const Model> ConstPtr;
using Ptr = boost::shared_ptr<Model>;
using ConstPtr = boost::shared_ptr<const Model>;
};

class PCL_EXPORTS TriangleMeshModel : public Model
{
public:
typedef boost::shared_ptr<TriangleMeshModel> Ptr;
typedef boost::shared_ptr<const TriangleMeshModel> ConstPtr;
using Ptr = boost::shared_ptr<TriangleMeshModel>;
using ConstPtr = boost::shared_ptr<const TriangleMeshModel>;

TriangleMeshModel (pcl::PolygonMesh::Ptr plg);

Expand All @@ -97,8 +97,8 @@ namespace pcl
virtual ~PolygonMeshModel();
void draw() override;

typedef boost::shared_ptr<PolygonMeshModel> Ptr;
typedef boost::shared_ptr<const PolygonMeshModel> ConstPtr;
using Ptr = boost::shared_ptr<PolygonMeshModel>;
using ConstPtr = boost::shared_ptr<const PolygonMeshModel>;
private:
std::vector<SinglePoly> polygons;

Expand All @@ -120,8 +120,8 @@ namespace pcl
class PCL_EXPORTS PointCloudModel : public Model
{
public:
typedef boost::shared_ptr<PointCloudModel> Ptr;
typedef boost::shared_ptr<const PointCloudModel> ConstPtr;
using Ptr = boost::shared_ptr<PointCloudModel>;
using ConstPtr = boost::shared_ptr<const PointCloudModel>;

PointCloudModel (GLenum mode, pcl::PointCloud<pcl::PointXYZRGB>::Ptr pc);

Expand Down Expand Up @@ -185,8 +185,8 @@ namespace pcl
class PCL_EXPORTS TexturedQuad
{
public:
typedef boost::shared_ptr<TexturedQuad> Ptr;
typedef boost::shared_ptr<const TexturedQuad> ConstPtr;
using Ptr = boost::shared_ptr<TexturedQuad>;
using ConstPtr = boost::shared_ptr<const TexturedQuad>;

TexturedQuad (int width, int height);
~TexturedQuad ();
Expand Down
4 changes: 2 additions & 2 deletions simulation/include/pcl/simulation/range_likelihood.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ namespace pcl
class PCL_EXPORTS RangeLikelihood
{
public:
typedef boost::shared_ptr<RangeLikelihood> Ptr;
typedef boost::shared_ptr<const RangeLikelihood> ConstPtr;
using Ptr = boost::shared_ptr<RangeLikelihood>;
using ConstPtr = boost::shared_ptr<const RangeLikelihood>;

public:
/**
Expand Down
4 changes: 2 additions & 2 deletions simulation/include/pcl/simulation/scene.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,8 @@ namespace pcl
class PCL_EXPORTS Scene
{
public:
typedef boost::shared_ptr<Scene> Ptr;
typedef boost::shared_ptr<Scene> ConstPtr;
using Ptr = boost::shared_ptr<Scene>;
using ConstPtr = boost::shared_ptr<Scene>;

void
draw ();
Expand Down
12 changes: 6 additions & 6 deletions simulation/tools/sim_viewer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,13 +106,13 @@ using namespace pcl::simulation;

using namespace std;

typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;
typedef ColorHandler::Ptr ColorHandlerPtr;
typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
using ColorHandler = pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2>;
using ColorHandlerPtr = ColorHandler::Ptr;
using ColorHandlerConstPtr = ColorHandler::ConstPtr;

typedef pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2> GeometryHandler;
typedef GeometryHandler::Ptr GeometryHandlerPtr;
typedef GeometryHandler::ConstPtr GeometryHandlerConstPtr;
using GeometryHandler = pcl::visualization::PointCloudGeometryHandler<pcl::PCLPointCloud2>;
using GeometryHandlerPtr = GeometryHandler::Ptr;
using GeometryHandlerConstPtr = GeometryHandler::ConstPtr;

#define NORMALS_SCALE 0.01
#define PC_SCALE 0.001
Expand Down
4 changes: 2 additions & 2 deletions simulation/tools/simulation_io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@ namespace pcl
class PCL_EXPORTS SimExample
{
public:
typedef boost::shared_ptr<SimExample> Ptr;
typedef boost::shared_ptr<const SimExample> ConstPtr;
using Ptr = boost::shared_ptr<SimExample>;
using ConstPtr = boost::shared_ptr<const SimExample>;

SimExample (int argc, char** argv,
int height,int width);
Expand Down
2 changes: 1 addition & 1 deletion stereo/include/pcl/stereo/disparity_map_converter.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ namespace pcl
class DisparityMapConverter
{
protected:
typedef pcl::PointCloud<PointT> PointCloud;
using PointCloud = pcl::PointCloud<PointT>;

public:
/** \brief DisparityMapConverter constructor. */
Expand Down
2 changes: 1 addition & 1 deletion surface/include/pcl/surface/bilateral_upsampling.h
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ namespace pcl
using PCLBase<PointInT>::deinitCompute;
using CloudSurfaceProcessing<PointInT, PointOutT>::process;

typedef pcl::PointCloud<PointOutT> PointCloudOut;
using PointCloudOut = pcl::PointCloud<PointOutT>;

Eigen::Matrix3f KinectVGAProjectionMatrix, KinectSXGAProjectionMatrix;

Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/concave_hull.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ namespace pcl
class ConcaveHull : public MeshConstruction<PointInT>
{
protected:
typedef boost::shared_ptr<ConcaveHull<PointInT> > Ptr;
typedef boost::shared_ptr<const ConcaveHull<PointInT> > ConstPtr;
using Ptr = boost::shared_ptr<ConcaveHull<PointInT> >;
using ConstPtr = boost::shared_ptr<const ConcaveHull<PointInT> >;

using PCLBase<PointInT>::input_;
using PCLBase<PointInT>::indices_;
Expand All @@ -66,9 +66,9 @@ namespace pcl
public:
using MeshConstruction<PointInT>::reconstruct;

typedef pcl::PointCloud<PointInT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointInT>;
using PointCloudPtr = typename PointCloud::Ptr;
using PointCloudConstPtr = typename PointCloud::ConstPtr;

/** \brief Empty constructor. */
ConcaveHull () : alpha_ (0), keep_information_ (false), voronoi_centers_ (), dim_(0)
Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/convex_hull.h
Original file line number Diff line number Diff line change
Expand Up @@ -77,14 +77,14 @@ namespace pcl
using PCLBase<PointInT>::deinitCompute;

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

using MeshConstruction<PointInT>::reconstruct;

typedef pcl::PointCloud<PointInT> PointCloud;
typedef typename PointCloud::Ptr PointCloudPtr;
typedef typename PointCloud::ConstPtr PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointInT>;
using PointCloudPtr = typename PointCloud::Ptr;
using PointCloudConstPtr = typename PointCloud::ConstPtr;

/** \brief Empty constructor. */
ConvexHull () : compute_area_ (false), total_area_ (0), total_volume_ (0), dimension_ (0),
Expand Down
4 changes: 2 additions & 2 deletions surface/include/pcl/surface/ear_clipping.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,8 +52,8 @@ namespace pcl
class PCL_EXPORTS EarClipping : public MeshProcessing
{
public:
typedef boost::shared_ptr<EarClipping> Ptr;
typedef boost::shared_ptr<const EarClipping> ConstPtr;
using Ptr = boost::shared_ptr<EarClipping>;
using ConstPtr = boost::shared_ptr<const EarClipping>;

using MeshProcessing::input_mesh_;
using MeshProcessing::initCompute;
Expand Down
14 changes: 7 additions & 7 deletions surface/include/pcl/surface/gp3.h
Original file line number Diff line number Diff line change
Expand Up @@ -136,19 +136,19 @@ namespace pcl
class GreedyProjectionTriangulation : public MeshConstruction<PointInT>
{
public:
typedef boost::shared_ptr<GreedyProjectionTriangulation<PointInT> > Ptr;
typedef boost::shared_ptr<const GreedyProjectionTriangulation<PointInT> > ConstPtr;
using Ptr = boost::shared_ptr<GreedyProjectionTriangulation<PointInT> >;
using ConstPtr = boost::shared_ptr<const GreedyProjectionTriangulation<PointInT> >;

using MeshConstruction<PointInT>::tree_;
using MeshConstruction<PointInT>::input_;
using MeshConstruction<PointInT>::indices_;

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

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

enum GP3Type
{
Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/grid_projection.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,16 +73,16 @@ namespace pcl
class GridProjection : public SurfaceReconstruction<PointNT>
{
public:
typedef boost::shared_ptr<GridProjection<PointNT> > Ptr;
typedef boost::shared_ptr<const GridProjection<PointNT> > ConstPtr;
using Ptr = boost::shared_ptr<GridProjection<PointNT> >;
using ConstPtr = boost::shared_ptr<const GridProjection<PointNT> >;

using SurfaceReconstruction<PointNT>::input_;
using SurfaceReconstruction<PointNT>::tree_;

typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
using PointCloudPtr = typename pcl::PointCloud<PointNT>::Ptr;

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

/** \brief Data leaf. */
struct Leaf
Expand Down
2 changes: 1 addition & 1 deletion surface/include/pcl/surface/impl/mls.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ pcl::MovingLeastSquares<PointInT, PointOutT>::process (PointCloudOut &output)

for (size_t i = 0; i < output.size (); ++i)
{
typedef typename pcl::traits::fieldList<PointOutT>::type FieldList;
using FieldList = typename pcl::traits::fieldList<PointOutT>::type;
pcl::for_each_type<FieldList> (SetIfFieldExists<PointOutT, float> (output.points[i], "normal_x", normals_->points[i].normal_x));
pcl::for_each_type<FieldList> (SetIfFieldExists<PointOutT, float> (output.points[i], "normal_y", normals_->points[i].normal_y));
pcl::for_each_type<FieldList> (SetIfFieldExists<PointOutT, float> (output.points[i], "normal_z", normals_->points[i].normal_z));
Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/marching_cubes.h
Original file line number Diff line number Diff line change
Expand Up @@ -362,16 +362,16 @@ namespace pcl
class MarchingCubes : public SurfaceReconstruction<PointNT>
{
public:
typedef boost::shared_ptr<MarchingCubes<PointNT> > Ptr;
typedef boost::shared_ptr<const MarchingCubes<PointNT> > ConstPtr;
using Ptr = boost::shared_ptr<MarchingCubes<PointNT> >;
using ConstPtr = boost::shared_ptr<const MarchingCubes<PointNT> >;

using SurfaceReconstruction<PointNT>::input_;
using SurfaceReconstruction<PointNT>::tree_;

typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
using PointCloudPtr = typename pcl::PointCloud<PointNT>::Ptr;

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

/** \brief Constructor. */
MarchingCubes (const float percentage_extend_grid = 0.0f,
Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/marching_cubes_hoppe.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ namespace pcl
class MarchingCubesHoppe : public MarchingCubes<PointNT>
{
public:
typedef boost::shared_ptr<MarchingCubesHoppe<PointNT> > Ptr;
typedef boost::shared_ptr<const MarchingCubesHoppe<PointNT> > ConstPtr;
using Ptr = boost::shared_ptr<MarchingCubesHoppe<PointNT> >;
using ConstPtr = boost::shared_ptr<const MarchingCubesHoppe<PointNT> >;

using SurfaceReconstruction<PointNT>::input_;
using SurfaceReconstruction<PointNT>::tree_;
Expand All @@ -64,10 +64,10 @@ namespace pcl
using MarchingCubes<PointNT>::upper_boundary_;
using MarchingCubes<PointNT>::lower_boundary_;

typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
using PointCloudPtr = typename pcl::PointCloud<PointNT>::Ptr;

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


/** \brief Constructor. */
Expand Down
10 changes: 5 additions & 5 deletions surface/include/pcl/surface/marching_cubes_rbf.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,8 @@ namespace pcl
class MarchingCubesRBF : public MarchingCubes<PointNT>
{
public:
typedef boost::shared_ptr<MarchingCubesRBF<PointNT> > Ptr;
typedef boost::shared_ptr<const MarchingCubesRBF<PointNT> > ConstPtr;
using Ptr = boost::shared_ptr<MarchingCubesRBF<PointNT> >;
using ConstPtr = boost::shared_ptr<const MarchingCubesRBF<PointNT> >;

using SurfaceReconstruction<PointNT>::input_;
using SurfaceReconstruction<PointNT>::tree_;
Expand All @@ -66,10 +66,10 @@ namespace pcl
using MarchingCubes<PointNT>::upper_boundary_;
using MarchingCubes<PointNT>::lower_boundary_;

typedef typename pcl::PointCloud<PointNT>::Ptr PointCloudPtr;
using PointCloudPtr = typename pcl::PointCloud<PointNT>::Ptr;

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


/** \brief Constructor. */
Expand Down
22 changes: 11 additions & 11 deletions surface/include/pcl/surface/mls.h
Original file line number Diff line number Diff line change
Expand Up @@ -260,20 +260,20 @@ namespace pcl
using PCLBase<PointInT>::initCompute;
using PCLBase<PointInT>::deinitCompute;

typedef pcl::search::Search<PointInT> KdTree;
typedef typename KdTree::Ptr KdTreePtr;
typedef pcl::PointCloud<pcl::Normal> NormalCloud;
typedef NormalCloud::Ptr NormalCloudPtr;
using KdTree = pcl::search::Search<PointInT>;
using KdTreePtr = typename KdTree::Ptr;
using NormalCloud = pcl::PointCloud<pcl::Normal>;
using NormalCloudPtr = NormalCloud::Ptr;

typedef pcl::PointCloud<PointOutT> PointCloudOut;
typedef typename PointCloudOut::Ptr PointCloudOutPtr;
typedef typename PointCloudOut::ConstPtr PointCloudOutConstPtr;
using PointCloudOut = pcl::PointCloud<PointOutT>;
using PointCloudOutPtr = typename PointCloudOut::Ptr;
using PointCloudOutConstPtr = typename PointCloudOut::ConstPtr;

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

typedef std::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
using SearchMethod = std::function<int (int, double, std::vector<int> &, std::vector<float> &)>;

enum UpsamplingMethod
{
Expand Down
Loading

0 comments on commit 560810b

Please sign in to comment.