Skip to content

Commit

Permalink
Merge branch 'master' into pcl_make_shared
Browse files Browse the repository at this point in the history
  • Loading branch information
aPonza authored Jun 13, 2019
2 parents e360687 + cb92b7d commit f29e39a
Show file tree
Hide file tree
Showing 688 changed files with 4,168 additions and 4,259 deletions.
8 changes: 4 additions & 4 deletions 2d/include/pcl/2d/edge.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ namespace pcl
class Edge
{
private:
typedef pcl::PointCloud<PointInT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
using PointCloudIn = pcl::PointCloud<PointInT>;
using PointCloudInPtr = typename PointCloudIn::Ptr;

PointCloudInPtr input_;
pcl::Convolution<PointInT> convolution_;
Expand Down Expand Up @@ -84,8 +84,8 @@ namespace pcl
pcl::PointCloud<pcl::PointXYZI> &maxima, float tLow);

public:
typedef boost::shared_ptr<Edge> Ptr;
typedef boost::shared_ptr<const Edge> ConstPtr;
using Ptr = boost::shared_ptr<Edge<PointInT, PointOutT> >;
using ConstPtr = boost::shared_ptr<const Edge<PointInT, PointOutT> >;

enum OUTPUT_TYPE
{
Expand Down
4 changes: 2 additions & 2 deletions 2d/include/pcl/2d/morphology.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ namespace pcl
class Morphology : public PCLBase<PointT>
{
private:
typedef pcl::PointCloud<PointT> PointCloudIn;
typedef typename PointCloudIn::Ptr PointCloudInPtr;
using PointCloudIn = pcl::PointCloud<PointT>;
using PointCloudInPtr = typename PointCloudIn::Ptr;

PointCloudInPtr structuring_element_;

Expand Down
15 changes: 4 additions & 11 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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")
Expand Down Expand Up @@ -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})
Expand Down Expand Up @@ -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")

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,11 @@
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/apps/3d_rec_framework/utils/vtk_model_sampling.h>
#include <boost/function.hpp>

#include <vtkTransformPolyDataFilter.h>

#include <functional>

namespace pcl
{
namespace rec_3d_framework
Expand Down Expand Up @@ -42,7 +44,7 @@ namespace pcl
float radius_sphere_;
float view_angle_;
bool gen_organized_;
boost::function<bool
std::function<bool
(const Eigen::Vector3f &)> campos_constraints_func_;

public:
Expand All @@ -62,7 +64,7 @@ namespace pcl
}

void
setCamPosConstraints (boost::function<bool
setCamPosConstraints (std::function<bool
(const Eigen::Vector3f &)> & bb)
{
campos_constraints_func_ = bb;
Expand Down
2 changes: 1 addition & 1 deletion apps/3d_rec_framework/src/tools/global_classification.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ segmentAndClassify (typename pcl::rec_3d_framework::GlobalNNPipeline<DistT, Poin
pcl::visualization::PCLVisualizer vis ("kinect");

//keyboard callback to stop getting frames and finalize application
boost::function<void
std::function<void
(const pcl::visualization::KeyboardEvent&)> keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera, _1);
vis.registerKeyboardCallback (keyboard_cb);
size_t previous_cluster_size = 0;
Expand Down
2 changes: 1 addition & 1 deletion apps/3d_rec_framework/src/tools/openni_frame_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace OpenNIFrameSource
OpenNIFrameSource::OpenNIFrameSource (const std::string& device_id) :
grabber_ (device_id), frame_counter_ (0), active_ (true)
{
boost::function<void
std::function<void
(const PointCloudConstPtr&)> frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1);
grabber_.registerCallback (frame_cb);
grabber_.start ();
Expand Down
2 changes: 0 additions & 2 deletions apps/in_hand_scanner/include/pcl/apps/in_hand_scanner/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,7 @@
# pragma GCC system_header
#endif

#include <boost/unordered_map.hpp>
#include <boost/bind/bind.hpp>
#include <boost/math/special_functions/fpclassify.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/signals2/connection.hpp>
#include <boost/type_traits/is_same.hpp>
Original file line number Diff line number Diff line change
Expand Up @@ -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!
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@
#include <mutex>
#include <iomanip>
#include <string>
#include <unordered_map>

namespace pcl
{
Expand Down Expand Up @@ -331,7 +332,7 @@ namespace pcl
typedef Eigen::Matrix <unsigned char, 3, Eigen::Dynamic> Colors;
typedef Eigen::Matrix <unsigned char, 3, 256 > Colormap;

typedef boost::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;
typedef std::unordered_map <std::string, CloudXYZRGBNormalPtr> CloudXYZRGBNormalMap;

typedef pcl::ihs::PointIHS PointIHS;
typedef pcl::ihs::CloudIHS CloudIHS;
Expand All @@ -341,7 +342,7 @@ namespace pcl
typedef pcl::ihs::detail::FaceVertexMesh FaceVertexMesh;
typedef boost::shared_ptr < FaceVertexMesh> FaceVertexMeshPtr;
typedef boost::shared_ptr <const FaceVertexMesh> FaceVertexMeshConstPtr;
typedef boost::unordered_map <std::string, FaceVertexMeshPtr> FaceVertexMeshMap;
typedef std::unordered_map <std::string, FaceVertexMeshPtr> FaceVertexMeshMap;

/** \brief Check if the mesh with the given id is added.
* \note Must lock the mutex before calling this method.
Expand Down
2 changes: 1 addition & 1 deletion apps/in_hand_scanner/src/in_hand_scanner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -483,7 +483,7 @@ pcl::ihs::InHandScanner::startGrabberImpl ()
lock.lock ();
if (destructor_called_) return;

boost::function <void (const CloudXYZRGBAConstPtr&)> new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1);
std::function <void (const CloudXYZRGBAConstPtr&)> new_data_cb = boost::bind (&pcl::ihs::InHandScanner::newDataCallback, this, _1);
new_data_connection_ = grabber_->registerCallback (new_data_cb);
grabber_->start ();

Expand Down
30 changes: 15 additions & 15 deletions apps/include/pcl/apps/organized_segmentation_demo.h
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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
Expand Down Expand Up @@ -89,7 +89,7 @@ class OrganizedSegmentationDemo : public QMainWindow
typedef pcl::PointCloud<PointT> Cloud;
typedef Cloud::Ptr CloudPtr;
typedef Cloud::ConstPtr CloudConstPtr;


OrganizedSegmentationDemo(pcl::Grabber& grabber);

Expand All @@ -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_;
Expand All @@ -113,9 +113,9 @@ class OrganizedSegmentationDemo : public QMainWindow
pcl::PointCloud<pcl::Normal> prev_normals_;
std::vector<pcl::PlanarRegion<PointT>, Eigen::aligned_allocator<pcl::PlanarRegion<PointT> > > prev_regions_;
float* prev_distance_map_;

pcl::PointCloud<PointT>::CloudVectorType prev_clusters_;

pcl::IntegralImageNormalEstimation<PointT, pcl::Normal> ne;
pcl::OrganizedMultiPlaneSegmentation<PointT, pcl::Normal, pcl::Label> mps;

Expand Down Expand Up @@ -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;
Expand All @@ -172,7 +172,7 @@ class OrganizedSegmentationDemo : public QMainWindow
{
use_clustering_ = true;
}


private Q_SLOTS:
void
Expand Down
10 changes: 6 additions & 4 deletions apps/include/pcl/apps/render_views_tesselated_sphere.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,12 @@

#pragma once

#include <pcl/common/common.h>

#include <vtkSmartPointer.h>
#include <vtkPolyData.h>
#include <pcl/common/common.h>
#include <boost/function.hpp>

#include <functional>

namespace pcl
{
Expand All @@ -37,7 +39,7 @@ namespace pcl
bool compute_entropy_;
vtkSmartPointer<vtkPolyData> polydata_;
bool gen_organized_;
boost::function<bool
std::function<bool
(const Eigen::Vector3f &)> campos_constraints_func_;

struct camPosConstraintsAllTrue
Expand All @@ -64,7 +66,7 @@ namespace pcl
}

void
setCamPosConstraints (boost::function<bool (const Eigen::Vector3f &)> & bb)
setCamPosConstraints (std::function<bool (const Eigen::Vector3f &)> & bb)
{
campos_constraints_func_ = bb;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,17 @@

#pragma once

#include <QGLWidget>
#include <boost/function.hpp>
#include <pcl/apps/point_cloud_editor/localTypes.h>
#include <pcl/apps/point_cloud_editor/common.h>
#include <pcl/apps/point_cloud_editor/commandQueue.h>
#include <pcl/apps/point_cloud_editor/denoiseParameterForm.h>
#include <pcl/apps/point_cloud_editor/statisticsDialog.h>
#include <pcl/apps/point_cloud_editor/toolInterface.h>

#include <QGLWidget>

#include <functional>

/// @brief class declaration for the widget for editing and viewing
/// point clouds.
class CloudEditorWidget : public QGLWidget
Expand Down Expand Up @@ -251,7 +253,7 @@ class CloudEditorWidget : public QGLWidget
return lhs.compare(rhs) < 0;
}
};
typedef boost::function<void (CloudEditorWidget*, const std::string&)>
typedef std::function<void (CloudEditorWidget*, const std::string&)>
FileLoadFunc;
typedef std::map<std::string, FileLoadFunc, ExtCompare> FileLoadMap;
/// a map of file type extensions to loader functions.
Expand Down Expand Up @@ -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<void (CloudEditorWidget*)> KeyMapFunc;
typedef std::function<void (CloudEditorWidget*)> KeyMapFunc;
/// map between pressed key and the corresponding functor
std::map<int, KeyMapFunc> key_map_;

Expand Down
2 changes: 1 addition & 1 deletion apps/src/dinast_grabber_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ class DinastProcessor
run ()
{

boost::function<void (const CloudConstPtr&)> f =
std::function<void (const CloudConstPtr&)> f =
boost::bind (&DinastProcessor::cloud_cb_, this, _1);

boost::signals2::connection c = interface.registerCallback (f);
Expand Down
2 changes: 1 addition & 1 deletion apps/src/face_detection/openni_face_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<void(const pcl::visualization::KeyboardEvent&)> keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera,
std::function<void(const pcl::visualization::KeyboardEvent&)> keyboard_cb = boost::bind (&OpenNIFrameSource::OpenNIFrameSource::onKeyboardEvent, &camera,
_1);
vis.registerKeyboardCallback (keyboard_cb);

Expand Down
2 changes: 1 addition & 1 deletion apps/src/face_detection/openni_frame_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ namespace OpenNIFrameSource
OpenNIFrameSource::OpenNIFrameSource(const std::string& device_id) :
grabber_ (device_id), frame_counter_ (0), active_ (true)
{
boost::function<void(const PointCloudConstPtr&)> frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1);
std::function<void(const PointCloudConstPtr&)> frame_cb = boost::bind (&OpenNIFrameSource::onNewFrame, this, _1);
grabber_.registerCallback (frame_cb);
grabber_.start ();
}
Expand Down
2 changes: 1 addition & 1 deletion apps/src/ni_agast.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ class AGASTDemo
void
init ()
{
boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&AGASTDemo::cloud_callback, this, _1);
std::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&AGASTDemo::cloud_callback, this, _1);
cloud_connection = grabber_.registerCallback (cloud_cb);
}

Expand Down
2 changes: 1 addition & 1 deletion apps/src/ni_brisk.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ class BRISKDemo
void
init ()
{
boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&BRISKDemo::cloud_callback, this, _1);
std::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&BRISKDemo::cloud_callback, this, _1);
cloud_connection = grabber_.registerCallback (cloud_cb);
}

Expand Down
2 changes: 1 addition & 1 deletion apps/src/ni_linemod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<void (const CloudConstPtr&) > cloud_cb = boost::bind (&NILinemod::cloud_callback, this, _1);
std::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&NILinemod::cloud_callback, this, _1);
cloud_connection = grabber_.registerCallback (cloud_cb);

image_viewer_.registerMouseCallback (&NILinemod::mouse_callback, *this);
Expand Down
Loading

0 comments on commit f29e39a

Please sign in to comment.