diff --git a/2d/include/pcl/2d/edge.h b/2d/include/pcl/2d/edge.h index d876c22235a..b4f876e913f 100644 --- a/2d/include/pcl/2d/edge.h +++ b/2d/include/pcl/2d/edge.h @@ -48,8 +48,8 @@ namespace pcl class Edge { private: - typedef pcl::PointCloud PointCloudIn; - typedef typename PointCloudIn::Ptr PointCloudInPtr; + using PointCloudIn = pcl::PointCloud; + using PointCloudInPtr = typename PointCloudIn::Ptr; PointCloudInPtr input_; pcl::Convolution convolution_; @@ -84,8 +84,8 @@ namespace pcl pcl::PointCloud &maxima, float tLow); public: - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; enum OUTPUT_TYPE { diff --git a/2d/include/pcl/2d/morphology.h b/2d/include/pcl/2d/morphology.h index 283e6a07f0d..24d6dd7a18d 100644 --- a/2d/include/pcl/2d/morphology.h +++ b/2d/include/pcl/2d/morphology.h @@ -45,8 +45,8 @@ namespace pcl class Morphology : public PCLBase { private: - typedef pcl::PointCloud PointCloudIn; - typedef typename PointCloudIn::Ptr PointCloudInPtr; + using PointCloudIn = pcl::PointCloud; + using PointCloudInPtr = typename PointCloudIn::Ptr; PointCloudInPtr structuring_element_; diff --git a/CMakeLists.txt b/CMakeLists.txt index 4e85b59046f..d21beda7b92 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -112,10 +112,6 @@ if(CMAKE_COMPILER_IS_GNUCXX) set(CMAKE_CXX_FLAGS "-Wabi -Wall -Wextra -Wno-unknown-pragmas -fno-strict-aliasing -Wno-format-extra-args -Wno-sign-compare -Wno-invalid-offsetof -Wno-conversion ${SSE_FLAGS_STR}") endif() - if(NOT ANDROID) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pthread") - endif() - if("${CMAKE_SHARED_LINKER_FLAGS}" STREQUAL "" AND NOT CMAKE_SYSTEM_NAME STREQUAL "Darwin") set(CMAKE_SHARED_LINKER_FLAGS "-Wl,--as-needed") endif() @@ -179,7 +175,7 @@ endif() if(CMAKE_COMPILER_IS_PATHSCALE) if("${CMAKE_CXX_FLAGS}" STREQUAL "${CMAKE_CXX_FLAGS_DEFAULT}") - set(CMAKE_CXX_FLAGS "-Wno-uninitialized -zerouv -pthread -mp") + set(CMAKE_CXX_FLAGS "-Wno-uninitialized -zerouv -mp") endif() if("${CMAKE_SHARED_LINKER_FLAGS}" STREQUAL "") set(CMAKE_SHARED_LINKER_FLAGS "-mp") @@ -280,6 +276,9 @@ else() message(STATUS "Not found OpenMP") endif() +# Threads (required) +find_package(Threads REQUIRED) + # Eigen (required) find_package(Eigen 3.1 REQUIRED) include_directories(SYSTEM ${EIGEN_INCLUDE_DIRS}) @@ -421,12 +420,6 @@ configure_file("${pcl_config_h_in}" "${pcl_config_h}") PCL_ADD_INCLUDES(common "" "${pcl_config_h}") include_directories("${CMAKE_CURRENT_BINARY_DIR}/include") -### ---[ Set up for tests -enable_testing() - -### ---[ Set up for examples -#include("${PCL_SOURCE_DIR}/cmake/pcl_examples.cmake") - ### ---[ Add the libraries subdirectories include("${PCL_SOURCE_DIR}/cmake/pcl_targets.cmake") diff --git a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h index 51b2dca1d9b..5f0fa6120e2 100644 --- a/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h +++ b/apps/3d_rec_framework/include/pcl/apps/3d_rec_framework/pc_source/mesh_source.h @@ -12,9 +12,11 @@ #include #include #include -#include + #include +#include + namespace pcl { namespace rec_3d_framework @@ -42,7 +44,7 @@ namespace pcl float radius_sphere_; float view_angle_; bool gen_organized_; - boost::function campos_constraints_func_; public: @@ -62,7 +64,7 @@ namespace pcl } void - setCamPosConstraints (boost::function & bb) { campos_constraints_func_ = bb; diff --git a/apps/3d_rec_framework/src/tools/global_classification.cpp b/apps/3d_rec_framework/src/tools/global_classification.cpp index 9ddd9649e66..3cfa2da712b 100644 --- a/apps/3d_rec_framework/src/tools/global_classification.cpp +++ b/apps/3d_rec_framework/src/tools/global_classification.cpp @@ -30,7 +30,7 @@ segmentAndClassify (typename pcl::rec_3d_framework::GlobalNNPipeline keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera, _1); vis.registerKeyboardCallback (keyboard_cb); size_t previous_cluster_size = 0; diff --git a/apps/3d_rec_framework/src/tools/openni_frame_source.cpp b/apps/3d_rec_framework/src/tools/openni_frame_source.cpp index 456739d1048..ac3f35a4d6a 100644 --- a/apps/3d_rec_framework/src/tools/openni_frame_source.cpp +++ b/apps/3d_rec_framework/src/tools/openni_frame_source.cpp @@ -8,7 +8,7 @@ namespace OpenNIFrameSource OpenNIFrameSource::OpenNIFrameSource (const std::string& device_id) : grabber_ (device_id), frame_counter_ (0), active_ (true) { - boost::function frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1); grabber_.registerCallback (frame_cb); grabber_.start (); diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h index 065f0eb0352..dc83375cde7 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h @@ -44,9 +44,7 @@ # pragma GCC system_header #endif -#include #include #include #include #include -#include diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h index 11c24ed3b7a..589296c8856 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/common_types.h @@ -83,7 +83,7 @@ namespace pcl typedef pcl::geometry::NoData HalfEdgeData; typedef pcl::geometry::NoData EdgeData; typedef pcl::geometry::NoData FaceData; - typedef boost::true_type IsManifold; + typedef std::true_type IsManifold; }; // NOTE: The drawMesh method in pcl::ihs::InHandScanner only supports triangles! diff --git a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h index bc911f0fca4..4f979d378a9 100644 --- a/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h +++ b/apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/opengl_viewer.h @@ -52,6 +52,7 @@ #include #include #include +#include namespace pcl { @@ -331,7 +332,7 @@ namespace pcl typedef Eigen::Matrix Colors; typedef Eigen::Matrix Colormap; - typedef boost::unordered_map CloudXYZRGBNormalMap; + typedef std::unordered_map CloudXYZRGBNormalMap; typedef pcl::ihs::PointIHS PointIHS; typedef pcl::ihs::CloudIHS CloudIHS; @@ -341,7 +342,7 @@ namespace pcl typedef pcl::ihs::detail::FaceVertexMesh FaceVertexMesh; typedef boost::shared_ptr < FaceVertexMesh> FaceVertexMeshPtr; typedef boost::shared_ptr FaceVertexMeshConstPtr; - typedef boost::unordered_map FaceVertexMeshMap; + typedef std::unordered_map FaceVertexMeshMap; /** \brief Check if the mesh with the given id is added. * \note Must lock the mutex before calling this method. diff --git a/apps/in_hand_scanner/src/in_hand_scanner.cpp b/apps/in_hand_scanner/src/in_hand_scanner.cpp index e343466203b..7889d9735aa 100644 --- a/apps/in_hand_scanner/src/in_hand_scanner.cpp +++ b/apps/in_hand_scanner/src/in_hand_scanner.cpp @@ -483,7 +483,7 @@ pcl::ihs::InHandScanner::startGrabberImpl () lock.lock (); if (destructor_called_) return; - boost::function new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1); + std::function new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1); new_data_connection_ = grabber_->registerCallback (new_data_cb); grabber_->start (); diff --git a/apps/include/pcl/apps/organized_segmentation_demo.h b/apps/include/pcl/apps/organized_segmentation_demo.h index ad8ea2ede4b..56e56015122 100644 --- a/apps/include/pcl/apps/organized_segmentation_demo.h +++ b/apps/include/pcl/apps/organized_segmentation_demo.h @@ -1,15 +1,15 @@ /* * Software License Agreement (BSD License) - * + * * Point Cloud Library (PCL) - www.pointclouds.org * Copyright (c) 2012-, Open Perception, Inc. - * + * * All rights reserved. - * + * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions - * are met: - * + * are met: + * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above @@ -19,7 +19,7 @@ * * Neither the name of the copyright holder(s) nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. - * + * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS @@ -89,7 +89,7 @@ class OrganizedSegmentationDemo : public QMainWindow typedef pcl::PointCloud Cloud; typedef Cloud::Ptr CloudPtr; typedef Cloud::ConstPtr CloudConstPtr; - + OrganizedSegmentationDemo(pcl::Grabber& grabber); @@ -98,9 +98,9 @@ class OrganizedSegmentationDemo : public QMainWindow if(grabber_.isRunning()) grabber_.stop(); } - + void cloud_cb (const CloudConstPtr& cloud); - + protected: pcl::visualization::PCLVisualizer::Ptr vis_; pcl::Grabber& grabber_; @@ -113,9 +113,9 @@ class OrganizedSegmentationDemo : public QMainWindow pcl::PointCloud prev_normals_; std::vector, Eigen::aligned_allocator > > prev_regions_; float* prev_distance_map_; - + pcl::PointCloud::CloudVectorType prev_clusters_; - + pcl::IntegralImageNormalEstimation ne; pcl::OrganizedMultiPlaneSegmentation mps; @@ -148,16 +148,16 @@ class OrganizedSegmentationDemo : public QMainWindow void useEuclideanComparatorPressed (); void useRGBComparatorPressed (); void useEdgeAwareComparatorPressed (); - + void displayCurvaturePressed (); void displayDistanceMapPressed (); void displayNormalsPressed (); - + void disableRefinementPressed () { use_planar_refinement_ = false; } - + void usePlanarRefinementPressed () { use_planar_refinement_ = true; @@ -172,7 +172,7 @@ class OrganizedSegmentationDemo : public QMainWindow { use_clustering_ = true; } - + private Q_SLOTS: void diff --git a/apps/include/pcl/apps/render_views_tesselated_sphere.h b/apps/include/pcl/apps/render_views_tesselated_sphere.h index 50f15e53e50..4d0376af935 100644 --- a/apps/include/pcl/apps/render_views_tesselated_sphere.h +++ b/apps/include/pcl/apps/render_views_tesselated_sphere.h @@ -7,10 +7,12 @@ #pragma once +#include + #include #include -#include -#include + +#include namespace pcl { @@ -37,7 +39,7 @@ namespace pcl bool compute_entropy_; vtkSmartPointer polydata_; bool gen_organized_; - boost::function campos_constraints_func_; struct camPosConstraintsAllTrue @@ -64,7 +66,7 @@ namespace pcl } void - setCamPosConstraints (boost::function & bb) + setCamPosConstraints (std::function & bb) { campos_constraints_func_ = bb; } diff --git a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h index 62e643b859a..7db35ac2c09 100644 --- a/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h +++ b/apps/point_cloud_editor/include/pcl/apps/point_cloud_editor/cloudEditorWidget.h @@ -40,8 +40,6 @@ #pragma once -#include -#include #include #include #include @@ -49,6 +47,10 @@ #include #include +#include + +#include + /// @brief class declaration for the widget for editing and viewing /// point clouds. class CloudEditorWidget : public QGLWidget @@ -251,7 +253,7 @@ class CloudEditorWidget : public QGLWidget return lhs.compare(rhs) < 0; } }; - typedef boost::function + typedef std::function FileLoadFunc; typedef std::map FileLoadMap; /// a map of file type extensions to loader functions. @@ -301,7 +303,7 @@ class CloudEditorWidget : public QGLWidget /// A flag indicates whether the cloud is initially colored or not. bool is_colored_; - typedef boost::function KeyMapFunc; + typedef std::function KeyMapFunc; /// map between pressed key and the corresponding functor std::map key_map_; diff --git a/apps/src/dinast_grabber_example.cpp b/apps/src/dinast_grabber_example.cpp index 7ada4ef9619..af720f52b64 100644 --- a/apps/src/dinast_grabber_example.cpp +++ b/apps/src/dinast_grabber_example.cpp @@ -74,7 +74,7 @@ class DinastProcessor run () { - boost::function f = + std::function f = boost::bind (&DinastProcessor::cloud_cb_, this, _1); boost::signals2::connection c = interface.registerCallback (f); diff --git a/apps/src/face_detection/openni_face_detection.cpp b/apps/src/face_detection/openni_face_detection.cpp index aea92209cca..379dfee15b2 100644 --- a/apps/src/face_detection/openni_face_detection.cpp +++ b/apps/src/face_detection/openni_face_detection.cpp @@ -21,7 +21,7 @@ void run(pcl::RFFaceDetectorTrainer & fdrf, bool heat_map = false, bool show_vot vis.addCoordinateSystem (0.1, "global"); //keyboard callback to stop getting frames and finalize application - boost::function keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera, + std::function keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera, _1); vis.registerKeyboardCallback (keyboard_cb); diff --git a/apps/src/face_detection/openni_frame_source.cpp b/apps/src/face_detection/openni_frame_source.cpp index ad64e654f4f..5e3c8a69f01 100644 --- a/apps/src/face_detection/openni_frame_source.cpp +++ b/apps/src/face_detection/openni_frame_source.cpp @@ -8,7 +8,7 @@ namespace OpenNIFrameSource OpenNIFrameSource::OpenNIFrameSource(const std::string& device_id) : grabber_ (device_id), frame_counter_ (0), active_ (true) { - boost::function frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1); + std::function frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1); grabber_.registerCallback (frame_cb); grabber_.start (); } diff --git a/apps/src/ni_agast.cpp b/apps/src/ni_agast.cpp index 5e194068775..fc6dc386c5e 100644 --- a/apps/src/ni_agast.cpp +++ b/apps/src/ni_agast.cpp @@ -193,7 +193,7 @@ class AGASTDemo void init () { - boost::function cloud_cb = boost::bind (&AGASTDemo::cloud_callback, this, _1); + std::function cloud_cb = boost::bind (&AGASTDemo::cloud_callback, this, _1); cloud_connection = grabber_.registerCallback (cloud_cb); } diff --git a/apps/src/ni_brisk.cpp b/apps/src/ni_brisk.cpp index 7d1b89fd410..6e398a47b8e 100644 --- a/apps/src/ni_brisk.cpp +++ b/apps/src/ni_brisk.cpp @@ -101,7 +101,7 @@ class BRISKDemo void init () { - boost::function cloud_cb = boost::bind (&BRISKDemo::cloud_callback, this, _1); + std::function cloud_cb = boost::bind (&BRISKDemo::cloud_callback, this, _1); cloud_connection = grabber_.registerCallback (cloud_cb); } diff --git a/apps/src/ni_linemod.cpp b/apps/src/ni_linemod.cpp index 3f55ec0b047..73c503a9b96 100644 --- a/apps/src/ni_linemod.cpp +++ b/apps/src/ni_linemod.cpp @@ -475,7 +475,7 @@ class NILinemod cloud_viewer_.registerMouseCallback (&NILinemod::mouse_callback, *this); cloud_viewer_.registerKeyboardCallback(&NILinemod::keyboard_callback, *this); cloud_viewer_.registerPointPickingCallback (&NILinemod::pp_callback, *this); - boost::function cloud_cb = boost::bind (&NILinemod::cloud_callback, this, _1); + std::function cloud_cb = boost::bind (&NILinemod::cloud_callback, this, _1); cloud_connection = grabber_.registerCallback (cloud_cb); image_viewer_.registerMouseCallback (&NILinemod::mouse_callback, *this); diff --git a/apps/src/ni_susan.cpp b/apps/src/ni_susan.cpp index f09c172713d..9033607b392 100644 --- a/apps/src/ni_susan.cpp +++ b/apps/src/ni_susan.cpp @@ -99,7 +99,7 @@ class SUSANDemo void init () { - boost::function cloud_cb = boost::bind (&SUSANDemo::cloud_callback, this, _1); + std::function cloud_cb = boost::bind (&SUSANDemo::cloud_callback, this, _1); cloud_connection = grabber_.registerCallback (cloud_cb); } diff --git a/apps/src/ni_trajkovic.cpp b/apps/src/ni_trajkovic.cpp index e5f25825aa5..687218bf7bd 100644 --- a/apps/src/ni_trajkovic.cpp +++ b/apps/src/ni_trajkovic.cpp @@ -113,7 +113,7 @@ class TrajkovicDemo void init () { - boost::function cloud_cb; + std::function cloud_cb; if (enable_3d_) cloud_cb = boost::bind (&TrajkovicDemo::cloud_callback_3d, this, _1); else diff --git a/apps/src/openni_3d_concave_hull.cpp b/apps/src/openni_3d_concave_hull.cpp index 07ffdfb8465..c46a21737b3 100644 --- a/apps/src/openni_3d_concave_hull.cpp +++ b/apps/src/openni_3d_concave_hull.cpp @@ -140,7 +140,7 @@ class OpenNI3DConcaveHull { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNI3DConcaveHull::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNI3DConcaveHull::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNI3DConcaveHull::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_3d_convex_hull.cpp b/apps/src/openni_3d_convex_hull.cpp index afd0a0ddff7..ab0b8d747ec 100644 --- a/apps/src/openni_3d_convex_hull.cpp +++ b/apps/src/openni_3d_convex_hull.cpp @@ -138,7 +138,7 @@ class OpenNI3DConvexHull { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNI3DConvexHull::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNI3DConvexHull::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNI3DConvexHull::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_boundary_estimation.cpp b/apps/src/openni_boundary_estimation.cpp index a704dd06fc7..2e80291288f 100644 --- a/apps/src/openni_boundary_estimation.cpp +++ b/apps/src/openni_boundary_estimation.cpp @@ -161,7 +161,7 @@ class OpenNIIntegralImageNormalEstimation { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function::ConstPtr &)> f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1); + std::function::ConstPtr &)> f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNIIntegralImageNormalEstimation::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_change_viewer.cpp b/apps/src/openni_change_viewer.cpp index b2227050bf2..5d0920cf0f9 100644 --- a/apps/src/openni_change_viewer.cpp +++ b/apps/src/openni_change_viewer.cpp @@ -125,7 +125,7 @@ class OpenNIChangeViewer { pcl::Grabber* interface = new pcl::OpenNIGrabber(); - boost::function::ConstPtr&)> f = + std::function::ConstPtr&)> f = boost::bind (&OpenNIChangeViewer::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); diff --git a/apps/src/openni_color_filter.cpp b/apps/src/openni_color_filter.cpp index 4ecba3fe32d..2edcc77a2ac 100644 --- a/apps/src/openni_color_filter.cpp +++ b/apps/src/openni_color_filter.cpp @@ -73,7 +73,7 @@ class OpenNIPassthrough : viewer ("PCL OpenNI ColorFilter Viewer") , grabber_(grabber) { - boost::function f = boost::bind (&OpenNIPassthrough::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIPassthrough::cloud_cb_, this, _1); boost::signals2::connection c = grabber_.registerCallback (f); std::vector lookup(1<<24, false); diff --git a/apps/src/openni_fast_mesh.cpp b/apps/src/openni_fast_mesh.cpp index 59b73ba92dc..6a17d06871e 100644 --- a/apps/src/openni_fast_mesh.cpp +++ b/apps/src/openni_fast_mesh.cpp @@ -106,7 +106,7 @@ class OpenNIFastMesh { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIFastMesh::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNIFastMesh::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); view.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCL OpenNI Mesh Viewer")); diff --git a/apps/src/openni_feature_persistence.cpp b/apps/src/openni_feature_persistence.cpp index e066081134c..41267584b67 100644 --- a/apps/src/openni_feature_persistence.cpp +++ b/apps/src/openni_feature_persistence.cpp @@ -190,7 +190,7 @@ class OpenNIFeaturePersistence { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIFeaturePersistence::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNIFeaturePersistence::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNIFeaturePersistence::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_grab_frame.cpp b/apps/src/openni_grab_frame.cpp index f69cf4b99a2..3320eeddb3e 100644 --- a/apps/src/openni_grab_frame.cpp +++ b/apps/src/openni_grab_frame.cpp @@ -186,7 +186,7 @@ class OpenNIGrabFrame // make callback function from member function - boost::function f = boost::bind (&OpenNIGrabFrame::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIGrabFrame::cloud_cb_, this, _1); // connect callback function for desired signal. In this case its a point cloud with color values boost::signals2::connection c = grabber_.registerCallback (f); diff --git a/apps/src/openni_grab_images.cpp b/apps/src/openni_grab_images.cpp index 545df268ebb..06842b71970 100644 --- a/apps/src/openni_grab_images.cpp +++ b/apps/src/openni_grab_images.cpp @@ -187,7 +187,7 @@ class OpenNIGrabFrame depth_image_viewer_.registerMouseCallback (&OpenNIGrabFrame::mouse_callback, *this); depth_image_viewer_.registerKeyboardCallback(&OpenNIGrabFrame::keyboard_callback, *this); - boost::function image_cb = boost::bind (&OpenNIGrabFrame::image_callback, this, _1, _2, _3); + std::function image_cb = boost::bind (&OpenNIGrabFrame::image_callback, this, _1, _2, _3); boost::signals2::connection image_connection = grabber_.registerCallback (image_cb); // start receiving point clouds diff --git a/apps/src/openni_ii_normal_estimation.cpp b/apps/src/openni_ii_normal_estimation.cpp index e364e427095..64de3f6fca5 100644 --- a/apps/src/openni_ii_normal_estimation.cpp +++ b/apps/src/openni_ii_normal_estimation.cpp @@ -163,7 +163,7 @@ class OpenNIIntegralImageNormalEstimation { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNIIntegralImageNormalEstimation::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_klt.cpp b/apps/src/openni_klt.cpp index 431587d54ad..b06723d2f1d 100644 --- a/apps/src/openni_klt.cpp +++ b/apps/src/openni_klt.cpp @@ -206,14 +206,14 @@ class OpenNIViewer void run () { - boost::function cloud_cb = boost::bind (&OpenNIViewer::cloud_callback, this, _1); + std::function cloud_cb = boost::bind (&OpenNIViewer::cloud_callback, this, _1); boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb); boost::signals2::connection image_connection; if (grabber_.providesCallback()) { image_viewer_.reset (new pcl::visualization::ImageViewer ("Pyramidal KLT Tracker")); - boost::function image_cb = boost::bind (&OpenNIViewer::image_callback, this, _1); + std::function image_cb = boost::bind (&OpenNIViewer::image_callback, this, _1); image_connection = grabber_.registerCallback (image_cb); } diff --git a/apps/src/openni_mls_smoothing.cpp b/apps/src/openni_mls_smoothing.cpp index 71dab9a7a3a..08513b9eecf 100644 --- a/apps/src/openni_mls_smoothing.cpp +++ b/apps/src/openni_mls_smoothing.cpp @@ -134,7 +134,7 @@ class OpenNISmoothing { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNISmoothing::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNISmoothing::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.registerKeyboardCallback (keyboardEventOccurred, reinterpret_cast (&stop_computing_)); diff --git a/apps/src/openni_mobile_server.cpp b/apps/src/openni_mobile_server.cpp index 5d0e4fa0268..7d53fab5ec0 100644 --- a/apps/src/openni_mobile_server.cpp +++ b/apps/src/openni_mobile_server.cpp @@ -158,7 +158,7 @@ class PCLMobileServer run () { pcl::OpenNIGrabber grabber (device_id_); - boost::function handler_function = boost::bind (&PCLMobileServer::handleIncomingCloud, this, _1); + std::function handler_function = boost::bind (&PCLMobileServer::handleIncomingCloud, this, _1); grabber.registerCallback (handler_function); grabber.start (); diff --git a/apps/src/openni_octree_compression.cpp b/apps/src/openni_octree_compression.cpp index 1596135fa48..9c091193090 100644 --- a/apps/src/openni_octree_compression.cpp +++ b/apps/src/openni_octree_compression.cpp @@ -155,7 +155,7 @@ class SimpleOpenNIViewer pcl::Grabber* interface = new pcl::OpenNIGrabber(); // make callback function from member function - boost::function::ConstPtr&)> f = + std::function::ConstPtr&)> f = boost::bind (&SimpleOpenNIViewer::cloud_cb_, this, _1); // connect callback function for desired signal. In this case its a point cloud with color values @@ -210,7 +210,7 @@ struct EventHelper pcl::Grabber* interface = new pcl::OpenNIGrabber (); // make callback function from member function - boost::function::ConstPtr&)> f = boost::bind (&EventHelper::cloud_cb_, this, _1); // connect callback function for desired signal. In this case its a point cloud with color values diff --git a/apps/src/openni_organized_compression.cpp b/apps/src/openni_organized_compression.cpp index 0f6284693d7..f5f705ed16c 100644 --- a/apps/src/openni_organized_compression.cpp +++ b/apps/src/openni_organized_compression.cpp @@ -155,7 +155,7 @@ class SimpleOpenNIViewer pcl::Grabber* interface = new pcl::OpenNIGrabber(); // make callback function from member function - boost::function::ConstPtr&)> f = + std::function::ConstPtr&)> f = boost::bind (&SimpleOpenNIViewer::cloud_cb_, this, _1); // connect callback function for desired signal. In this case its a point cloud with color values @@ -246,7 +246,7 @@ struct EventHelper pcl::Grabber* interface = new pcl::OpenNIGrabber (); // make callback function from member function - boost::function::ConstPtr&)> f = boost::bind (&EventHelper::cloud_cb_, this, _1); // connect callback function for desired signal. In this case its a point cloud with color values @@ -271,7 +271,7 @@ struct EventHelper // Set the depth output format grabber.getDevice ()->setDepthOutputFormat (static_cast (depthformat)); - boost::function image_cb + std::function image_cb = boost::bind (&EventHelper::image_callback, this, _1, _2, _3); boost::signals2::connection image_connection = grabber.registerCallback (image_cb); diff --git a/apps/src/openni_organized_edge_detection.cpp b/apps/src/openni_organized_edge_detection.cpp index be96f2cadf5..ba1b65a947a 100644 --- a/apps/src/openni_organized_edge_detection.cpp +++ b/apps/src/openni_organized_edge_detection.cpp @@ -145,7 +145,7 @@ class OpenNIOrganizedEdgeDetection { pcl::Grabber* interface = new pcl::OpenNIGrabber (); - boost::function::ConstPtr&)> f = boost::bind (&OpenNIOrganizedEdgeDetection::cloud_cb_, this, _1); + std::function::ConstPtr&)> f = boost::bind (&OpenNIOrganizedEdgeDetection::cloud_cb_, this, _1); // Make and initialize a cloud viewer pcl::PointCloud::Ptr init_cloud_ptr (new pcl::PointCloud); diff --git a/apps/src/openni_organized_multi_plane_segmentation.cpp b/apps/src/openni_organized_multi_plane_segmentation.cpp index c5e93a64e07..ea9a17b3c7f 100644 --- a/apps/src/openni_organized_multi_plane_segmentation.cpp +++ b/apps/src/openni_organized_multi_plane_segmentation.cpp @@ -111,7 +111,7 @@ class OpenNIOrganizedMultiPlaneSegmentation { pcl::Grabber* interface = new pcl::OpenNIGrabber (); - boost::function::ConstPtr&)> f = boost::bind (&OpenNIOrganizedMultiPlaneSegmentation::cloud_cb_, this, _1); + std::function::ConstPtr&)> f = boost::bind (&OpenNIOrganizedMultiPlaneSegmentation::cloud_cb_, this, _1); //make a viewer pcl::PointCloud::Ptr init_cloud_ptr (new pcl::PointCloud); diff --git a/apps/src/openni_passthrough.cpp b/apps/src/openni_passthrough.cpp index 23f19e1cf1e..4c97238f6d4 100644 --- a/apps/src/openni_passthrough.cpp +++ b/apps/src/openni_passthrough.cpp @@ -73,7 +73,7 @@ OpenNIPassthrough::OpenNIPassthrough (pcl::OpenNIGrabber& grabber) ui_->qvtk_widget->update (); // Start the OpenNI data acquision - boost::function f = boost::bind (&OpenNIPassthrough::cloud_cb, this, _1); + std::function f = boost::bind (&OpenNIPassthrough::cloud_cb, this, _1); boost::signals2::connection c = grabber_.registerCallback (f); grabber_.start (); diff --git a/apps/src/openni_planar_convex_hull.cpp b/apps/src/openni_planar_convex_hull.cpp index da0a9f19540..6aea51788b6 100644 --- a/apps/src/openni_planar_convex_hull.cpp +++ b/apps/src/openni_planar_convex_hull.cpp @@ -121,7 +121,7 @@ class OpenNIPlanarSegmentation { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); interface->start (); diff --git a/apps/src/openni_planar_segmentation.cpp b/apps/src/openni_planar_segmentation.cpp index 608091777a8..bae0d4ea9e0 100644 --- a/apps/src/openni_planar_segmentation.cpp +++ b/apps/src/openni_planar_segmentation.cpp @@ -116,7 +116,7 @@ class OpenNIPlanarSegmentation { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIPlanarSegmentation::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); interface->start (); diff --git a/apps/src/openni_shift_to_depth_conversion.cpp b/apps/src/openni_shift_to_depth_conversion.cpp index f818b663418..4bedd927900 100644 --- a/apps/src/openni_shift_to_depth_conversion.cpp +++ b/apps/src/openni_shift_to_depth_conversion.cpp @@ -135,7 +135,7 @@ class SimpleOpenNIViewer grabber_->getDevice ()->setDepthOutputFormat (static_cast (depthformat)); // define image callback - boost::function image_cb = boost::bind (&SimpleOpenNIViewer::image_callback, this, _1, _2, _3); boost::signals2::connection image_connection = grabber_->registerCallback (image_cb); diff --git a/apps/src/openni_tracking.cpp b/apps/src/openni_tracking.cpp index 9a7bdf260b0..dc0dbef935e 100644 --- a/apps/src/openni_tracking.cpp +++ b/apps/src/openni_tracking.cpp @@ -638,7 +638,7 @@ class OpenNISegmentTracking run () { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = + std::function f = boost::bind (&OpenNISegmentTracking::cloud_cb, this, _1); interface->registerCallback (f); diff --git a/apps/src/openni_uniform_sampling.cpp b/apps/src/openni_uniform_sampling.cpp index b3a400c89da..476759dce76 100644 --- a/apps/src/openni_uniform_sampling.cpp +++ b/apps/src/openni_uniform_sampling.cpp @@ -125,7 +125,7 @@ class OpenNIUniformSampling { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIUniformSampling::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIUniformSampling::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); viewer.runOnVisualizationThread (boost::bind(&OpenNIUniformSampling::viz_cb, this, _1), "viz_cb"); diff --git a/apps/src/openni_voxel_grid.cpp b/apps/src/openni_voxel_grid.cpp index 5f86781426b..15d8f846be4 100644 --- a/apps/src/openni_voxel_grid.cpp +++ b/apps/src/openni_voxel_grid.cpp @@ -113,7 +113,7 @@ class OpenNIVoxelGrid { pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_); - boost::function f = boost::bind (&OpenNIVoxelGrid::cloud_cb_, this, _1); + std::function f = boost::bind (&OpenNIVoxelGrid::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); interface->start (); diff --git a/apps/src/organized_segmentation_demo.cpp b/apps/src/organized_segmentation_demo.cpp index 0bb248f63d4..f21e9f4a750 100644 --- a/apps/src/organized_segmentation_demo.cpp +++ b/apps/src/organized_segmentation_demo.cpp @@ -14,7 +14,7 @@ #include void -displayPlanarRegions (std::vector, Eigen::aligned_allocator > > ®ions, +displayPlanarRegions (std::vector, Eigen::aligned_allocator > > ®ions, pcl::visualization::PCLVisualizer::Ptr viewer) { char name[1024]; @@ -34,7 +34,7 @@ displayPlanarRegions (std::vector, Eigen::aligned_allo centroid[2] + (0.5f * model[2])); sprintf (name, "normal_%d", unsigned (i)); viewer->addArrow (pt2, pt1, 1.0, 0, 0, false, name); - + contour->points = regions[i].getContour (); sprintf (name, "plane_%02d", int (i)); pcl::visualization::PointCloudColorHandlerCustom color (contour, red[i%6], grn[i%6], blu[i%6]); @@ -45,7 +45,7 @@ displayPlanarRegions (std::vector, Eigen::aligned_allo } void -displayEuclideanClusters (const pcl::PointCloud::CloudVectorType &clusters, +displayEuclideanClusters (const pcl::PointCloud::CloudVectorType &clusters, pcl::visualization::PCLVisualizer::Ptr viewer) { char name[1024]; @@ -84,7 +84,7 @@ displayCurvature (pcl::PointCloud& cloud, pcl::PointCloud& curvature_cloud.points[i].b = 0; } } - + if (!viewer->updatePointCloud (curvature_cloud.makeShared (), "curvature")) viewer->addPointCloud (curvature_cloud.makeShared (), "curvature"); } @@ -108,7 +108,7 @@ displayDistanceMap (pcl::PointCloud& cloud, float* distance_map, pcl::vi distance_map_cloud.points[i].b = 0; } } - + if (!viewer->updatePointCloud (distance_map_cloud.makeShared (), "distance_map")) viewer->addPointCloud (distance_map_cloud.makeShared (), "distance_map"); } @@ -121,11 +121,11 @@ removePreviousDataFromScreen (size_t prev_models_size, size_t prev_clusters_size { sprintf (name, "normal_%d", unsigned (i)); viewer->removeShape (name); - + sprintf (name, "plane_%02d", int (i)); viewer->removePointCloud (name); } - + for (size_t i = 0; i < prev_clusters_size; i++) { sprintf (name, "cluster_%d", int (i)); @@ -139,7 +139,7 @@ compareClusterToRegion (pcl::PlanarRegion& region, pcl::PointCloud poly; poly.points = region.getContour (); - + for (const auto &point : cluster.points) { double ptp_dist = fabs (model[0] * point.x + @@ -157,7 +157,7 @@ bool comparePointToRegion (PointT& pt, pcl::ModelCoefficients& model, pcl::PointCloud& poly) { //bool dist_ok; - + double ptp_dist = fabs (model.values[0] * pt.x + model.values[1] * pt.y + model.values[2] * pt.z + @@ -177,7 +177,7 @@ comparePointToRegion (PointT& pt, pcl::ModelCoefficients& model, pcl::PointCloud PointT projected_pt; projected_pt.x = projected[0]; projected_pt.y = projected[1]; - projected_pt.z = projected[2]; + projected_pt.z = projected[2]; PCL_INFO ("pt: %lf %lf %lf\n", projected_pt.x, projected_pt.y, projected_pt.z); @@ -191,7 +191,7 @@ comparePointToRegion (PointT& pt, pcl::ModelCoefficients& model, pcl::PointCloud PCL_INFO ("not inside!\n"); return false; } - + } ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -205,7 +205,7 @@ OrganizedSegmentationDemo::OrganizedSegmentationDemo (pcl::Grabber& grabber) : g ui_ = new Ui::MainWindow; ui_->setupUi (this); - + this->setWindowTitle ("PCL Organized Connected Component Segmentation Demo"); vis_ = pcl::make_shared ("", false); ui_->qvtk_widget->SetRenderWindow (vis_->getRenderWindow ()); @@ -213,9 +213,9 @@ OrganizedSegmentationDemo::OrganizedSegmentationDemo (pcl::Grabber& grabber) : g vis_->getInteractorStyle ()->setKeyboardModifier (pcl::visualization::INTERACTOR_KB_MOD_SHIFT); ui_->qvtk_widget->update (); - boost::function f = boost::bind (&OrganizedSegmentationDemo::cloud_cb, this, _1); + std::function f = boost::bind (&OrganizedSegmentationDemo::cloud_cb, this, _1); boost::signals2::connection c = grabber_.registerCallback(f); - + connect (ui_->captureButton, SIGNAL(clicked()), this, SLOT(toggleCapturePressed())); connect (ui_->euclideanComparatorButton, SIGNAL (clicked ()), this, SLOT (useEuclideanComparatorPressed ())); @@ -244,12 +244,12 @@ OrganizedSegmentationDemo::OrganizedSegmentationDemo (pcl::Grabber& grabber) : g use_planar_refinement_ = true; use_clustering_ = false; - + // Set up Normal Estimation //ne.setNormalEstimationMethod (ne.SIMPLE_3D_GRADIENT); ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX); - ne.setMaxDepthChangeFactor (0.02f); + ne.setMaxDepthChangeFactor (0.02f); // set as default, well performing for tabletop objects as imaged by a primesense sensor ne.setNormalSmoothingSize (20.0f); plane_comparator_ = pcl::make_shared> (); @@ -259,18 +259,18 @@ OrganizedSegmentationDemo::OrganizedSegmentationDemo (pcl::Grabber& grabber) : g euclidean_cluster_comparator_ = pcl::EuclideanClusterComparator::Ptr (new pcl::EuclideanClusterComparator ()); // Set up Organized Multi Plane Segmentation - mps.setMinInliers (10000); - mps.setAngularThreshold (pcl::deg2rad (3.0)); //3 degrees - mps.setDistanceThreshold (0.02); //2cm - + mps.setMinInliers (10000u); + mps.setAngularThreshold (pcl::deg2rad (3.0)); // 3 degrees, set as default, well performing for tabletop objects as imaged by a primesense sensor + mps.setDistanceThreshold (0.02); // 2cm, set as default, well performing for tabletop objects as imaged by a primesense sensor + PCL_INFO ("starting grabber\n"); grabber_.start (); } -void +void OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud) -{ +{ if (!capture_) return; QMutexLocker locker (&mtx_); @@ -289,7 +289,7 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud) double mps_start = pcl::getTime (); std::vector, Eigen::aligned_allocator > > regions; std::vector model_coefficients; - std::vector inlier_indices; + std::vector inlier_indices; pcl::PointCloud::Ptr labels (new pcl::PointCloud); std::vector label_indices; std::vector boundary_indices; @@ -313,7 +313,7 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud) { pcl::EuclideanClusterComparator::ExcludeLabelSetPtr plane_labels (new pcl::EuclideanClusterComparator::ExcludeLabelSet); for (size_t i = 0; i < label_indices.size (); ++i) - if (label_indices[i].indices.size () > 10000) + if (label_indices[i].indices.size () > mps.getMinInliers()) plane_labels->insert (i); euclidean_cluster_comparator_->setInputCloud (cloud); @@ -326,21 +326,21 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud) pcl::OrganizedConnectedComponentSegmentation euclidean_segmentation (euclidean_cluster_comparator_); euclidean_segmentation.setInputCloud (cloud); euclidean_segmentation.segment (euclidean_labels, euclidean_label_indices); - + for (const auto &euclidean_label_index : euclidean_label_indices) { - if (euclidean_label_index.indices.size () > 1000) + if (euclidean_label_index.indices.size () > 1000u) { pcl::PointCloud cluster; pcl::copyPointCloud (*cloud, euclidean_label_index.indices,cluster); clusters.push_back (cluster); - } + } } - + PCL_INFO ("Got %d euclidean clusters!\n", clusters.size ()); - } + } - { + { QMutexLocker vis_locker (&vis_mtx_); prev_cloud_ = *cloud; prev_normals_ = *normal_cloud; @@ -351,7 +351,7 @@ OrganizedSegmentationDemo::cloud_cb (const CloudConstPtr& cloud) } } -void +void OrganizedSegmentationDemo::timeoutSlot () { { @@ -387,7 +387,7 @@ OrganizedSegmentationDemo::timeoutSlot () { vis_->removePointCloud ("normals"); } - + displayEuclideanClusters (prev_clusters_,vis_); previous_data_size_ = prev_regions_.size (); @@ -395,7 +395,7 @@ OrganizedSegmentationDemo::timeoutSlot () data_modified_ = false; } } - + ui_->qvtk_widget->update(); } @@ -453,7 +453,7 @@ int main (int argc, char ** argv) { QApplication app(argc, argv); - + //PCL_INFO ("Creating PCD Grabber\n"); //std::vector pcd_files; //boost::filesystem::directory_iterator end_itr; @@ -468,7 +468,7 @@ main (int argc, char ** argv) //PCL_INFO ("PCD Grabber created\n"); pcl::OpenNIGrabber grabber ("#1"); - + OrganizedSegmentationDemo seg_demo (grabber); seg_demo.show(); return (QApplication::exec ()); diff --git a/cmake/Modules/FindGTestSource.cmake b/cmake/Modules/FindGTestSource.cmake index 801886f1435..e4c6e133dd4 100644 --- a/cmake/Modules/FindGTestSource.cmake +++ b/cmake/Modules/FindGTestSource.cmake @@ -32,7 +32,8 @@ set(GTEST_INCLUDE_DIRS ${GTEST_INCLUDE_DIR}) set(CMAKE_FIND_FRAMEWORK) include(FindPackageHandleStandardArgs) -find_package_handle_standard_args(Gtest DEFAULT_MSG GTEST_INCLUDE_DIR GTEST_SRC_DIR) +find_package_handle_standard_args(GTestSource DEFAULT_MSG GTEST_INCLUDE_DIR GTEST_SRC_DIR) +set(GTEST_FOUND ${GTestSource_FOUND}) mark_as_advanced(GTEST_INCLUDE_DIR GTEST_SRC_DIR) diff --git a/cmake/pcl_targets.cmake b/cmake/pcl_targets.cmake index 5ae0f1129a7..a50d0d0998a 100644 --- a/cmake/pcl_targets.cmake +++ b/cmake/pcl_targets.cmake @@ -223,7 +223,7 @@ function(PCL_ADD_LIBRARY _name) PCL_ADD_VERSION_INFO(${_name}) target_compile_features(${_name} PUBLIC ${PCL_CXX_COMPILE_FEATURES}) # must link explicitly against boost. - target_link_libraries(${_name} ${Boost_LIBRARIES}) + target_link_libraries(${_name} ${Boost_LIBRARIES} Threads::Threads) if((UNIX AND NOT ANDROID) OR MINGW) target_link_libraries(${_name} m) endif() @@ -302,11 +302,7 @@ function(PCL_ADD_EXECUTABLE _name) endif() PCL_ADD_VERSION_INFO(${_name}) # must link explicitly against boost. - if(UNIX AND NOT ANDROID) - target_link_libraries(${_name} ${Boost_LIBRARIES} pthread m ${CLANG_LIBRARIES}) - else() - target_link_libraries(${_name} ${Boost_LIBRARIES}) - endif() + target_link_libraries(${_name} ${Boost_LIBRARIES} Threads::Threads) if(WIN32 AND MSVC) set_target_properties(${_name} PROPERTIES DEBUG_OUTPUT_NAME ${_name}${CMAKE_DEBUG_POSTFIX} @@ -384,12 +380,7 @@ macro(PCL_ADD_TEST _name _exename) #target_link_libraries(${_exename} ${GTEST_BOTH_LIBRARIES} ${PCL_ADD_TEST_LINK_WITH}) target_link_libraries(${_exename} ${PCL_ADD_TEST_LINK_WITH} ${CLANG_LIBRARIES}) - if(CMAKE_SYSTEM_NAME STREQUAL "Darwin") - target_link_libraries(${_exename} pthread) - elseif(UNIX AND NOT ANDROID) - # GTest >= 1.5 requires pthread and CMake's 2.8.4 FindGTest is broken - target_link_libraries(${_exename} pthread) - endif() + target_link_libraries(${_exename} Threads::Threads) # must link explicitly against boost only on Windows target_link_libraries(${_exename} ${Boost_LIBRARIES}) diff --git a/common/include/pcl/ModelCoefficients.h b/common/include/pcl/ModelCoefficients.h index 3790ef0030c..29f111657a8 100644 --- a/common/include/pcl/ModelCoefficients.h +++ b/common/include/pcl/ModelCoefficients.h @@ -20,12 +20,12 @@ namespace pcl std::vector values; public: - typedef boost::shared_ptr< ::pcl::ModelCoefficients> Ptr; - typedef boost::shared_ptr< ::pcl::ModelCoefficients const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::ModelCoefficients>; + using ConstPtr = boost::shared_ptr; }; // struct ModelCoefficients - typedef boost::shared_ptr< ::pcl::ModelCoefficients> ModelCoefficientsPtr; - typedef boost::shared_ptr< ::pcl::ModelCoefficients const> ModelCoefficientsConstPtr; + using ModelCoefficientsPtr = boost::shared_ptr< ::pcl::ModelCoefficients>; + using ModelCoefficientsConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::ModelCoefficients & v) { diff --git a/common/include/pcl/PCLHeader.h b/common/include/pcl/PCLHeader.h index f8027516b1c..96d681f830b 100644 --- a/common/include/pcl/PCLHeader.h +++ b/common/include/pcl/PCLHeader.h @@ -27,12 +27,12 @@ namespace pcl /** \brief Coordinate frame ID */ std::string frame_id; - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; }; // struct PCLHeader - typedef boost::shared_ptr HeaderPtr; - typedef boost::shared_ptr HeaderConstPtr; + using HeaderPtr = boost::shared_ptr; + using HeaderConstPtr = boost::shared_ptr; inline std::ostream& operator << (std::ostream& out, const PCLHeader &h) { diff --git a/common/include/pcl/PCLImage.h b/common/include/pcl/PCLImage.h index a0c0e039d4e..ede95a646c7 100644 --- a/common/include/pcl/PCLImage.h +++ b/common/include/pcl/PCLImage.h @@ -30,12 +30,12 @@ namespace pcl std::vector data; - typedef boost::shared_ptr< ::pcl::PCLImage> Ptr; - typedef boost::shared_ptr< ::pcl::PCLImage const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::PCLImage>; + using ConstPtr = boost::shared_ptr; }; // struct PCLImage - typedef boost::shared_ptr< ::pcl::PCLImage> PCLImagePtr; - typedef boost::shared_ptr< ::pcl::PCLImage const> PCLImageConstPtr; + using PCLImagePtr = boost::shared_ptr< ::pcl::PCLImage>; + using PCLImageConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLImage & v) { diff --git a/common/include/pcl/PCLPointCloud2.h b/common/include/pcl/PCLPointCloud2.h index 4c7827b78bf..c4bd398b91c 100644 --- a/common/include/pcl/PCLPointCloud2.h +++ b/common/include/pcl/PCLPointCloud2.h @@ -47,12 +47,12 @@ namespace pcl pcl::uint8_t is_dense; public: - typedef boost::shared_ptr< ::pcl::PCLPointCloud2> Ptr; - typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::PCLPointCloud2>; + using ConstPtr = boost::shared_ptr; }; // struct PCLPointCloud2 - typedef boost::shared_ptr< ::pcl::PCLPointCloud2> PCLPointCloud2Ptr; - typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> PCLPointCloud2ConstPtr; + using PCLPointCloud2Ptr = boost::shared_ptr< ::pcl::PCLPointCloud2>; + using PCLPointCloud2ConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLPointCloud2 &v) { diff --git a/common/include/pcl/PCLPointField.h b/common/include/pcl/PCLPointField.h index 956ba803b74..e285bc6c4e2 100644 --- a/common/include/pcl/PCLPointField.h +++ b/common/include/pcl/PCLPointField.h @@ -33,12 +33,12 @@ namespace pcl FLOAT64 = 8 }; public: - typedef boost::shared_ptr< ::pcl::PCLPointField> Ptr; - typedef boost::shared_ptr< ::pcl::PCLPointField const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::PCLPointField>; + using ConstPtr = boost::shared_ptr; }; // struct PCLPointField - typedef boost::shared_ptr< ::pcl::PCLPointField> PCLPointFieldPtr; - typedef boost::shared_ptr< ::pcl::PCLPointField const> PCLPointFieldConstPtr; + using PCLPointFieldPtr = boost::shared_ptr< ::pcl::PCLPointField>; + using PCLPointFieldConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::PCLPointField & v) { diff --git a/common/include/pcl/PointIndices.h b/common/include/pcl/PointIndices.h index 9091f693a2b..dd151e8c231 100644 --- a/common/include/pcl/PointIndices.h +++ b/common/include/pcl/PointIndices.h @@ -19,12 +19,12 @@ namespace pcl std::vector indices; public: - typedef boost::shared_ptr< ::pcl::PointIndices> Ptr; - typedef boost::shared_ptr< ::pcl::PointIndices const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::PointIndices>; + using ConstPtr = boost::shared_ptr; }; // struct PointIndices - typedef boost::shared_ptr< ::pcl::PointIndices> PointIndicesPtr; - typedef boost::shared_ptr< ::pcl::PointIndices const> PointIndicesConstPtr; + using PointIndicesPtr = boost::shared_ptr< ::pcl::PointIndices>; + using PointIndicesConstPtr = boost::shared_ptr; inline std::ostream& operator << (std::ostream& s, const ::pcl::PointIndices &v) { diff --git a/common/include/pcl/PolygonMesh.h b/common/include/pcl/PolygonMesh.h index 2957b5b435e..8120c06a251 100644 --- a/common/include/pcl/PolygonMesh.h +++ b/common/include/pcl/PolygonMesh.h @@ -25,12 +25,12 @@ namespace pcl public: - typedef boost::shared_ptr< ::pcl::PolygonMesh> Ptr; - typedef boost::shared_ptr< ::pcl::PolygonMesh const> ConstPtr; + using Ptr = boost::shared_ptr< ::pcl::PolygonMesh>; + using ConstPtr = boost::shared_ptr; }; // struct PolygonMesh - typedef boost::shared_ptr< ::pcl::PolygonMesh> PolygonMeshPtr; - typedef boost::shared_ptr< ::pcl::PolygonMesh const> PolygonMeshConstPtr; + using PolygonMeshPtr = boost::shared_ptr< ::pcl::PolygonMesh>; + using PolygonMeshConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::PolygonMesh &v) { diff --git a/common/include/pcl/TextureMesh.h b/common/include/pcl/TextureMesh.h index 51dbbd4b4e4..a21af1bdc19 100644 --- a/common/include/pcl/TextureMesh.h +++ b/common/include/pcl/TextureMesh.h @@ -100,10 +100,10 @@ namespace pcl std::vector tex_materials; // define texture material public: - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; }; // struct TextureMesh - typedef boost::shared_ptr TextureMeshPtr; - typedef boost::shared_ptr TextureMeshConstPtr; + using TextureMeshPtr = boost::shared_ptr; + using TextureMeshConstPtr = boost::shared_ptr; } // namespace pcl diff --git a/common/include/pcl/Vertices.h b/common/include/pcl/Vertices.h index 666bdeb61dd..8e39926b832 100644 --- a/common/include/pcl/Vertices.h +++ b/common/include/pcl/Vertices.h @@ -19,13 +19,13 @@ namespace pcl std::vector vertices; public: - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; }; // struct Vertices - typedef boost::shared_ptr VerticesPtr; - typedef boost::shared_ptr VerticesConstPtr; + using VerticesPtr = boost::shared_ptr; + using VerticesConstPtr = boost::shared_ptr; inline std::ostream& operator<<(std::ostream& s, const ::pcl::Vertices & v) { diff --git a/common/include/pcl/common/bivariate_polynomial.h b/common/include/pcl/common/bivariate_polynomial.h index 1946d8b8fb8..1b0d5e131a8 100644 --- a/common/include/pcl/common/bivariate_polynomial.h +++ b/common/include/pcl/common/bivariate_polynomial.h @@ -133,8 +133,8 @@ namespace pcl std::ostream& operator<< (std::ostream& os, const BivariatePolynomialT& p); - typedef BivariatePolynomialT BivariatePolynomiald; - typedef BivariatePolynomialT BivariatePolynomial; + using BivariatePolynomiald = BivariatePolynomialT; + using BivariatePolynomial = BivariatePolynomialT; } // end namespace diff --git a/common/include/pcl/common/boost.h b/common/include/pcl/common/boost.h index 4cc420fd097..3c5d68c0cbb 100644 --- a/common/include/pcl/common/boost.h +++ b/common/include/pcl/common/boost.h @@ -49,7 +49,6 @@ #include #include #include -#include #include #include #include diff --git a/common/include/pcl/common/centroid.h b/common/include/pcl/common/centroid.h index 122f816ac82..10ebd4144e7 100644 --- a/common/include/pcl/common/centroid.h +++ b/common/include/pcl/common/centroid.h @@ -840,7 +840,7 @@ namespace pcl template struct NdCentroidFunctor { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; NdCentroidFunctor (const PointT &p, Eigen::Matrix ¢roid) : f_idx_ (0), @@ -849,7 +849,7 @@ namespace pcl template inline void operator() () { - typedef typename pcl::traits::datatype::type T; + using T = typename pcl::traits::datatype::type; const uint8_t* raw_ptr = reinterpret_cast(&p_) + pcl::traits::offset::value; const T* data_ptr = reinterpret_cast(raw_ptr); diff --git a/common/include/pcl/common/colors.h b/common/include/pcl/common/colors.h index 584fba454e4..bd04c609bc6 100644 --- a/common/include/pcl/common/colors.h +++ b/common/include/pcl/common/colors.h @@ -80,7 +80,7 @@ namespace pcl }; - typedef ColorLUT GlasbeyLUT; - typedef ColorLUT ViridisLUT; + using GlasbeyLUT = ColorLUT; + using ViridisLUT = ColorLUT; } diff --git a/common/include/pcl/common/concatenate.h b/common/include/pcl/common/concatenate.h index 7ec177fa952..07727da84fc 100644 --- a/common/include/pcl/common/concatenate.h +++ b/common/include/pcl/common/concatenate.h @@ -40,15 +40,7 @@ #include -// We're doing a lot of black magic with Boost here, so disable warnings in Maintainer mode, as we will never -// be able to fix them anyway -#ifdef BUILD_Maintainer -# if defined __GNUC__ -# pragma GCC system_header -# elif defined _MSC_VER -# pragma warning(push, 1) -# endif -#endif +#include namespace pcl { @@ -58,8 +50,8 @@ namespace pcl template struct NdConcatenateFunctor { - typedef typename traits::POD::type PodIn; - typedef typename traits::POD::type PodOut; + using PodIn = typename traits::POD::type; + using PodOut = typename traits::POD::type; NdConcatenateFunctor (const PointInT &p1, PointOutT &p2) : p1_ (reinterpret_cast (p1)) @@ -70,10 +62,10 @@ namespace pcl { // This sucks without Fusion :( //boost::fusion::at_key (p2_) = boost::fusion::at_key (p1_); - typedef typename pcl::traits::datatype::type InT; - typedef typename pcl::traits::datatype::type OutT; + using InT = typename pcl::traits::datatype::type; + using OutT = typename pcl::traits::datatype::type; // Note: don't currently support different types for the same field (e.g. converting double to float) - BOOST_MPL_ASSERT_MSG ((boost::is_same::value), + BOOST_MPL_ASSERT_MSG ((std::is_same::value), POINT_IN_AND_POINT_OUT_HAVE_DIFFERENT_TYPES_FOR_FIELD, (Key, PointInT&, InT, PointOutT&, OutT)); memcpy (reinterpret_cast(&p2_) + pcl::traits::offset::value, @@ -86,14 +78,3 @@ namespace pcl PodOut &p2_; }; } - -#ifdef BUILD_Maintainer -# if defined __GNUC__ -# if __GNUC__ == 4 && __GNUC_MINOR__ > 3 -# pragma GCC diagnostic warning "-Weffc++" -# pragma GCC diagnostic warning "-pedantic" -# endif -# elif defined _MSC_VER -# pragma warning(pop) -# endif -#endif diff --git a/common/include/pcl/common/fft/_kiss_fft_guts.h b/common/include/pcl/common/fft/_kiss_fft_guts.h index ba661444039..8e3b56df1ad 100644 --- a/common/include/pcl/common/fft/_kiss_fft_guts.h +++ b/common/include/pcl/common/fft/_kiss_fft_guts.h @@ -15,7 +15,7 @@ THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND /* kiss_fft.h defines kiss_fft_scalar as either short or a float type and defines - typedef struct { kiss_fft_scalar r; kiss_fft_scalar i; }kiss_fft_cpx; */ + struct kiss_fft_cpx { kiss_fft_scalar r; kiss_fft_scalar i; }; */ #include "kiss_fft.h" #include diff --git a/common/include/pcl/common/gaussian.h b/common/include/pcl/common/gaussian.h index 16c6d225eda..2760203ba13 100644 --- a/common/include/pcl/common/gaussian.h +++ b/common/include/pcl/common/gaussian.h @@ -39,10 +39,11 @@ #pragma once -#include #include #include -#include + +#include +#include namespace pcl { @@ -57,8 +58,6 @@ namespace pcl { public: - GaussianKernel () {} - static const unsigned MAX_KERNEL_WIDTH = 71; /** Computes the gaussian kernel and dervative assiociated to sigma. * The kernel and derivative width are adjusted according. @@ -108,7 +107,7 @@ namespace pcl */ template void convolveRows (const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf &kernel, pcl::PointCloud &output) const; @@ -134,7 +133,7 @@ namespace pcl */ template void convolveCols (const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf &kernel, pcl::PointCloud &output) const; @@ -170,7 +169,7 @@ namespace pcl */ template inline void convolve (const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf &horiz_kernel, const Eigen::VectorXf &vert_kernel, pcl::PointCloud &output) const @@ -216,7 +215,7 @@ namespace pcl */ template inline void computeGradients (const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf &gaussian_kernel, const Eigen::VectorXf &gaussian_kernel_derivative, pcl::PointCloud &grad_x, @@ -251,7 +250,7 @@ namespace pcl */ template inline void smooth (const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf &gaussian_kernel, pcl::PointCloud &output) const { diff --git a/common/include/pcl/common/generate.h b/common/include/pcl/common/generate.h index 6305c713628..4e4fb1c4822 100644 --- a/common/include/pcl/common/generate.h +++ b/common/include/pcl/common/generate.h @@ -58,7 +58,7 @@ namespace pcl class CloudGenerator { public: - typedef typename GeneratorT::Parameters GeneratorParameters; + using GeneratorParameters = typename GeneratorT::Parameters; /// Default constructor CloudGenerator (); @@ -143,7 +143,7 @@ namespace pcl class CloudGenerator { public: - typedef typename GeneratorT::Parameters GeneratorParameters; + using GeneratorParameters = typename GeneratorT::Parameters; CloudGenerator (); diff --git a/common/include/pcl/common/impl/accumulators.hpp b/common/include/pcl/common/impl/accumulators.hpp index 029152bf6b8..e14284a866e 100644 --- a/common/include/pcl/common/impl/accumulators.hpp +++ b/common/include/pcl/common/impl/accumulators.hpp @@ -68,7 +68,7 @@ namespace pcl { // Requires that point type has x, y, and z fields - typedef pcl::traits::has_xyz IsCompatible; + using IsCompatible = pcl::traits::has_xyz; // Storage Eigen::Vector3f xyz; @@ -89,7 +89,7 @@ namespace pcl { // Requires that point type has normal_x, normal_y, and normal_z fields - typedef pcl::traits::has_normal IsCompatible; + using IsCompatible = pcl::traits::has_normal; // Storage Eigen::Vector4f normal; @@ -122,7 +122,7 @@ namespace pcl { // Requires that point type has curvature field - typedef pcl::traits::has_curvature IsCompatible; + using IsCompatible = pcl::traits::has_curvature; // Storage float curvature; @@ -141,7 +141,7 @@ namespace pcl { // Requires that point type has rgb or rgba field - typedef pcl::traits::has_color IsCompatible; + using IsCompatible = pcl::traits::has_color; // Storage float r, g, b, a; @@ -172,7 +172,7 @@ namespace pcl { // Requires that point type has intensity field - typedef pcl::traits::has_intensity IsCompatible; + using IsCompatible = pcl::traits::has_intensity; // Storage float intensity; @@ -191,7 +191,7 @@ namespace pcl { // Requires that point type has label field - typedef pcl::traits::has_label IsCompatible; + using IsCompatible = pcl::traits::has_label; // Storage // A better performance may be achieved with a heap structure @@ -240,7 +240,7 @@ namespace pcl template struct Accumulators { - typedef + using type = typename boost::fusion::result_of::as_vector< typename boost::mpl::filter_view< boost::mpl::vector< @@ -253,8 +253,7 @@ namespace pcl > , IsAccumulatorCompatible > - >::type - type; + >::type; }; /* Fusion function object to invoke point addition on every accumulator in diff --git a/common/include/pcl/common/impl/centroid.hpp b/common/include/pcl/common/impl/centroid.hpp index 86c8ace726d..422c94ac5dc 100644 --- a/common/include/pcl/common/impl/centroid.hpp +++ b/common/include/pcl/common/impl/centroid.hpp @@ -809,7 +809,7 @@ template inline void pcl::computeNDCentroid (const pcl::PointCloud &cloud, Eigen::Matrix ¢roid) { - typedef typename pcl::traits::fieldList::type FieldList; + using FieldList = typename pcl::traits::fieldList::type; // Get the size of the fields centroid.setZero (boost::mpl::size::value); @@ -832,7 +832,7 @@ pcl::computeNDCentroid (const pcl::PointCloud &cloud, const std::vector &indices, Eigen::Matrix ¢roid) { - typedef typename pcl::traits::fieldList::type FieldList; + using FieldList = typename pcl::traits::fieldList::type; // Get the size of the fields centroid.setZero (boost::mpl::size::value); diff --git a/common/include/pcl/common/impl/copy_point.hpp b/common/include/pcl/common/impl/copy_point.hpp index b4070a0e902..0f08ebfe6d1 100644 --- a/common/include/pcl/common/impl/copy_point.hpp +++ b/common/include/pcl/common/impl/copy_point.hpp @@ -77,7 +77,7 @@ namespace pcl struct CopyPointHelper { }; template - struct CopyPointHelper >::type> + struct CopyPointHelper::value>> { void operator () (const PointInT& point_in, PointOutT& point_out) const { @@ -87,36 +87,36 @@ namespace pcl template struct CopyPointHelper >, - boost::mpl::or_ >, - boost::mpl::not_ >, - boost::mpl::and_, - pcl::traits::has_field >, - boost::mpl::and_, - pcl::traits::has_field > > > >::type> + std::enable_if_t>, + boost::mpl::or_>, + boost::mpl::not_>, + boost::mpl::and_, + pcl::traits::has_field>, + boost::mpl::and_, + pcl::traits::has_field>>>::value>> { void operator () (const PointInT& point_in, PointOutT& point_out) const { - typedef typename pcl::traits::fieldList::type FieldListInT; - typedef typename pcl::traits::fieldList::type FieldListOutT; - typedef typename pcl::intersect::type FieldList; + using FieldListInT = typename pcl::traits::fieldList::type; + using FieldListOutT = typename pcl::traits::fieldList::type; + using FieldList = typename pcl::intersect::type; pcl::for_each_type (pcl::NdConcatenateFunctor (point_in, point_out)); } }; template struct CopyPointHelper >, - boost::mpl::or_, - pcl::traits::has_field >, - boost::mpl::and_, - pcl::traits::has_field > > > >::type> + std::enable_if_t>, + boost::mpl::or_, + pcl::traits::has_field>, + boost::mpl::and_, + pcl::traits::has_field>>>::value>> { void operator () (const PointInT& point_in, PointOutT& point_out) const { - typedef typename pcl::traits::fieldList::type FieldListInT; - typedef typename pcl::traits::fieldList::type FieldListOutT; - typedef typename pcl::intersect::type FieldList; + using FieldListInT = typename pcl::traits::fieldList::type; + using FieldListOutT = typename pcl::traits::fieldList::type; + using FieldList = typename pcl::intersect::type; const uint32_t offset_in = boost::mpl::if_, pcl::traits::offset, pcl::traits::offset >::type::value; diff --git a/common/include/pcl/common/impl/eigen.hpp b/common/include/pcl/common/impl/eigen.hpp index 76386547efd..0a302c4021b 100644 --- a/common/include/pcl/common/impl/eigen.hpp +++ b/common/include/pcl/common/impl/eigen.hpp @@ -60,7 +60,7 @@ pcl::computeRoots2 (const Scalar& b, const Scalar& c, Roots& roots) template inline void pcl::computeRoots (const Matrix& m, Roots& roots) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0. The // eigenvalues are the roots to this equation, all guaranteed to be @@ -218,7 +218,7 @@ pcl::eigen22 (const Matrix& mat, Matrix& eigenvectors, Vector& eigenvalues) template inline void pcl::computeCorrespondingEigenVector (const Matrix& mat, const typename Matrix::Scalar& eigenvalue, Vector& eigenvector) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; // Scale the matrix so its entries are in [-1,1]. The scaling is applied // only when at least one matrix entry has magnitude larger than 1. @@ -250,7 +250,7 @@ pcl::computeCorrespondingEigenVector (const Matrix& mat, const typename Matrix:: template inline void pcl::eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& eigenvector) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; // Scale the matrix so its entries are in [-1,1]. The scaling is applied // only when at least one matrix entry has magnitude larger than 1. @@ -287,7 +287,7 @@ pcl::eigen33 (const Matrix& mat, typename Matrix::Scalar& eigenvalue, Vector& ei template inline void pcl::eigen33 (const Matrix& mat, Vector& evals) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; Scalar scale = mat.cwiseAbs ().maxCoeff (); if (scale <= std::numeric_limits < Scalar > ::min ()) scale = Scalar (1.0); @@ -301,7 +301,7 @@ pcl::eigen33 (const Matrix& mat, Vector& evals) template inline void pcl::eigen33 (const Matrix& mat, Matrix& evecs, Vector& evals) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; // Scale the matrix so its entries are in [-1,1]. The scaling is applied // only when at least one matrix entry has magnitude larger than 1. @@ -484,7 +484,7 @@ pcl::eigen33 (const Matrix& mat, Matrix& evecs, Vector& evals) template inline typename Matrix::Scalar pcl::invert2x2 (const Matrix& matrix, Matrix& inverse) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; Scalar det = matrix.coeff (0) * matrix.coeff (3) - matrix.coeff (1) * matrix.coeff (2); if (det != 0) @@ -503,7 +503,7 @@ pcl::invert2x2 (const Matrix& matrix, Matrix& inverse) template inline typename Matrix::Scalar pcl::invert3x3SymMatrix (const Matrix& matrix, Matrix& inverse) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; // elements // a b c // b d e @@ -538,7 +538,7 @@ pcl::invert3x3SymMatrix (const Matrix& matrix, Matrix& inverse) template inline typename Matrix::Scalar pcl::invert3x3Matrix (const Matrix& matrix, Matrix& inverse) { - typedef typename Matrix::Scalar Scalar; + using Scalar = typename Matrix::Scalar; //| a b c |-1 | ie-hf hc-ib fb-ec | //| d e f | = 1/det * | gf-id ia-gc dc-fa | @@ -741,10 +741,10 @@ pcl::umeyama (const Eigen::MatrixBase& src, const Eigen::MatrixBase::type TransformationMatrixType; - typedef typename Eigen::internal::traits::Scalar Scalar; - typedef typename Eigen::NumTraits::Real RealScalar; - typedef typename Derived::Index Index; + using TransformationMatrixType = typename Eigen::internal::umeyama_transform_matrix_type::type; + using Scalar = typename Eigen::internal::traits::Scalar; + using RealScalar = typename Eigen::NumTraits::Real; + using Index = typename Derived::Index; static_assert (!Eigen::NumTraits::IsComplex, "Numeric type must be real."); static_assert ((Eigen::internal::is_same::Scalar>::value), @@ -752,9 +752,9 @@ pcl::umeyama (const Eigen::MatrixBase& src, const Eigen::MatrixBase VectorType; - typedef Eigen::Matrix MatrixType; - typedef typename Eigen::internal::plain_matrix_type_row_major::type RowMajorMatrixType; + using VectorType = Eigen::Matrix; + using MatrixType = Eigen::Matrix; + using RowMajorMatrixType = typename Eigen::internal::plain_matrix_type_row_major::type; const Index m = src.rows (); // dimension const Index n = src.cols (); // number of measurements diff --git a/common/include/pcl/common/impl/gaussian.hpp b/common/include/pcl/common/impl/gaussian.hpp index ef09383d783..3631a0de17e 100644 --- a/common/include/pcl/common/impl/gaussian.hpp +++ b/common/include/pcl/common/impl/gaussian.hpp @@ -42,9 +42,9 @@ #include -template void +template void pcl::GaussianKernel::convolveRows(const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf& kernel, pcl::PointCloud &output) const { @@ -75,9 +75,9 @@ pcl::GaussianKernel::convolveRows(const pcl::PointCloud &input, } } -template void +template void pcl::GaussianKernel::convolveCols(const pcl::PointCloud &input, - boost::function field_accessor, + std::function field_accessor, const Eigen::VectorXf& kernel, pcl::PointCloud &output) const { diff --git a/common/include/pcl/common/impl/intersections.hpp b/common/include/pcl/common/impl/intersections.hpp index cfc7a67b85a..12e8bf97e71 100644 --- a/common/include/pcl/common/impl/intersections.hpp +++ b/common/include/pcl/common/impl/intersections.hpp @@ -78,10 +78,10 @@ pcl::planeWithPlaneIntersection (const Eigen::Matrix &plane_a, Eigen::Matrix &line, double angular_tolerance) { - typedef Eigen::Matrix Vector3; - typedef Eigen::Matrix Vector4; - typedef Eigen::Matrix Vector5; - typedef Eigen::Matrix Matrix5; + using Vector3 = Eigen::Matrix; + using Vector4 = Eigen::Matrix; + using Vector5 = Eigen::Matrix; + using Matrix5 = Eigen::Matrix; // Normalize plane normals Vector3 plane_a_norm (plane_a.template head<3> ()); @@ -127,8 +127,8 @@ pcl::threePlanesIntersection (const Eigen::Matrix &plane_a, Eigen::Matrix &intersection_point, double determinant_tolerance) { - typedef Eigen::Matrix Vector3; - typedef Eigen::Matrix Matrix3; + using Vector3 = Eigen::Matrix; + using Matrix3 = Eigen::Matrix; // TODO: Using Eigen::HyperPlanes is better to solve this problem // Check if some planes are parallel diff --git a/common/include/pcl/common/impl/io.hpp b/common/include/pcl/common/impl/io.hpp index ac157e6e01b..3bf37ab871b 100644 --- a/common/include/pcl/common/impl/io.hpp +++ b/common/include/pcl/common/impl/io.hpp @@ -347,8 +347,8 @@ pcl::concatenateFields (const pcl::PointCloud &cloud1_in, const pcl::PointCloud &cloud2_in, pcl::PointCloud &cloud_out) { - typedef typename pcl::traits::fieldList::type FieldList1; - typedef typename pcl::traits::fieldList::type FieldList2; + using FieldList1 = typename pcl::traits::fieldList::type; + using FieldList2 = typename pcl::traits::fieldList::type; if (cloud1_in.points.size () != cloud2_in.points.size ()) { diff --git a/common/include/pcl/common/impl/projection_matrix.hpp b/common/include/pcl/common/impl/projection_matrix.hpp index efffea41046..71d1ef7ba8b 100644 --- a/common/include/pcl/common/impl/projection_matrix.hpp +++ b/common/include/pcl/common/impl/projection_matrix.hpp @@ -81,7 +81,7 @@ pcl::estimateProjectionMatrix ( const std::vector& indices) { // internally we calculate with double but store the result into float matrices. - typedef double Scalar; + using Scalar = double; projection_matrix.setZero (); if (cloud->height == 1 || cloud->width == 1) { diff --git a/common/include/pcl/common/io.h b/common/include/pcl/common/io.h index 11316f1c645..8aac9bc4fcc 100644 --- a/common/include/pcl/common/io.h +++ b/common/include/pcl/common/io.h @@ -226,13 +226,13 @@ namespace pcl } } - typedef enum + enum InterpolationType { BORDER_CONSTANT = 0, BORDER_REPLICATE = 1, BORDER_REFLECT = 2, BORDER_WRAP = 3, BORDER_REFLECT_101 = 4, BORDER_TRANSPARENT = 5, BORDER_DEFAULT = BORDER_REFLECT_101 - } InterpolationType; + }; /** \brief \return the right index according to the interpolation type. * \note this is adapted from OpenCV diff --git a/common/include/pcl/common/pca.h b/common/include/pcl/common/pca.h index 63a96db24c0..1237ea94415 100644 --- a/common/include/pcl/common/pca.h +++ b/common/include/pcl/common/pca.h @@ -61,12 +61,12 @@ namespace pcl class PCA : public pcl::PCLBase { public: - typedef pcl::PCLBase Base; - typedef typename Base::PointCloud PointCloud; - typedef typename Base::PointCloudPtr PointCloudPtr; - typedef typename Base::PointCloudConstPtr PointCloudConstPtr; - typedef typename Base::PointIndicesPtr PointIndicesPtr; - typedef typename Base::PointIndicesConstPtr PointIndicesConstPtr; + using Base = pcl::PCLBase; + using PointCloud = typename Base::PointCloud; + using PointCloudPtr = typename Base::PointCloudPtr; + using PointCloudConstPtr = typename Base::PointCloudConstPtr; + using PointIndicesPtr = typename Base::PointIndicesPtr; + using PointIndicesConstPtr = typename Base::PointIndicesConstPtr; using Base::input_; using Base::indices_; diff --git a/common/include/pcl/common/polynomial_calculations.h b/common/include/pcl/common/polynomial_calculations.h index b537debb8b5..919a1e5af95 100644 --- a/common/include/pcl/common/polynomial_calculations.h +++ b/common/include/pcl/common/polynomial_calculations.h @@ -124,8 +124,8 @@ namespace pcl Parameters parameters_; }; - typedef PolynomialCalculationsT PolynomialCalculationsd; - typedef PolynomialCalculationsT PolynomialCalculations; + using PolynomialCalculationsd = PolynomialCalculationsT; + using PolynomialCalculations = PolynomialCalculationsT; } // end namespace diff --git a/common/include/pcl/common/poses_from_matches.h b/common/include/pcl/common/poses_from_matches.h index 26efb33b65a..26bb1d5de1e 100644 --- a/common/include/pcl/common/poses_from_matches.h +++ b/common/include/pcl/common/poses_from_matches.h @@ -86,7 +86,7 @@ namespace pcl }; // =====TYPEDEFS===== - typedef std::vector > PoseEstimatesVector; + using PoseEstimatesVector = std::vector >; // =====STATIC METHODS===== diff --git a/common/include/pcl/common/random.h b/common/include/pcl/common/random.h index 98488ab58e6..2838823a1f1 100644 --- a/common/include/pcl/common/random.h +++ b/common/include/pcl/common/random.h @@ -53,19 +53,19 @@ namespace pcl template struct uniform_distribution::value>> { - typedef std::uniform_int_distribution type; + using type = std::uniform_int_distribution; }; /// uniform distribution float specialized template struct uniform_distribution::value>> { - typedef std::uniform_real_distribution type; + using type = std::uniform_real_distribution; }; /// normal distribution template struct normal_distribution { - typedef std::normal_distribution type; + using type = std::normal_distribution; }; /** \brief UniformGenerator class generates a random number from range [min, max] at each run picked @@ -132,7 +132,7 @@ namespace pcl run () { return (distribution_ (rng_)); } private: - typedef typename uniform_distribution::type DistributionType; + using DistributionType = typename uniform_distribution::type; /// parameters Parameters parameters_; /// random number generator @@ -203,7 +203,7 @@ namespace pcl inline T run () { return (distribution_ (rng_)); } - typedef typename normal_distribution::type DistributionType; + using DistributionType = typename normal_distribution::type; /// parameters Parameters parameters_; /// random number generator diff --git a/common/include/pcl/common/synchronizer.h b/common/include/pcl/common/synchronizer.h index 05bf1761b60..fa83fb5a183 100644 --- a/common/include/pcl/common/synchronizer.h +++ b/common/include/pcl/common/synchronizer.h @@ -35,6 +35,7 @@ #pragma once +#include #include namespace pcl @@ -50,15 +51,15 @@ namespace pcl template class Synchronizer { - typedef std::pair T1Stamped; - typedef std::pair T2Stamped; + using T1Stamped = std::pair; + using T2Stamped = std::pair; std::mutex mutex1_; std::mutex mutex2_; std::mutex publish_mutex_; std::deque queueT1; std::deque queueT2; - typedef boost::function CallbackFunction; + using CallbackFunction = std::function; std::map cb_; int callback_counter; @@ -109,7 +110,7 @@ namespace pcl for (typename std::map::iterator cb = cb_.begin (); cb != cb_.end (); ++cb) { - if (!cb->second.empty ()) + if (cb->second) { cb->second.operator()(queueT1.front ().second, queueT2.front ().second, queueT1.front ().first, queueT2.front ().first); } diff --git a/common/include/pcl/common/time_trigger.h b/common/include/pcl/common/time_trigger.h index 6e43679ca93..b9cfa72c264 100644 --- a/common/include/pcl/common/time_trigger.h +++ b/common/include/pcl/common/time_trigger.h @@ -40,11 +40,11 @@ #include #ifndef Q_MOC_RUN -#include #include #endif #include +#include #include #include @@ -56,7 +56,7 @@ namespace pcl class PCL_EXPORTS TimeTrigger { public: - typedef boost::function callback_type; + using callback_type = std::function; /** \brief Timer class that calls a callback method periodically. Due to possible blocking calls, only one callback method can be registered per instance. * \param[in] interval_seconds interval in seconds @@ -73,7 +73,7 @@ namespace pcl ~TimeTrigger (); /** \brief registers a callback - * \param[in] callback callback function to the list of callbacks. signature has to be boost::function + * \param[in] callback callback function to the list of callbacks. signature has to be std::function * \return connection the connection, which can be used to disable/enable and remove callback from list */ boost::signals2::connection registerCallback (const callback_type& callback); diff --git a/common/include/pcl/common/vector_average.h b/common/include/pcl/common/vector_average.h index f323a64b040..5b1c8a8fddf 100644 --- a/common/include/pcl/common/vector_average.h +++ b/common/include/pcl/common/vector_average.h @@ -111,9 +111,9 @@ namespace pcl Eigen::Matrix covariance_; }; - typedef VectorAverage VectorAverage2f; - typedef VectorAverage VectorAverage3f; - typedef VectorAverage VectorAverage4f; + using VectorAverage2f = VectorAverage; + using VectorAverage3f = VectorAverage; + using VectorAverage4f = VectorAverage; } // END namespace #include diff --git a/common/include/pcl/correspondence.h b/common/include/pcl/correspondence.h index 6b38b17f97a..0603a137695 100644 --- a/common/include/pcl/correspondence.h +++ b/common/include/pcl/correspondence.h @@ -90,9 +90,9 @@ namespace pcl /** \brief overloaded << operator */ PCL_EXPORTS std::ostream& operator << (std::ostream& os, const Correspondence& c); - typedef std::vector< pcl::Correspondence, Eigen::aligned_allocator > Correspondences; - typedef boost::shared_ptr CorrespondencesPtr; - typedef boost::shared_ptr CorrespondencesConstPtr; + using Correspondences = std::vector< pcl::Correspondence, Eigen::aligned_allocator >; + using CorrespondencesPtr = boost::shared_ptr; + using CorrespondencesConstPtr = boost::shared_ptr; /** * \brief Get the query points of correspondences that are present in @@ -131,7 +131,7 @@ namespace pcl PCL_MAKE_ALIGNED_OPERATOR_NEW }; - typedef std::vector > PointCorrespondences3DVector; + using PointCorrespondences3DVector = std::vector >; /** * \brief Representation of a (possible) correspondence between two points (e.g. from feature matching), @@ -147,7 +147,7 @@ namespace pcl PCL_MAKE_ALIGNED_OPERATOR_NEW }; - typedef std::vector > PointCorrespondences6DVector; + using PointCorrespondences6DVector = std::vector >; /** * \brief Comparator to enable us to sort a vector of PointCorrespondences according to their scores using diff --git a/common/include/pcl/for_each_type.h b/common/include/pcl/for_each_type.h index 762d0c37b11..3abbad748f2 100644 --- a/common/include/pcl/for_each_type.h +++ b/common/include/pcl/for_each_type.h @@ -53,9 +53,10 @@ #include #include #include -#include #endif +#include + namespace pcl { ////////////////////////////////////////////////////////////////////////////////////////////// @@ -73,7 +74,7 @@ namespace pcl template static void execute (F f) { - typedef typename boost::mpl::deref::type arg; + using arg = typename boost::mpl::deref::type; #if (defined _WIN32 && defined _MSC_VER) boost::mpl::aux::unwrap (f, 0).operator() (); @@ -81,8 +82,8 @@ namespace pcl boost::mpl::aux::unwrap (f, 0).template operator() (); #endif - typedef typename boost::mpl::next::type iter; - for_each_type_impl::value> + using iter = typename boost::mpl::next::type; + for_each_type_impl::value> ::template execute (f); } }; @@ -92,15 +93,15 @@ namespace pcl for_each_type (F f) { BOOST_MPL_ASSERT (( boost::mpl::is_sequence )); - typedef typename boost::mpl::begin::type first; - typedef typename boost::mpl::end::type last; - for_each_type_impl::value>::template execute (f); + using first = typename boost::mpl::begin::type; + using last = typename boost::mpl::end::type; + for_each_type_impl::value>::template execute (f); } ////////////////////////////////////////////////////////////////////////////////////////////// template struct intersect { - typedef typename boost::mpl::remove_if > >::type type; + using type = typename boost::mpl::remove_if > >::type; }; } diff --git a/common/include/pcl/impl/point_types.hpp b/common/include/pcl/impl/point_types.hpp index 93d7013e747..43ea7f6114b 100644 --- a/common/include/pcl/impl/point_types.hpp +++ b/common/include/pcl/impl/point_types.hpp @@ -161,21 +161,21 @@ namespace pcl { - typedef Eigen::Map Array3fMap; - typedef const Eigen::Map Array3fMapConst; - typedef Eigen::Map Array4fMap; - typedef const Eigen::Map Array4fMapConst; - typedef Eigen::Map Vector3fMap; - typedef const Eigen::Map Vector3fMapConst; - typedef Eigen::Map Vector4fMap; - typedef const Eigen::Map Vector4fMapConst; - - typedef Eigen::Matrix Vector3c; - typedef Eigen::Map Vector3cMap; - typedef const Eigen::Map Vector3cMapConst; - typedef Eigen::Matrix Vector4c; - typedef Eigen::Map Vector4cMap; - typedef const Eigen::Map Vector4cMapConst; + using Array3fMap = Eigen::Map; + using Array3fMapConst = const Eigen::Map; + using Array4fMap = Eigen::Map; + using Array4fMapConst = const Eigen::Map; + using Vector3fMap = Eigen::Map; + using Vector3fMapConst = const Eigen::Map; + using Vector4fMap = Eigen::Map; + using Vector4fMapConst = const Eigen::Map; + + using Vector3c = Eigen::Matrix; + using Vector3cMap = Eigen::Map; + using Vector3cMapConst = const Eigen::Map; + using Vector4c = Eigen::Matrix; + using Vector4cMap = Eigen::Map; + using Vector4cMapConst = const Eigen::Map; #define PCL_ADD_UNION_POINT4D \ union EIGEN_ALIGN16 { \ diff --git a/common/include/pcl/pcl_base.h b/common/include/pcl/pcl_base.h index ec2c2927c36..eafb80cbeee 100644 --- a/common/include/pcl/pcl_base.h +++ b/common/include/pcl/pcl_base.h @@ -57,8 +57,9 @@ namespace pcl { // definitions used everywhere - typedef boost::shared_ptr > IndicesPtr; - typedef boost::shared_ptr > IndicesConstPtr; + using Indices = std::vector; + using IndicesPtr = boost::shared_ptr; + using IndicesConstPtr = boost::shared_ptr; ///////////////////////////////////////////////////////////////////////////////////////// /** \brief PCL base class. Implements methods that are used by most PCL algorithms. @@ -68,12 +69,12 @@ namespace pcl class PCLBase { public: - typedef pcl::PointCloud PointCloud; - typedef typename PointCloud::Ptr PointCloudPtr; - typedef typename PointCloud::ConstPtr PointCloudConstPtr; + using PointCloud = pcl::PointCloud; + using PointCloudPtr = typename PointCloud::Ptr; + using PointCloudConstPtr = typename PointCloud::ConstPtr; - typedef boost::shared_ptr PointIndicesPtr; - typedef boost::shared_ptr PointIndicesConstPtr; + using PointIndicesPtr = boost::shared_ptr; + using PointIndicesConstPtr = boost::shared_ptr; /** \brief Empty constructor. */ PCLBase (); @@ -184,12 +185,12 @@ namespace pcl class PCL_EXPORTS PCLBase { public: - typedef pcl::PCLPointCloud2 PCLPointCloud2; - typedef boost::shared_ptr PCLPointCloud2Ptr; - typedef boost::shared_ptr PCLPointCloud2ConstPtr; + using PCLPointCloud2 = pcl::PCLPointCloud2; + using PCLPointCloud2Ptr = boost::shared_ptr; + using PCLPointCloud2ConstPtr = boost::shared_ptr; - typedef boost::shared_ptr PointIndicesPtr; - typedef boost::shared_ptr PointIndicesConstPtr; + using PointIndicesPtr = boost::shared_ptr; + using PointIndicesConstPtr = boost::shared_ptr; /** \brief Empty constructor. */ PCLBase (); diff --git a/common/include/pcl/point_cloud.h b/common/include/pcl/point_cloud.h index 9f4a2748ef2..191e68922a2 100644 --- a/common/include/pcl/point_cloud.h +++ b/common/include/pcl/point_cloud.h @@ -63,13 +63,13 @@ namespace pcl // Forward declarations template class PointCloud; - typedef std::vector MsgFieldMap; + using MsgFieldMap = std::vector; /** \brief Helper functor structure for copying data between an Eigen type and a PointT. */ template struct NdCopyEigenPointFunctor { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; /** \brief Constructor * \param[in] p1 the input Eigen type @@ -85,7 +85,7 @@ namespace pcl operator() () { //boost::fusion::at_key (p2_) = p1_[f_idx_++]; - typedef typename pcl::traits::datatype::type T; + using T = typename pcl::traits::datatype::type; uint8_t* data_ptr = reinterpret_cast(&p2_) + pcl::traits::offset::value; *reinterpret_cast(data_ptr) = static_cast (p1_[f_idx_++]); } @@ -102,7 +102,7 @@ namespace pcl template struct NdCopyPointEigenFunctor { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; /** \brief Constructor * \param[in] p1 the input Point type @@ -116,7 +116,7 @@ namespace pcl operator() () { //p2_[f_idx_++] = boost::fusion::at_key (p1_); - typedef typename pcl::traits::datatype::type T; + using T = typename pcl::traits::datatype::type; const uint8_t* data_ptr = reinterpret_cast(&p1_) + pcl::traits::offset::value; p2_[f_idx_++] = static_cast (*reinterpret_cast(data_ptr)); } @@ -422,23 +422,23 @@ namespace pcl /** \brief Sensor acquisition pose (rotation). */ Eigen::Quaternionf sensor_orientation_; - typedef PointT PointType; // Make the template class available from the outside - typedef std::vector > VectorType; - typedef std::vector, Eigen::aligned_allocator > > CloudVectorType; - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using PointType = PointT; // Make the template class available from the outside + using VectorType = std::vector >; + using CloudVectorType = std::vector, Eigen::aligned_allocator > >; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; // std container compatibility typedefs according to // http://en.cppreference.com/w/cpp/concept/Container - typedef PointT value_type; - typedef PointT& reference; - typedef const PointT& const_reference; - typedef typename VectorType::difference_type difference_type; - typedef typename VectorType::size_type size_type; + using value_type = PointT; + using reference = PointT&; + using const_reference = const PointT&; + using difference_type = typename VectorType::difference_type; + using size_type = typename VectorType::size_type; // iterators - typedef typename VectorType::iterator iterator; - typedef typename VectorType::const_iterator const_iterator; + using iterator = typename VectorType::iterator; + using const_iterator = typename VectorType::const_iterator; inline iterator begin () { return (points.begin ()); } inline iterator end () { return (points.end ()); } inline const_iterator begin () const { return (points.begin ()); } diff --git a/common/include/pcl/point_representation.h b/common/include/pcl/point_representation.h index 7ebb9fd61ea..9a703ece88a 100644 --- a/common/include/pcl/point_representation.h +++ b/common/include/pcl/point_representation.h @@ -71,8 +71,8 @@ namespace pcl bool trivial_; public: - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; /** \brief Empty constructor */ PointRepresentation () : nr_dimensions_ (0), alpha_ (0), trivial_ (false) {} @@ -182,8 +182,8 @@ namespace pcl public: // Boost shared pointers - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; DefaultPointRepresentation () { @@ -242,14 +242,14 @@ namespace pcl struct NdCopyPointFunctor { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; NdCopyPointFunctor (const PointDefault &p1, float * p2) : p1_ (reinterpret_cast(p1)), p2_ (p2), f_idx_ (0) { } template inline void operator() () { - typedef typename pcl::traits::datatype::type FieldT; + using FieldT = typename pcl::traits::datatype::type; const int NrDims = pcl::traits::datatype::size; Helper::copyPoint (p1_, p2_, f_idx_); } @@ -290,9 +290,9 @@ namespace pcl public: // Boost shared pointers - typedef typename boost::shared_ptr > Ptr; - typedef typename boost::shared_ptr > ConstPtr; - typedef typename pcl::traits::fieldList::type FieldList; + using Ptr = typename boost::shared_ptr >; + using ConstPtr = typename boost::shared_ptr >; + using FieldList = typename pcl::traits::fieldList::type; DefaultFeatureRepresentation () { @@ -536,8 +536,8 @@ namespace pcl public: // Boost shared pointers - typedef boost::shared_ptr > Ptr; - typedef boost::shared_ptr > ConstPtr; + using Ptr = boost::shared_ptr >; + using ConstPtr = boost::shared_ptr >; /** \brief Constructor * \param[in] max_dim the maximum number of dimensions to use diff --git a/common/include/pcl/point_traits.h b/common/include/pcl/point_traits.h index 920d87aa54a..a9c5a12f183 100644 --- a/common/include/pcl/point_traits.h +++ b/common/include/pcl/point_traits.h @@ -45,8 +45,6 @@ #include "pcl/pcl_macros.h" #include -#include -#include #include // This is required for the workaround at line 109 @@ -55,6 +53,8 @@ #include #endif +#include + namespace pcl { namespace deprecated @@ -85,20 +85,20 @@ namespace pcl // Metafunction to return type of enum value template struct asType {}; - template<> struct asType { typedef int8_t type; }; - template<> struct asType { typedef uint8_t type; }; - template<> struct asType { typedef int16_t type; }; - template<> struct asType { typedef uint16_t type; }; - template<> struct asType { typedef int32_t type; }; - template<> struct asType { typedef uint32_t type; }; - template<> struct asType { typedef float type; }; - template<> struct asType { typedef double type; }; + template<> struct asType { using type = int8_t; }; + template<> struct asType { using type = uint8_t; }; + template<> struct asType { using type = int16_t; }; + template<> struct asType { using type = uint16_t; }; + template<> struct asType { using type = int32_t; }; + template<> struct asType { using type = uint32_t; }; + template<> struct asType { using type = float; }; + template<> struct asType { using type = double; }; // Metafunction to decompose a type (possibly of array of any number of dimensions) into // its scalar type and total number of elements. template struct decomposeArray { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t value = sizeof (T) / sizeof (type); }; @@ -106,7 +106,7 @@ namespace pcl template struct POD { - typedef PointT type; + using type = PointT; }; #ifdef _MSC_VER @@ -122,7 +122,7 @@ namespace pcl template struct POD > { - typedef PointT type; + using type = PointT; }; #endif @@ -144,7 +144,7 @@ namespace pcl // static const char value[]; // Avoid infinite compile-time recursion - BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + BOOST_MPL_ASSERT_MSG((!std::is_same::type>::value), POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); }; @@ -156,7 +156,7 @@ namespace pcl // static const size_t value; // Avoid infinite compile-time recursion - BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + BOOST_MPL_ASSERT_MSG((!std::is_same::type>::value), POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); }; @@ -165,12 +165,12 @@ namespace pcl struct datatype : datatype::type, Tag> { // Contents of specialization: - // typedef ... type; + // using type = ...; // static const uint8_t value; // static const uint32_t size; // Avoid infinite compile-time recursion - BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + BOOST_MPL_ASSERT_MSG((!std::is_same::type>::value), POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); }; @@ -179,23 +179,12 @@ namespace pcl struct fieldList : fieldList::type> { // Contents of specialization: - // typedef boost::mpl::vector<...> type; + // using type = boost::mpl::vector<...>; // Avoid infinite compile-time recursion - BOOST_MPL_ASSERT_MSG((!boost::is_same::type>::value), + BOOST_MPL_ASSERT_MSG((!std::is_same::type>::value), POINT_TYPE_NOT_PROPERLY_REGISTERED, (PointT&)); }; -#if PCL_LINEAR_VERSION(__GNUC__,__GNUC_MINOR__,__GNUC_PATCHLEVEL__) == PCL_LINEAR_VERSION(4,4,3) - /* - At least on GCC 4.4.3, but not later versions, some valid usages of the above traits for - non-POD (but registered) point types fail with: - error: ‘!(bool)mpl_::bool_::value’ is not a valid template argument for type ‘bool’ because it is a non-constant expression - - "Priming the pump" with the trivial assertion below somehow fixes the problem... - */ - //BOOST_MPL_ASSERT_MSG((!bool (mpl_::bool_::value)), WTF_GCC443, (bool)); - BOOST_MPL_ASSERT_MSG((!bool (boost::mpl::bool_::value)), WTF_GCC443, (bool)); -#endif } //namespace traits // Return true if the PCLPointField matches the expected name and data type. @@ -221,14 +210,14 @@ namespace pcl * PointInT p; * bool exists; * float value; - * typedef typename pcl::traits::fieldList::type FieldList; + * using FieldList = typename pcl::traits::fieldList::type; * pcl::for_each_type (pcl::CopyIfFieldExists (p, "intensity", exists, value)); * \endcode */ template struct CopyIfFieldExists { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; /** \brief Constructor. * \param[in] pt the input point @@ -264,7 +253,7 @@ namespace pcl if (name_ == pcl::traits::name::value) { exists_ = true; - typedef typename pcl::traits::datatype::type T; + using T = typename pcl::traits::datatype::type; const uint8_t* data_ptr = reinterpret_cast(&pt_) + pcl::traits::offset::value; value_ = static_cast (*reinterpret_cast(data_ptr)); } @@ -286,14 +275,14 @@ namespace pcl * * \code * PointT p; - * typedef typename pcl::traits::fieldList::type FieldList; + * using FieldList = typename pcl::traits::fieldList::type; * pcl::for_each_type (pcl::SetIfFieldExists (p, "intensity", 42.0f)); * \endcode */ template struct SetIfFieldExists { - typedef typename traits::POD::type Pod; + using Pod = typename traits::POD::type; /** \brief Constructor. * \param[in] pt the input point @@ -313,7 +302,7 @@ namespace pcl { if (name_ == pcl::traits::name::value) { - typedef typename pcl::traits::datatype::type T; + using T = typename pcl::traits::datatype::type; uint8_t* data_ptr = reinterpret_cast(&pt_) + pcl::traits::offset::value; *reinterpret_cast(data_ptr) = static_cast (value_); } diff --git a/common/include/pcl/point_types.h b/common/include/pcl/point_types.h index 386f9bb2419..b3d1a453785 100644 --- a/common/include/pcl/point_types.h +++ b/common/include/pcl/point_types.h @@ -308,7 +308,7 @@ namespace pcl /** \brief Data type to store extended information about a transition from foreground to backgroundSpecification of the fields for BorderDescription::traits. * \ingroup common */ - typedef std::bitset<32> BorderTraits; + using BorderTraits = std::bitset<32>; /** \brief Specification of the fields for BorderDescription::traits. * \ingroup common diff --git a/common/include/pcl/range_image/bearing_angle_image.h b/common/include/pcl/range_image/bearing_angle_image.h index 3bf0381f89b..83c1a590ef0 100644 --- a/common/include/pcl/range_image/bearing_angle_image.h +++ b/common/include/pcl/range_image/bearing_angle_image.h @@ -54,7 +54,7 @@ namespace pcl { public: // ===== TYPEDEFS ===== - typedef pcl::PointCloud BaseClass; + using BaseClass = pcl::PointCloud; // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ diff --git a/common/include/pcl/range_image/impl/range_image.hpp b/common/include/pcl/range_image/impl/range_image.hpp index b80e90d40e3..1252d8382be 100644 --- a/common/include/pcl/range_image/impl/range_image.hpp +++ b/common/include/pcl/range_image/impl/range_image.hpp @@ -229,7 +229,7 @@ RangeImage::createFromPointCloudWithViewpoints (const PointCloudTypeWithViewpoin template void RangeImage::doZBuffer (const PointCloudType& point_cloud, float noise_level, float min_range, int& top, int& right, int& bottom, int& left) { - typedef typename PointCloudType::PointType PointType2; + using PointType2 = typename PointCloudType::PointType; const typename pcl::PointCloud::VectorType &points2 = point_cloud.points; unsigned int size = width*height; diff --git a/common/include/pcl/range_image/range_image.h b/common/include/pcl/range_image/range_image.h index 4aef16586d1..7a5a70f7f23 100644 --- a/common/include/pcl/range_image/range_image.h +++ b/common/include/pcl/range_image/range_image.h @@ -56,10 +56,10 @@ namespace pcl { public: // =====TYPEDEFS===== - typedef pcl::PointCloud BaseClass; - typedef std::vector > VectorOfEigenVector3f; - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using BaseClass = pcl::PointCloud; + using VectorOfEigenVector3f = std::vector >; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; enum CoordinateFrame { diff --git a/common/include/pcl/range_image/range_image_planar.h b/common/include/pcl/range_image/range_image_planar.h index ca2719578ec..de2014968cc 100644 --- a/common/include/pcl/range_image/range_image_planar.h +++ b/common/include/pcl/range_image/range_image_planar.h @@ -52,9 +52,9 @@ namespace pcl { public: // =====TYPEDEFS===== - typedef RangeImage BaseClass; - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using BaseClass = RangeImage; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ diff --git a/common/include/pcl/range_image/range_image_spherical.h b/common/include/pcl/range_image/range_image_spherical.h index f595d2e7f5b..da2b061b016 100644 --- a/common/include/pcl/range_image/range_image_spherical.h +++ b/common/include/pcl/range_image/range_image_spherical.h @@ -51,9 +51,9 @@ namespace pcl { public: // =====TYPEDEFS===== - typedef RangeImage BaseClass; - typedef boost::shared_ptr Ptr; - typedef boost::shared_ptr ConstPtr; + using BaseClass = RangeImage; + using Ptr = boost::shared_ptr; + using ConstPtr = boost::shared_ptr; // =====CONSTRUCTOR & DESTRUCTOR===== /** Constructor */ diff --git a/common/include/pcl/register_point_struct.h b/common/include/pcl/register_point_struct.h index 349063c97b8..61df205c3d0 100644 --- a/common/include/pcl/register_point_struct.h +++ b/common/include/pcl/register_point_struct.h @@ -60,10 +60,10 @@ #include #include #include -#include -#include #endif -#include //offsetof + +#include //offsetof +#include // Must be used in global namespace with name fully qualified #define POINT_CLOUD_REGISTER_POINT_STRUCT(name, fseq) \ @@ -75,7 +75,7 @@ BOOST_MPL_ASSERT_MSG(sizeof(wrapper) == sizeof(pod), POINT_WRAPPER_AND_POD_TYPES_HAVE_DIFFERENT_SIZES, (wrapper&, pod&)); \ namespace pcl { \ namespace traits { \ - template<> struct POD { typedef pod type; }; \ + template<> struct POD { using type = pod; }; \ } \ } \ /***/ @@ -94,102 +94,102 @@ namespace pcl namespace traits { template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> plus (T &l, const T &r) { l += r; } template inline - typename boost::enable_if_c::value>::type - plus (typename boost::remove_const::type &l, const T &r) + std::enable_if_t::value> + plus (std::remove_const_t &l, const T &r) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T) / sizeof (type); for (int i = 0; i < count; ++i) l[i] += r[i]; } template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> plusscalar (T1 &p, const T2 &scalar) { p += scalar; } template inline - typename boost::enable_if_c::value>::type + std::enable_if_t::value> plusscalar (T1 &p, const T2 &scalar) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T1) / sizeof (type); for (int i = 0; i < count; ++i) p[i] += scalar; } template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> minus (T &l, const T &r) { l -= r; } template inline - typename boost::enable_if_c::value>::type - minus (typename boost::remove_const::type &l, const T &r) + std::enable_if_t::value> + minus (std::remove_const_t &l, const T &r) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T) / sizeof (type); for (int i = 0; i < count; ++i) l[i] -= r[i]; } template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> minusscalar (T1 &p, const T2 &scalar) { p -= scalar; } template inline - typename boost::enable_if_c::value>::type + std::enable_if_t::value> minusscalar (T1 &p, const T2 &scalar) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T1) / sizeof (type); for (int i = 0; i < count; ++i) p[i] -= scalar; } template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> mulscalar (T1 &p, const T2 &scalar) { p *= scalar; } template inline - typename boost::enable_if_c::value>::type + std::enable_if_t::value> mulscalar (T1 &p, const T2 &scalar) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T1) / sizeof (type); for (int i = 0; i < count; ++i) p[i] *= scalar; } template inline - typename boost::disable_if_c::value>::type + std::enable_if_t::value> divscalar (T1 &p, const T2 &scalar) { p /= scalar; } template inline - typename boost::enable_if_c::value>::type + std::enable_if_t::value> divscalar (T1 &p, const T2 &scalar) { - typedef typename boost::remove_all_extents::type type; + using type = std::remove_all_extents_t; static const uint32_t count = sizeof (T1) / sizeof (type); for (int i = 0; i < count; ++i) p[i] /= scalar; @@ -231,7 +231,7 @@ namespace pcl /***/ // Construct type traits given full sequence of (type, name, tag) triples -// BOOST_MPL_ASSERT_MSG(boost::is_pod::value, +// BOOST_MPL_ASSERT_MSG(std::is_pod::value, // REGISTERED_POINT_TYPE_MUST_BE_PLAIN_OLD_DATA, (name)); #define POINT_CLOUD_REGISTER_POINT_STRUCT_I(name, seq) \ namespace pcl \ @@ -334,15 +334,11 @@ namespace pcl }; \ /***/ -// \note: the mpl::identity weirdness is to support array types without requiring the -// user to wrap them. The basic problem is: -// typedef float[81] type; // SYNTAX ERROR! -// typedef float type[81]; // OK, can now use "type" as a synonym for float[81] #define POINT_CLOUD_REGISTER_FIELD_DATATYPE(r, name, elem) \ template<> struct datatype \ { \ - typedef boost::mpl::identity::type type; \ - typedef decomposeArray decomposed; \ + using type = boost::mpl::identity::type; \ + using decomposed = decomposeArray; \ static const uint8_t value = asEnum::value; \ static const uint32_t size = decomposed::value; \ }; \ @@ -355,7 +351,7 @@ namespace pcl #define POINT_CLOUD_REGISTER_POINT_FIELD_LIST(name, seq) \ template<> struct fieldList \ { \ - typedef boost::mpl::vector type; \ + using type = boost::mpl::vector; \ }; \ /***/ diff --git a/cuda/apps/src/kinect_cloud.cpp b/cuda/apps/src/kinect_cloud.cpp index c16f814383a..d2dbc87da25 100644 --- a/cuda/apps/src/kinect_cloud.cpp +++ b/cuda/apps/src/kinect_cloud.cpp @@ -62,7 +62,7 @@ struct EventHelper const pcl::PCLImage::ConstPtr &rgb, const pcl::CameraInfo::ConstPtr &info) { - //typedef pcl_cuda::SampleConsensusModel::Indices Indices; + //using Indices = pcl_cuda::SampleConsensusModel::Indices; //pcl_cuda::PointCloudAOS::Ptr data (new pcl_cuda::PointCloudAOS); PointCloudAOS::Ptr data; diff --git a/cuda/apps/src/kinect_debayering.cpp b/cuda/apps/src/kinect_debayering.cpp index daa5fd7678b..5e8a75b3590 100644 --- a/cuda/apps/src/kinect_debayering.cpp +++ b/cuda/apps/src/kinect_debayering.cpp @@ -44,6 +44,7 @@ #include +#include #include #include @@ -72,7 +73,7 @@ class SimpleKinectTool cv::namedWindow("test", CV_WINDOW_AUTOSIZE); pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id); - boost::function& image)> f = boost::bind (&SimpleKinectTool::cloud_cb_, this, _1); + std::function& image)> f = boost::bind (&SimpleKinectTool::cloud_cb_, this, _1); boost::signals2::connection c = interface->registerCallback (f); diff --git a/cuda/apps/src/kinect_dediscretize.cpp b/cuda/apps/src/kinect_dediscretize.cpp index ee336a62fae..3c391e9e697 100644 --- a/cuda/apps/src/kinect_dediscretize.cpp +++ b/cuda/apps/src/kinect_dediscretize.cpp @@ -48,6 +48,7 @@ #include +#include #include #include @@ -76,7 +77,7 @@ class SimpleKinectTool { pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id); - boost::function& image, const boost::shared_ptr& depth_image, float)> f = boost::bind (&SimpleKinectTool::cloud_cb_, this, _1, _2, _3); + std::function& image, const boost::shared_ptr& depth_image, float)> f = boost::bind (&SimpleKinectTool::cloud_cb_, this, _1, _2, _3); boost::signals2::connection c = interface->registerCallback (f); diff --git a/cuda/apps/src/kinect_mapping.cpp b/cuda/apps/src/kinect_mapping.cpp index e8227b9b87d..afddd8c8a02 100644 --- a/cuda/apps/src/kinect_mapping.cpp +++ b/cuda/apps/src/kinect_mapping.cpp @@ -35,25 +35,24 @@ * */ -#include -#include #include #include #include #include #include #include +#include +#include +#include #include #include #include #include #include -#include #include #include - #include #include @@ -63,6 +62,7 @@ #include #include +#include #include #include @@ -71,19 +71,19 @@ using namespace pcl_cuda; template