diff --git a/pcl_ros/CMakeLists.txt b/pcl_ros/CMakeLists.txt
index a9275ac8..bdeebd84 100644
--- a/pcl_ros/CMakeLists.txt
+++ b/pcl_ros/CMakeLists.txt
@@ -33,13 +33,6 @@ include_directories(include
${PCL_INCLUDE_DIRS}
)
-## Add link directories
-link_directories(
- ${Boost_LIBRARY_DIRS}
- ${Eigen_LIBRARY_DIRS}
- ${PCL_LIBRARY_DIRS}
-)
-
## Generate dynamic_reconfigure
generate_dynamic_reconfigure_options(
cfg/EuclideanClusterExtraction.cfg
@@ -83,7 +76,7 @@ catkin_package(
## Declare the pcl_ros_tf library
add_library(pcl_ros_tf src/transforms.cpp)
-target_link_libraries(pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_tf pcl_ros_generate_messages_cpp ${catkin_EXPORTED_TARGETS})
## Nodelets
@@ -96,7 +89,7 @@ add_library(pcl_ros_io
src/pcl_ros/io/io.cpp
src/pcl_ros/io/pcd_io.cpp
)
-target_link_libraries(pcl_ros_io pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcl_ros_io pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
class_loader_hide_library_symbols(pcl_ros_io)
## Declare the pcl_ros_features library
@@ -115,7 +108,7 @@ add_library(pcl_ros_features
src/pcl_ros/features/principal_curvatures.cpp
src/pcl_ros/features/vfh.cpp
)
-target_link_libraries (pcl_ros_features ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries (pcl_ros_features ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_features ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_features)
@@ -131,7 +124,7 @@ add_library(pcl_ros_filters
src/pcl_ros/filters/voxel_grid.cpp
src/pcl_ros/filters/crop_box.cpp
)
-target_link_libraries(pcl_ros_filters pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcl_ros_filters pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_filters ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_filters)
@@ -143,7 +136,7 @@ add_library (pcl_ros_segmentation
src/pcl_ros/segmentation/segment_differences.cpp
src/pcl_ros/segmentation/segmentation.cpp
)
-target_link_libraries(pcl_ros_segmentation pcl_segmentation pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcl_ros_segmentation pcl_segmentation pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_segmentation ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_segmentation)
@@ -154,26 +147,26 @@ add_library (pcl_ros_surface
src/pcl_ros/surface/convex_hull.cpp
src/pcl_ros/surface/moving_least_squares.cpp
)
-target_link_libraries(pcl_ros_surface ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcl_ros_surface ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_surface ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_surface)
## Tools
add_executable(pcd_to_pointcloud tools/pcd_to_pointcloud.cpp)
-target_link_libraries(pcd_to_pointcloud pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pcd_to_pointcloud pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_executable(pointcloud_to_pcd tools/pointcloud_to_pcd.cpp)
-target_link_libraries(pointcloud_to_pcd pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(pointcloud_to_pcd pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARY_DIRS} ${PCL_LIBRARIES})
add_executable(bag_to_pcd tools/bag_to_pcd.cpp)
-target_link_libraries(bag_to_pcd pcl_io pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(bag_to_pcd pcl_io pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARY_DIRS} ${PCL_LIBRARIES})
add_executable(convert_pcd_to_image tools/convert_pcd_to_image.cpp)
-target_link_libraries(convert_pcd_to_image pcl_io pcl_common ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(convert_pcd_to_image pcl_io pcl_common ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
add_executable(convert_pointcloud_to_image tools/convert_pointcloud_to_image.cpp)
-target_link_libraries(convert_pointcloud_to_image pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
+target_link_libraries(convert_pointcloud_to_image pcl_io ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${Eigen_LIBRARIES} ${PCL_LIBRARIES})
install(DIRECTORY include/${PROJECT_NAME}/
diff --git a/pcl_ros/package.xml b/pcl_ros/package.xml
index 165a6190..77602acf 100644
--- a/pcl_ros/package.xml
+++ b/pcl_ros/package.xml
@@ -20,8 +20,11 @@
https://github.com/ros-perception/perception_pcl
catkin
-
cmake_modules
+ rosconsole
+ genmsg
+ roslib
+
dynamic_reconfigure
eigen
nodelet
diff --git a/pcl_ros/pcl_nodelets.xml b/pcl_ros/pcl_nodelets.xml
index 71978735..215ef9a9 100644
--- a/pcl_ros/pcl_nodelets.xml
+++ b/pcl_ros/pcl_nodelets.xml
@@ -47,6 +47,41 @@
in parallel, using the OpenMP standard.
+
+
+
+ NormalEstimationTBB estimates local surface properties at each 3D point, such as surface normals and curvatures, in
+ parallel, using Intel's Threading Building Blocks library.
+
+
+
+
+
+ NormalEstimation estimates local surface properties at each 3D point, such as surface normals and curvatures.
+
+
+
+
+
+ PFHEstimation estimates the Point Feature Histogram (PFH) descriptor for a given point cloud dataset containing
+ points and normals.
+
+
+
+
+
+ PrincipalCurvaturesEstimation estimates the directions (eigenvectors) and magnitudes (eigenvalues) of principal surface
+ curvatures for a given point cloud dataset containing points and normals.
+
+
+
+
+
+ VFHEstimation estimates the Viewpoint Feature Histogram (VFH) global descriptor for a given point cloud cluster dataset
+ containing points and normals.
+
+
+
@@ -143,5 +178,55 @@
+
+
+
+
+ ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given
+ height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it.
+
+
+
+
+ EuclideanClusterExtraction represents a segmentation class for cluster extraction in an Euclidean sense.
+
+
+
+
+
+ SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that
+ it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation.
+
+
+
+
+
+ SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that
+ it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation.
+
+
+
+
+
+ SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the
+ difference between them for a maximum given distance threshold.
+
+
+
+
+
+
+
+
+
+ MovingLeastSquares is an implementation of the MLS algorithm for data reconstruction through bivariate polynomial fitting.
+
+
+
+
+ ConvexHull2D represents a 2D ConvexHull implementation.
+
+
+