Skip to content

Commit

Permalink
[filters/keypoints/octree/people/seg/surf] Migrate boost::function to…
Browse files Browse the repository at this point in the history
… std::function
  • Loading branch information
SergioRAgostinho committed Jun 5, 2019
1 parent 74eab34 commit ea0e78e
Show file tree
Hide file tree
Showing 10 changed files with 17 additions and 21 deletions.
1 change: 0 additions & 1 deletion filters/include/pcl/filters/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,5 +53,4 @@
#include <boost/mpl/size.hpp>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include <boost/bind.hpp>
#include <boost/function.hpp>
#include <boost/optional.hpp>
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/model_outlier_removal.h
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ namespace pcl
* \param[in] thresh pointer to a threshold function
*/
void
setThresholdFunction (boost::function<bool (double)> thresh)
setThresholdFunction (std::function<bool (double)> thresh)
{
threshold_function_ = thresh;
}
Expand Down Expand Up @@ -235,7 +235,7 @@ namespace pcl

/** \brief The type of model to use (user given parameter). */
pcl::SacModel model_type_;
boost::function<bool (double)> threshold_function_;
std::function<bool (double)> threshold_function_;

inline bool
checkSingleThreshold (double value)
Expand Down
6 changes: 3 additions & 3 deletions keypoints/include/pcl/keypoints/keypoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@

// PCL includes
#include <pcl/pcl_base.h>
#include <boost/function.hpp>
#include <boost/bind.hpp>
#include <pcl/search/pcl_search.h>
#include <pcl/pcl_config.h>
#include <functional>

namespace pcl
{
Expand All @@ -67,8 +67,8 @@ namespace pcl
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
typedef pcl::PointCloud<PointOutT> PointCloudOut;
typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
typedef boost::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
typedef std::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
typedef std::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;

public:
/** \brief Empty constructor. */
Expand Down
1 change: 0 additions & 1 deletion octree/include/pcl/octree/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,3 @@

// Marking all Boost headers as system headers to remove warnings
#include <boost/graph/adjacency_list.hpp>
#include <boost/function.hpp>
4 changes: 2 additions & 2 deletions octree/include/pcl/octree/octree_pointcloud_adjacency.h
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,7 @@ namespace pcl
* \param[in] transform_func A boost:function pointer to the transform to be used. The transform must have one
* parameter (a point) which it modifies in place. */
void
setTransformFunction (boost::function<void (PointT &p)> transform_func)
setTransformFunction (std::function<void (PointT &p)> transform_func)
{
transform_func_ = transform_func;
}
Expand Down Expand Up @@ -216,7 +216,7 @@ namespace pcl
/// Local leaf pointer vector used to make iterating through leaves fast.
LeafVectorT leaf_vector_;

boost::function<void (PointT &p)> transform_func_;
std::function<void (PointT &p)> transform_func_;

};

Expand Down
2 changes: 1 addition & 1 deletion people/apps/main_ground_based_people_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,7 +143,7 @@ int main (int argc, char** argv)
PointCloudT::Ptr cloud (new PointCloudT);
bool new_cloud_available_flag = false;
pcl::Grabber* interface = new pcl::OpenNIGrabber();
boost::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)> f =
boost::bind (&cloud_cb_, _1, cloud, &new_cloud_available_flag);
interface->registerCallback (f);
interface->start ();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@

#pragma once

#include <boost/function.hpp>

#include <pcl/pcl_base.h>
#include <pcl/search/pcl_search.h>

#include <functional>

namespace pcl
{
typedef std::vector<pcl::PointIndices> IndicesClusters;
Expand Down Expand Up @@ -148,7 +148,7 @@ namespace pcl
/** \brief Set the condition that needs to hold for neighboring points to be considered part of the same cluster.
* This is an overloaded function provided for convenience. See the documentation for setConditionFunction(). */
inline void
setConditionFunction (boost::function<bool (const PointT&, const PointT&, float)> condition_function)
setConditionFunction (std::function<bool (const PointT&, const PointT&, float)> condition_function)
{
condition_function_ = condition_function;
}
Expand Down Expand Up @@ -237,7 +237,7 @@ namespace pcl
SearcherPtr searcher_;

/** \brief The condition function that needs to hold for clustering */
boost::function<bool (const PointT&, const PointT&, float)> condition_function_;
std::function<bool (const PointT&, const PointT&, float)> condition_function_;

/** \brief The distance to scan for cluster candidates (default = 0.0) */
float cluster_tolerance_;
Expand Down
1 change: 0 additions & 1 deletion surface/include/pcl/surface/boost.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,5 @@
#endif

#include <boost/bind.hpp>
#include <boost/function.hpp>
#include <boost/dynamic_bitset/dynamic_bitset.hpp>
#include <boost/shared_ptr.hpp>
4 changes: 2 additions & 2 deletions surface/include/pcl/surface/impl/mls.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -719,7 +719,7 @@ pcl::MLSResult::computeMLSSurface (const pcl::PointCloud<PointT> &cloud,
const std::vector<int> &nn_indices,
double search_radius,
int polynomial_order,
boost::function<double(const double)> weight_func)
std::function<double(const double)> weight_func)
{
// Compute the plane coefficients
EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix;
Expand Down Expand Up @@ -777,7 +777,7 @@ pcl::MLSResult::computeMLSSurface (const pcl::PointCloud<PointT> &cloud,
{
// Note: The max_sq_radius parameter is only used if weight_func was not defined
double max_sq_radius = 1;
if (weight_func.empty())
if (!weight_func)
{
max_sq_radius = search_radius * search_radius;
weight_func = boost::bind (&pcl::MLSResult::computeMLSWeight, this, _1, max_sq_radius);
Expand Down
7 changes: 3 additions & 4 deletions surface/include/pcl/surface/mls.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,10 @@

#pragma once

#include <functional>
#include <map>
#include <random>

#include <boost/function.hpp>

// PCL includes
#include <pcl/pcl_base.h>
#include <pcl/search/pcl_search.h>
Expand Down Expand Up @@ -210,7 +209,7 @@ namespace pcl
const std::vector<int> &nn_indices,
double search_radius,
int polynomial_order = 2,
boost::function<double(const double)> weight_func = {});
std::function<double(const double)> weight_func = {});

Eigen::Vector3d query_point; /**< \brief The query point about which the mls surface was generated */
Eigen::Vector3d mean; /**< \brief The mean point of all the neighbors. */
Expand Down Expand Up @@ -274,7 +273,7 @@ namespace pcl
typedef typename PointCloudIn::Ptr PointCloudInPtr;
typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;

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

enum UpsamplingMethod
{
Expand Down

0 comments on commit ea0e78e

Please sign in to comment.