Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updates for Ubuntu 22 #358

Open
wants to merge 3 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 0 additions & 9 deletions pcl_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,15 +1,6 @@
cmake_minimum_required(VERSION 3.0.2)
project(pcl_ros)

# CMake 3.1 added support for CMAKE_CXX_STANDARD to manage the C++ standard version
# Use CMake C++ standard management where possible for better interoperability
# with dependencies that export target standards and/or features
if (${CMAKE_VERSION} VERSION_LESS "3.1")
add_compile_options(-std=c++14)
else()
set(CMAKE_CXX_STANDARD 14)
endif()

## Find catkin packages
find_package(catkin REQUIRED COMPONENTS
dynamic_reconfigure
Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/include/pcl_ros/point_cloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

#include <ros/ros.h>
#include <pcl/point_cloud.h>
#include <pcl/point_traits.h>
#include <pcl/type_traits.h>
#include <pcl/for_each_type.h>
#include <pcl/conversions.h>
#include <pcl_conversions/pcl_conversions.h>
Expand Down
24 changes: 12 additions & 12 deletions pcl_ros/src/pcl_ros/features/feature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ pcl_ros::Feature::onInit ()

// Enable the dynamic reconfigure service
srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&Feature::config_callback, this, _1, _2);
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&Feature::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
Expand Down Expand Up @@ -124,7 +124,7 @@ pcl_ros::Feature::subscribe ()
}
else // Use only indices
{
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1));
// surface not enabled, connect the input-indices duo and register
if (approximate_sync_)
sync_input_surface_indices_a_->connectInput (sub_input_filter_, nf_pc_, sub_indices_filter_);
Expand All @@ -134,7 +134,7 @@ pcl_ros::Feature::subscribe ()
}
else // Use only surface
{
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&Feature::input_callback, this, boost::placeholders::_1));
// indices not enabled, connect the input-surface duo and register
sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);
if (approximate_sync_)
Expand All @@ -144,13 +144,13 @@ pcl_ros::Feature::subscribe ()
}
// Register callbacks
if (approximate_sync_)
sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
sync_input_surface_indices_a_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
else
sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, _1, _2, _3));
sync_input_surface_indices_e_->registerCallback (bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}
else
// Subscribe in an old fashion to input only (no filters)
sub_input_ = pnh_->subscribe<PointCloudIn> ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, _1, PointCloudInConstPtr (), PointIndicesConstPtr ()));
sub_input_ = pnh_->subscribe<PointCloudIn> ("input", max_queue_size_, bind (&Feature::input_surface_indices_callback, this, boost::placeholders::_1, PointCloudInConstPtr (), PointIndicesConstPtr ()));
}

////////////////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -300,7 +300,7 @@ pcl_ros::FeatureFromNormals::onInit ()

// Enable the dynamic reconfigure service
srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, _1, _2);
dynamic_reconfigure::Server<FeatureConfig>::CallbackType f = boost::bind (&FeatureFromNormals::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
Expand Down Expand Up @@ -345,7 +345,7 @@ pcl_ros::FeatureFromNormals::subscribe ()
}
else // Use only indices
{
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));
if (approximate_sync_)
// surface not enabled, connect the input-indices duo and register
sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, sub_indices_filter_);
Expand All @@ -359,7 +359,7 @@ pcl_ros::FeatureFromNormals::subscribe ()
// indices not enabled, connect the input-surface duo and register
sub_surface_filter_.subscribe (*pnh_, "surface", max_queue_size_);

sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));
if (approximate_sync_)
sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_surface_filter_, nf_pi_);
else
Expand All @@ -368,7 +368,7 @@ pcl_ros::FeatureFromNormals::subscribe ()
}
else
{
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&FeatureFromNormals::input_callback, this, boost::placeholders::_1));

if (approximate_sync_)
sync_input_normals_surface_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_pc_, nf_pi_);
Expand All @@ -378,9 +378,9 @@ pcl_ros::FeatureFromNormals::subscribe ()

// Register callbacks
if (approximate_sync_)
sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
sync_input_normals_surface_indices_a_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
else
sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, _1, _2, _3, _4));
sync_input_normals_surface_indices_e_->registerCallback (bind (&FeatureFromNormals::input_normals_surface_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/src/pcl_ros/filters/crop_box.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
// Enable the dynamic reconfigure service
has_service = true;
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::CropBoxConfig>::CallbackType f = boost::bind (&CropBox::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

return (true);
Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/src/pcl_ros/filters/extract_indices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pcl_ros::ExtractIndices::child_init (ros::NodeHandle &nh, bool &has_service)
has_service = true;

srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig>::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::ExtractIndicesConfig>::CallbackType f = boost::bind (&ExtractIndices::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

use_indices_ = true;
Expand Down
8 changes: 4 additions & 4 deletions pcl_ros/src/pcl_ros/filters/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,18 +116,18 @@ pcl_ros::Filter::subscribe()
{
sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
}
else
{
sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
}
}
else
// Subscribe in an old fashion to input only (no filters)
sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, _1, pcl_msgs::PointIndicesConstPtr ()));
sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_, bind (&Filter::input_indices_callback, this, boost::placeholders::_1, pcl_msgs::PointIndicesConstPtr ()));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down Expand Up @@ -164,7 +164,7 @@ pcl_ros::Filter::onInit ()
if (!has_service)
{
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (*pnh_);
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&Filter::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&Filter::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);
}

Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/src/pcl_ros/filters/passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service)
// Enable the dynamic reconfigure service
has_service = true;
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

return (true);
Expand Down
4 changes: 2 additions & 2 deletions pcl_ros/src/pcl_ros/filters/project_inliers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,13 +99,13 @@ pcl_ros::ProjectInliers::subscribe ()
{
sync_input_indices_model_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
sync_input_indices_model_a_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}
else
{
sync_input_indices_model_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
sync_input_indices_model_e_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}
}

Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pcl_ros::RadiusOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_servic
// Enable the dynamic reconfigure service
has_service = true;
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig>::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig>::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

return (true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pcl_ros::StatisticalOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_s
// Enable the dynamic reconfigure service
has_service = true;
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig>::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig>::CallbackType f = boost::bind (&StatisticalOutlierRemoval::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

return (true);
Expand Down
2 changes: 1 addition & 1 deletion pcl_ros/src/pcl_ros/filters/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ pcl_ros::VoxelGrid::child_init (ros::NodeHandle &nh, bool &has_service)
// Enable the dynamic reconfigure service
has_service = true;
srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig> > (nh);
dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig>::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, _1, _2);
dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig>::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

return (true);
Expand Down
6 changes: 3 additions & 3 deletions pcl_ros/src/pcl_ros/io/concatenate_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe ()
}

// Bogus null filter
filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, _1));
filters_[0]->registerCallback (bind (&PointCloudConcatenateDataSynchronizer::input_callback, this, boost::placeholders::_1));

switch (input_topics_.size ())
{
Expand Down Expand Up @@ -186,9 +186,9 @@ pcl_ros::PointCloudConcatenateDataSynchronizer::subscribe ()
}

if (approximate_sync_)
ts_a_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8));
ts_a_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8));
else
ts_e_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, _1, _2, _3, _4, _5, _6, _7, _8));
ts_e_->registerCallback (boost::bind (&PointCloudConcatenateDataSynchronizer::input, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
8 changes: 4 additions & 4 deletions pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ pcl_ros::EuclideanClusterExtraction::onInit ()

// Enable the dynamic reconfigure service
srv_ = boost::make_shared <dynamic_reconfigure::Server<EuclideanClusterExtractionConfig> > (*pnh_);
dynamic_reconfigure::Server<EuclideanClusterExtractionConfig>::CallbackType f = boost::bind (&EuclideanClusterExtraction::config_callback, this, _1, _2);
dynamic_reconfigure::Server<EuclideanClusterExtractionConfig>::CallbackType f = boost::bind (&EuclideanClusterExtraction::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
Expand Down Expand Up @@ -108,18 +108,18 @@ pcl_ros::EuclideanClusterExtraction::subscribe ()
{
sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloud, PointIndices> > > (max_queue_size_);
sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
sync_input_indices_a_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, _2));
sync_input_indices_a_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
}
else
{
sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloud, PointIndices> > > (max_queue_size_);
sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
sync_input_indices_e_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, _2));
sync_input_indices_e_->registerCallback (bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2));
}
}
else
// Subscribe in an old fashion to input only (no filters)
sub_input_ = pnh_->subscribe<PointCloud> ("input", max_queue_size_, bind (&EuclideanClusterExtraction::input_indices_callback, this, _1, PointIndicesConstPtr ()));
sub_input_ = pnh_->subscribe<PointCloud> ("input", max_queue_size_, bind (&EuclideanClusterExtraction::input_indices_callback, this, boost::placeholders::_1, PointIndicesConstPtr ()));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ pcl_ros::ExtractPolygonalPrismData::onInit ()

// Enable the dynamic reconfigure service
srv_ = boost::make_shared <dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > (*pnh_);
dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, _1, _2);
dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, boost::placeholders::_1, boost::placeholders::_2);
srv_->setCallback (f);

// Advertise the output topics
Expand Down Expand Up @@ -85,7 +85,7 @@ pcl_ros::ExtractPolygonalPrismData::subscribe ()
}
else
{
sub_input_filter_.registerCallback (bind (&ExtractPolygonalPrismData::input_callback, this, _1));
sub_input_filter_.registerCallback (bind (&ExtractPolygonalPrismData::input_callback, this, boost::placeholders::_1));

if (approximate_sync_)
sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
Expand All @@ -94,9 +94,9 @@ pcl_ros::ExtractPolygonalPrismData::subscribe ()
}
// Register callbacks
if (approximate_sync_)
sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
else
sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3));
}

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
Loading