Skip to content

Commit

Permalink
Merge pull request #3138 from SunBlack/modernize-use-using_io
Browse files Browse the repository at this point in the history
Use using instead of typedef [io]
  • Loading branch information
taketwo authored Jun 11, 2019
2 parents 388cac7 + fc7e91f commit dcd11a6
Show file tree
Hide file tree
Showing 49 changed files with 263 additions and 293 deletions.
6 changes: 3 additions & 3 deletions io/include/pcl/compression/color_coding.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,9 +62,9 @@ namespace pcl
{

// public typedefs
typedef pcl::PointCloud<PointT> PointCloud;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointT>;
using PointCloudPtr = boost::shared_ptr<PointCloud>;
using PointCloudConstPtr = boost::shared_ptr<const PointCloud>;

public:

Expand Down
4 changes: 2 additions & 2 deletions io/include/pcl/compression/entropy_range_coder.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ namespace pcl
decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector<char>& outputByteVector_arg);

protected:
typedef boost::uint32_t DWord; // 4 bytes
using DWord = boost::uint32_t; // 4 bytes

private:
/** vector containing compressed data
Expand Down Expand Up @@ -162,7 +162,7 @@ namespace pcl
decodeStreamToCharVector (std::istream& inputByteStream_arg, std::vector<char>& outputByteVector_arg);

protected:
typedef boost::uint32_t DWord; // 4 bytes
using DWord = boost::uint32_t; // 4 bytes

/** \brief Helper function to calculate the binary logarithm
* \param n_arg: some value
Expand Down
18 changes: 9 additions & 9 deletions io/include/pcl/compression/octree_pointcloud_compression.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,19 +73,19 @@ namespace pcl
{
public:
// public typedefs
typedef typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloud PointCloud;
typedef typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudPtr PointCloudPtr;
typedef typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudConstPtr PointCloudConstPtr;
using PointCloud = typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloud;
using PointCloudPtr = typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudPtr;
using PointCloudConstPtr = typename OctreePointCloud<PointT, LeafT, BranchT, OctreeT>::PointCloudConstPtr;

// Boost shared pointers
typedef boost::shared_ptr<OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeT> > Ptr;
typedef boost::shared_ptr<const OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeT> > ConstPtr;
using Ptr = boost::shared_ptr<OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeT> >;
using ConstPtr = boost::shared_ptr<const OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeT> >;

typedef typename OctreeT::LeafNode LeafNode;
typedef typename OctreeT::BranchNode BranchNode;
using LeafNode = typename OctreeT::LeafNode;
using BranchNode = typename OctreeT::BranchNode;

typedef OctreePointCloudCompression<PointT, LeafT, BranchT, Octree2BufBase<LeafT, BranchT> > RealTimeStreamCompression;
typedef OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeBase<LeafT, BranchT> > SinglePointCloudCompressionLowMemory;
using RealTimeStreamCompression = OctreePointCloudCompression<PointT, LeafT, BranchT, Octree2BufBase<LeafT, BranchT> >;
using SinglePointCloudCompressionLowMemory = OctreePointCloudCompression<PointT, LeafT, BranchT, OctreeBase<LeafT, BranchT> >;


/** \brief Constructor
Expand Down
6 changes: 3 additions & 3 deletions io/include/pcl/compression/organized_pointcloud_compression.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,9 +60,9 @@ namespace pcl
class OrganizedPointCloudCompression
{
public:
typedef pcl::PointCloud<PointT> PointCloud;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointT>;
using PointCloudPtr = boost::shared_ptr<PointCloud>;
using PointCloudConstPtr = boost::shared_ptr<const PointCloud>;

/** \brief Empty Constructor. */
OrganizedPointCloudCompression ()
Expand Down
6 changes: 3 additions & 3 deletions io/include/pcl/compression/point_coding.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ namespace pcl
class PointCoding
{
// public typedefs
typedef pcl::PointCloud<PointT> PointCloud;
typedef boost::shared_ptr<PointCloud> PointCloudPtr;
typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
using PointCloud = pcl::PointCloud<PointT>;
using PointCloudPtr = boost::shared_ptr<PointCloud>;
using PointCloudConstPtr = boost::shared_ptr<const PointCloud>;

public:
/** \brief Constructor. */
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/buffers.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ namespace pcl

public:

typedef T value_type;
using value_type = T;

virtual
~Buffer ();
Expand Down
23 changes: 9 additions & 14 deletions io/include/pcl/io/davidsdk_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,26 +67,21 @@ namespace pcl
{
public:
/** @cond */
typedef boost::shared_ptr<DavidSDKGrabber> Ptr;
typedef boost::shared_ptr<const DavidSDKGrabber> ConstPtr;
using Ptr = boost::shared_ptr<DavidSDKGrabber>;
using ConstPtr = boost::shared_ptr<const DavidSDKGrabber>;

// Define callback signature typedefs
typedef void
(sig_cb_davidsdk_point_cloud) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &);
using sig_cb_davidsdk_point_cloud = void() (const pcl::PointCloud<pcl::PointXYZ>::Ptr &);

typedef void
(sig_cb_davidsdk_mesh) (const pcl::PolygonMesh::Ptr &);
using sig_cb_davidsdk_mesh = void() (const pcl::PolygonMesh::Ptr &);

typedef void
(sig_cb_davidsdk_image) (const boost::shared_ptr<pcl::PCLImage> &);
using sig_cb_davidsdk_image = void() (const boost::shared_ptr<pcl::PCLImage> &);

typedef void
(sig_cb_davidsdk_point_cloud_image) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &,
const boost::shared_ptr<pcl::PCLImage> &);
using sig_cb_davidsdk_point_cloud_image = void()
(const pcl::PointCloud<pcl::PointXYZ>::Ptr &, const boost::shared_ptr<pcl::PCLImage> &);

typedef void
(sig_cb_davidsdk_mesh_image) (const pcl::PolygonMesh::Ptr &,
const boost::shared_ptr<pcl::PCLImage> &);
using sig_cb_davidsdk_mesh_image = void()
(const pcl::PolygonMesh::Ptr &, const boost::shared_ptr<pcl::PCLImage> &);
/** @endcond */

/** @brief Constructor */
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/depth_sense/depth_sense_device_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ namespace pcl

public:

typedef boost::shared_ptr<DepthSenseDeviceManager> Ptr;
using Ptr = boost::shared_ptr<DepthSenseDeviceManager>;

static Ptr&
getInstance ()
Expand Down
4 changes: 2 additions & 2 deletions io/include/pcl/io/depth_sense/depth_sense_grabber_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ namespace pcl

boost::shared_ptr<DepthSense::ProjectionHelper> projection_;

typedef DepthSenseGrabber::sig_cb_depth_sense_point_cloud sig_cb_depth_sense_point_cloud;
typedef DepthSenseGrabber::sig_cb_depth_sense_point_cloud_rgba sig_cb_depth_sense_point_cloud_rgba;
using sig_cb_depth_sense_point_cloud = DepthSenseGrabber::sig_cb_depth_sense_point_cloud;
using sig_cb_depth_sense_point_cloud_rgba = DepthSenseGrabber::sig_cb_depth_sense_point_cloud_rgba;

/// Signal to indicate whether new XYZ cloud is available
boost::signals2::signal<sig_cb_depth_sense_point_cloud>* point_cloud_signal_;
Expand Down
8 changes: 2 additions & 6 deletions io/include/pcl/io/depth_sense_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,9 @@ namespace pcl

public:

typedef
void (sig_cb_depth_sense_point_cloud)
(const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&);
using sig_cb_depth_sense_point_cloud = void () (const pcl::PointCloud<pcl::PointXYZ>::ConstPtr&);

typedef
void (sig_cb_depth_sense_point_cloud_rgba)
(const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&);
using sig_cb_depth_sense_point_cloud_rgba = void () (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&);

enum Mode
{
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/dinast_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ namespace pcl
class PCL_EXPORTS DinastGrabber: public Grabber
{
// Define callback signature typedefs
typedef void (sig_cb_dinast_point_cloud) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
using sig_cb_dinast_point_cloud = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> > &);

public:
/** \brief Constructor that sets up the grabber constants.
Expand Down
17 changes: 7 additions & 10 deletions io/include/pcl/io/ensenso_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,23 +67,20 @@ namespace pcl
*/
class PCL_EXPORTS EnsensoGrabber : public Grabber
{
typedef std::pair<pcl::PCLImage, pcl::PCLImage> PairOfImages;
using PairOfImages = std::pair<pcl::PCLImage, pcl::PCLImage>;

public:
/** @cond */
typedef boost::shared_ptr<EnsensoGrabber> Ptr;
typedef boost::shared_ptr<const EnsensoGrabber> ConstPtr;
using Ptr = boost::shared_ptr<EnsensoGrabber>;
using ConstPtr = boost::shared_ptr<const EnsensoGrabber>;

// Define callback signature typedefs
typedef void
(sig_cb_ensenso_point_cloud) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &);
using sig_cb_ensenso_point_cloud = void() (const pcl::PointCloud<pcl::PointXYZ>::Ptr &);

typedef void
(sig_cb_ensenso_images) (const boost::shared_ptr<PairOfImages> &);
using sig_cb_ensenso_images void() (const boost::shared_ptr<PairOfImages> &);

typedef void
(sig_cb_ensenso_point_cloud_images) (const pcl::PointCloud<pcl::PointXYZ>::Ptr &,
const boost::shared_ptr<PairOfImages> &);
using sig_cb_ensenso_point_cloud_images = void()
(const pcl::PointCloud<pcl::PointXYZ>::Ptr &, const boost::shared_ptr<PairOfImages> &);
/** @endcond */

/** @brief Constructor */
Expand Down
10 changes: 5 additions & 5 deletions io/include/pcl/io/grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,7 @@ namespace pcl
template<typename T> boost::signals2::signal<T>*
Grabber::find_signal () const
{
typedef boost::signals2::signal<T> Signal;
using Signal = boost::signals2::signal<T>;

std::map<std::string, boost::signals2::signal_base*>::const_iterator signal_it = signals_.find (typeid (T).name ());
if (signal_it != signals_.end ())
Expand All @@ -172,7 +172,7 @@ namespace pcl
template<typename T> void
Grabber::disconnect_all_slots ()
{
typedef boost::signals2::signal<T> Signal;
using Signal = boost::signals2::signal<T>;

if (signals_.find (typeid (T).name ()) != signals_.end ())
{
Expand Down Expand Up @@ -216,7 +216,7 @@ namespace pcl
template<typename T> int
Grabber::num_slots () const
{
typedef boost::signals2::signal<T> Signal;
using Signal = boost::signals2::signal<T>;

// see if we have a signal for this type
std::map<std::string, boost::signals2::signal_base*>::const_iterator signal_it = signals_.find (typeid (T).name ());
Expand All @@ -231,7 +231,7 @@ namespace pcl
template<typename T> boost::signals2::signal<T>*
Grabber::createSignal ()
{
typedef boost::signals2::signal<T> Signal;
using Signal = boost::signals2::signal<T>;

if (signals_.find (typeid (T).name ()) == signals_.end ())
{
Expand All @@ -245,7 +245,7 @@ namespace pcl
template<typename T> boost::signals2::connection
Grabber::registerCallback (const std::function<T> & callback)
{
typedef boost::signals2::signal<T> Signal;
using Signal = boost::signals2::signal<T>;
if (signals_.find (typeid (T).name ()) == signals_.end ())
{
std::stringstream sstream;
Expand Down
36 changes: 12 additions & 24 deletions io/include/pcl/io/hdl_grabber.h
Original file line number Diff line number Diff line change
Expand Up @@ -63,53 +63,41 @@ namespace pcl
/** \brief Signal used for a single sector
* Represents 1 corrected packet from the HDL Velodyne
*/
typedef void
(sig_cb_velodyne_hdl_scan_point_cloud_xyz) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&,
float,
float);
using sig_cb_velodyne_hdl_scan_point_cloud_xyz = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> > &, float, float);

/** \brief Signal used for a single sector
* Represents 1 corrected packet from the HDL Velodyne. Each laser has a different RGB
*/
typedef void
(sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&,
float,
float);
using sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> > &, float, float);

[[deprecated("use sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba instead")]]
typedef sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb;
using sig_cb_velodyne_hdl_scan_point_cloud_xyzrgb [[deprecated("use sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba instead")]]
= sig_cb_velodyne_hdl_scan_point_cloud_xyzrgba;

/** \brief Signal used for a single sector
* Represents 1 corrected packet from the HDL Velodyne with the returned intensity.
*/
typedef void
(sig_cb_velodyne_hdl_scan_point_cloud_xyzi) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&,
float startAngle,
float);
using sig_cb_velodyne_hdl_scan_point_cloud_xyzi = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> > &, float, float);

/** \brief Signal used for a 360 degree sweep
* Represents multiple corrected packets from the HDL Velodyne
* This signal is sent when the Velodyne passes angle "0"
*/
typedef void
(sig_cb_velodyne_hdl_sweep_point_cloud_xyz) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> >&);
using sig_cb_velodyne_hdl_sweep_point_cloud_xyz = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZ> > &);

/** \brief Signal used for a 360 degree sweep
* Represents multiple corrected packets from the HDL Velodyne with the returned intensity
* This signal is sent when the Velodyne passes angle "0"
*/
typedef void
(sig_cb_velodyne_hdl_sweep_point_cloud_xyzi) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> >&);
using sig_cb_velodyne_hdl_sweep_point_cloud_xyzi = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZI> > &);

/** \brief Signal used for a 360 degree sweep
* Represents multiple corrected packets from the HDL Velodyne
* This signal is sent when the Velodyne passes angle "0". Each laser has a different RGB
*/
typedef void
(sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba) (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> >&);
using sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba = void (const boost::shared_ptr<const pcl::PointCloud<pcl::PointXYZRGBA> > &);

[[deprecated("use sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba instead")]]
typedef sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb;
using sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgb [[deprecated("use sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba instead")]]
= sig_cb_velodyne_hdl_sweep_point_cloud_xyzrgba;

/** \brief Constructor taking an optional path to an HDL corrections file. The Grabber will listen on the default IP/port for data packets [192.168.3.255/2368]
* \param[in] correctionsFile Path to a file which contains the correction parameters for the HDL. This parameter is mandatory for the HDL-64, optional for the HDL-32
Expand Down Expand Up @@ -224,11 +212,11 @@ namespace pcl
};

#pragma pack(push, 1)
typedef struct HDLLaserReturn
struct HDLLaserReturn
{
uint16_t distance;
uint8_t intensity;
} HDLLaserReturn;
};
#pragma pack(pop)

struct HDLFiringData
Expand Down
12 changes: 6 additions & 6 deletions io/include/pcl/io/image.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,18 +57,18 @@ namespace pcl
class PCL_EXPORTS Image
{
public:
typedef boost::shared_ptr<Image> Ptr;
typedef boost::shared_ptr<const Image> ConstPtr;
using Ptr = boost::shared_ptr<Image>;
using ConstPtr = boost::shared_ptr<const Image>;

typedef boost::chrono::high_resolution_clock Clock;
typedef boost::chrono::high_resolution_clock::time_point Timestamp;
using Clock = boost::chrono::high_resolution_clock;
using Timestamp = boost::chrono::high_resolution_clock::time_point;

typedef enum
enum Encoding
{
BAYER_GRBG,
YUV422,
RGB
} Encoding;
};

Image (FrameWrapper::Ptr image_metadata)
: wrapper_ (image_metadata)
Expand Down
8 changes: 4 additions & 4 deletions io/include/pcl/io/image_depth.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,11 +55,11 @@ namespace pcl
class PCL_EXPORTS DepthImage
{
public:
typedef boost::shared_ptr<DepthImage> Ptr;
typedef boost::shared_ptr<const DepthImage> ConstPtr;
using Ptr = boost::shared_ptr<DepthImage>;
using ConstPtr = boost::shared_ptr<const DepthImage>;

typedef boost::chrono::high_resolution_clock Clock;
typedef boost::chrono::high_resolution_clock::time_point Timestamp;
using Clock = boost::chrono::high_resolution_clock;
using Timestamp = boost::chrono::high_resolution_clock::time_point;

/** \brief Constructor
* \param[in] depth_metadata the actual data from the OpenNI library
Expand Down
8 changes: 4 additions & 4 deletions io/include/pcl/io/image_ir.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,11 @@ namespace pcl
class PCL_EXPORTS IRImage
{
public:
typedef boost::shared_ptr<IRImage> Ptr;
typedef boost::shared_ptr<const IRImage> ConstPtr;
using Ptr = boost::shared_ptr<IRImage>;
using ConstPtr = boost::shared_ptr<const IRImage>;

typedef boost::chrono::high_resolution_clock Clock;
typedef boost::chrono::high_resolution_clock::time_point Timestamp;
using Clock = boost::chrono::high_resolution_clock;
using Timestamp = boost::chrono::high_resolution_clock::time_point;

IRImage (FrameWrapper::Ptr ir_metadata);
IRImage (FrameWrapper::Ptr ir_metadata, Timestamp time);
Expand Down
2 changes: 1 addition & 1 deletion io/include/pcl/io/image_metadata_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ namespace pcl
class FrameWrapper
{
public:
typedef boost::shared_ptr<FrameWrapper> Ptr;
using Ptr = boost::shared_ptr<FrameWrapper>;

virtual
~FrameWrapper() = default;
Expand Down
Loading

0 comments on commit dcd11a6

Please sign in to comment.