Skip to content
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
3 changes: 3 additions & 0 deletions pcl_conversions/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@

<buildtool_depend>catkin</buildtool_depend>

<build_depend>libpcl-all-dev</build_depend>
<build_depend>eigen</build_depend>

<build_export_depend>eigen</build_export_depend>
<build_export_depend>libpcl-all-dev</build_export_depend>
<build_export_depend>pcl_msgs</build_export_depend>
Expand Down
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: 2 additions & 0 deletions pcl_ros/src/pcl_ros/features/feature.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,8 @@
//#include "vfh.cpp"
#include "pcl_ros/features/feature.h"

using namespace boost::placeholders;

////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::Feature::onInit ()
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/crop_box.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/crop_box.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::CropBox::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/extract_indices.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/extract_indices.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::ExtractIndices::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@
//#include <pcl/filters/filter_dimension.h>
*/

using namespace boost::placeholders;

/*//typedef pcl::PixelGrid PixelGrid;
//typedef pcl::FilterDimension FilterDimension;
*/
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/passthrough.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/passthrough.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/project_inliers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/project_inliers.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ProjectInliers::onInit ()
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/radius_outlier_removal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/radius_outlier_removal.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::RadiusOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/statistical_outlier_removal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/statistical_outlier_removal.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::StatisticalOutlierRemoval::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/filters/voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/filters/voxel_grid.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
bool
pcl_ros::VoxelGrid::child_init (ros::NodeHandle &nh, bool &has_service)
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/io/concatenate_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@

#include <pcl_conversions/pcl_conversions.h>

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::PointCloudConcatenateDataSynchronizer::onInit ()
Expand Down
1 change: 1 addition & 0 deletions pcl_ros/src/pcl_ros/segmentation/extract_clusters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <pcl_conversions/pcl_conversions.h>

using namespace boost::placeholders;
using pcl_conversions::fromPCL;
using pcl_conversions::moveFromPCL;
using pcl_conversions::toPCL;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@

#include <pcl_conversions/pcl_conversions.h>

using namespace boost::placeholders;
using pcl_conversions::moveFromPCL;
using pcl_conversions::moveToPCL;

Expand Down
1 change: 1 addition & 0 deletions pcl_ros/src/pcl_ros/segmentation/sac_segmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <pcl_conversions/pcl_conversions.h>

using namespace boost::placeholders;
using pcl_conversions::fromPCL;

//////////////////////////////////////////////////////////////////////////////////////////////
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/segmentation/segment_differences.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/segmentation/segment_differences.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::SegmentDifferences::onInit ()
Expand Down
2 changes: 2 additions & 0 deletions pcl_ros/src/pcl_ros/surface/convex_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@
#include "pcl_ros/surface/convex_hull.h"
#include <geometry_msgs/PolygonStamped.h>

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ConvexHull2D::onInit ()
Expand Down
3 changes: 3 additions & 0 deletions pcl_ros/src/pcl_ros/surface/moving_least_squares.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,9 @@

#include <pluginlib/class_list_macros.hpp>
#include "pcl_ros/surface/moving_least_squares.h"

using namespace boost::placeholders;

//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::MovingLeastSquares::onInit ()
Expand Down
3 changes: 2 additions & 1 deletion pcl_ros/src/test/test_tf_message_filter_pcl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include <tf/message_filter.h>
#include <tf/transform_listener.h>

#include <boost/bind.hpp>
#include <boost/bind/bind.hpp>
#include <boost/scoped_ptr.hpp>

#include <pcl_ros/point_cloud.h>
Expand All @@ -47,6 +47,7 @@

#include <gtest/gtest.h>

using namespace boost::placeholders;
using namespace tf;

// using a random point type, as we want to make sure that it does work with
Expand Down