diff --git a/pcl_conversions/package.xml b/pcl_conversions/package.xml
index 59e31f1de..0bfd4c928 100644
--- a/pcl_conversions/package.xml
+++ b/pcl_conversions/package.xml
@@ -18,6 +18,9 @@
catkin
+ libpcl-all-dev
+ eigen
+
eigen
libpcl-all-dev
pcl_msgs
diff --git a/pcl_ros/CMakeLists.txt b/pcl_ros/CMakeLists.txt
index 2466227dd..6230e32ef 100644
--- a/pcl_ros/CMakeLists.txt
+++ b/pcl_ros/CMakeLists.txt
@@ -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
diff --git a/pcl_ros/src/pcl_ros/features/feature.cpp b/pcl_ros/src/pcl_ros/features/feature.cpp
index cee3dbc28..89e94c0a9 100644
--- a/pcl_ros/src/pcl_ros/features/feature.cpp
+++ b/pcl_ros/src/pcl_ros/features/feature.cpp
@@ -49,6 +49,8 @@
//#include "vfh.cpp"
#include "pcl_ros/features/feature.h"
+using namespace boost::placeholders;
+
////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::Feature::onInit ()
diff --git a/pcl_ros/src/pcl_ros/filters/crop_box.cpp b/pcl_ros/src/pcl_ros/filters/crop_box.cpp
index af173dcc4..c76c0793a 100644
--- a/pcl_ros/src/pcl_ros/filters/crop_box.cpp
+++ b/pcl_ros/src/pcl_ros/filters/crop_box.cpp
@@ -39,6 +39,8 @@
#include
#include "pcl_ros/filters/crop_box.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp
index 89b1608ce..5f4e30267 100644
--- a/pcl_ros/src/pcl_ros/filters/extract_indices.cpp
+++ b/pcl_ros/src/pcl_ros/filters/extract_indices.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/extract_indices.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::ExtractIndices::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/filters/filter.cpp b/pcl_ros/src/pcl_ros/filters/filter.cpp
index 0bfe6d3de..25129bd39 100644
--- a/pcl_ros/src/pcl_ros/filters/filter.cpp
+++ b/pcl_ros/src/pcl_ros/filters/filter.cpp
@@ -42,6 +42,8 @@
//#include
*/
+using namespace boost::placeholders;
+
/*//typedef pcl::PixelGrid PixelGrid;
//typedef pcl::FilterDimension FilterDimension;
*/
diff --git a/pcl_ros/src/pcl_ros/filters/passthrough.cpp b/pcl_ros/src/pcl_ros/filters/passthrough.cpp
index f85f536b8..9284e2631 100644
--- a/pcl_ros/src/pcl_ros/filters/passthrough.cpp
+++ b/pcl_ros/src/pcl_ros/filters/passthrough.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/passthrough.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp
index 6781d26b6..f4324322b 100644
--- a/pcl_ros/src/pcl_ros/filters/project_inliers.cpp
+++ b/pcl_ros/src/pcl_ros/filters/project_inliers.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/project_inliers.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ProjectInliers::onInit ()
diff --git a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp
index 4b242db63..46b294f84 100644
--- a/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp
+++ b/pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/radius_outlier_removal.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::RadiusOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp
index fa69a756d..b83066394 100644
--- a/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp
+++ b/pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/statistical_outlier_removal.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::StatisticalOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp
index 389df9718..6ab472d33 100644
--- a/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp
+++ b/pcl_ros/src/pcl_ros/filters/voxel_grid.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/filters/voxel_grid.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::VoxelGrid::child_init (ros::NodeHandle &nh, bool &has_service)
diff --git a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp
index b0425ff03..e6bac452c 100644
--- a/pcl_ros/src/pcl_ros/io/concatenate_data.cpp
+++ b/pcl_ros/src/pcl_ros/io/concatenate_data.cpp
@@ -41,6 +41,8 @@
#include
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::PointCloudConcatenateDataSynchronizer::onInit ()
diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp
index 2d41b6821..580fcb2b4 100644
--- a/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp
+++ b/pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp
@@ -41,6 +41,7 @@
#include
+using namespace boost::placeholders;
using pcl_conversions::fromPCL;
using pcl_conversions::moveFromPCL;
using pcl_conversions::toPCL;
diff --git a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
index af445cfd3..6e8cf2e2f 100644
--- a/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
+++ b/pcl_ros/src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
@@ -41,6 +41,7 @@
#include
+using namespace boost::placeholders;
using pcl_conversions::moveFromPCL;
using pcl_conversions::moveToPCL;
diff --git a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp
index 06b136152..7d04a84bc 100644
--- a/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp
+++ b/pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp
@@ -40,6 +40,7 @@
#include
+using namespace boost::placeholders;
using pcl_conversions::fromPCL;
//////////////////////////////////////////////////////////////////////////////////////////////
diff --git a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp
index bde054bb5..ea127f680 100644
--- a/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp
+++ b/pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp
@@ -38,6 +38,8 @@
#include
#include "pcl_ros/segmentation/segment_differences.h"
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::SegmentDifferences::onInit ()
diff --git a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp
index 6719aceeb..0777b5533 100644
--- a/pcl_ros/src/pcl_ros/surface/convex_hull.cpp
+++ b/pcl_ros/src/pcl_ros/surface/convex_hull.cpp
@@ -39,6 +39,8 @@
#include "pcl_ros/surface/convex_hull.h"
#include
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ConvexHull2D::onInit ()
diff --git a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp
index 46c6a39dd..69d0ec016 100644
--- a/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp
+++ b/pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp
@@ -37,6 +37,9 @@
#include
#include "pcl_ros/surface/moving_least_squares.h"
+
+using namespace boost::placeholders;
+
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::MovingLeastSquares::onInit ()
diff --git a/pcl_ros/src/test/test_tf_message_filter_pcl.cpp b/pcl_ros/src/test/test_tf_message_filter_pcl.cpp
index 073e358c8..e447fc69d 100644
--- a/pcl_ros/src/test/test_tf_message_filter_pcl.cpp
+++ b/pcl_ros/src/test/test_tf_message_filter_pcl.cpp
@@ -37,7 +37,7 @@
#include
#include
-#include
+#include
#include
#include
@@ -47,6 +47,7 @@
#include
+using namespace boost::placeholders;
using namespace tf;
// using a random point type, as we want to make sure that it does work with