2012-09-13 13:26:12 +00:00
|
|
|
cmake_minimum_required(VERSION 2.8)
|
2012-09-14 18:17:12 +00:00
|
|
|
project(pcl_ros)
|
2012-09-13 13:26:12 +00:00
|
|
|
|
|
|
|
|
# Deal with catkin
|
2012-09-14 14:30:42 +00:00
|
|
|
find_package(Boost COMPONENTS system filesystem thread REQUIRED)
|
2013-01-01 14:52:37 +01:00
|
|
|
find_package(catkin REQUIRED dynamic_reconfigure genmsg nodelet nodelet_topic_tools roscpp sensor_msgs std_msgs tf rosbag rosconsole roslib pluginlib)
|
2012-09-14 14:30:42 +00:00
|
|
|
find_package(Eigen)
|
2012-10-04 16:58:35 +02:00
|
|
|
find_package(PCL)
|
2012-09-13 13:26:12 +00:00
|
|
|
|
|
|
|
|
# deal with ROS
|
2012-10-23 19:45:04 -07:00
|
|
|
include_directories(SYSTEM ${Boost_INCLUDE_DIRS}
|
|
|
|
|
${catkin_INCLUDE_DIRS}
|
|
|
|
|
${Eigen_INCLUDE_DIRS}
|
|
|
|
|
${PCL_INCLUDE_DIRS}
|
|
|
|
|
)
|
2012-09-14 14:30:42 +00:00
|
|
|
include_directories(include)
|
|
|
|
|
|
|
|
|
|
link_directories(${catkin_LIBRARY_DIRS} ${Boost_LIBRARY_DIRS} ${Eigen_LIBRARY_DIRS} ${PCL_LIBRARY_DIRS})
|
2012-09-13 13:26:12 +00:00
|
|
|
|
2012-12-17 18:09:15 -08:00
|
|
|
# generate the dynamic_reconfigure config file
|
2013-05-11 03:29:09 +09:00
|
|
|
generate_dynamic_reconfigure_options(cfg/Feature.cfg
|
|
|
|
|
cfg/Filter.cfg
|
|
|
|
|
cfg/EuclideanClusterExtraction.cfg
|
2012-12-17 18:09:15 -08:00
|
|
|
cfg/ExtractIndices.cfg
|
2013-05-11 03:29:09 +09:00
|
|
|
cfg/ExtractPolygonalPrismData.cfg
|
|
|
|
|
cfg/MLS.cfg
|
|
|
|
|
cfg/SACSegmentation.cfg
|
|
|
|
|
cfg/SACSegmentationFromNormals.cfg
|
|
|
|
|
cfg/SegmentDifferences.cfg
|
2012-12-17 18:09:15 -08:00
|
|
|
cfg/StatisticalOutlierRemoval.cfg
|
|
|
|
|
cfg/VoxelGrid.cfg
|
|
|
|
|
|
2012-09-13 13:26:12 +00:00
|
|
|
)
|
2012-12-17 18:09:15 -08:00
|
|
|
include_directories(include cfg/cpp)
|
2012-09-13 13:26:12 +00:00
|
|
|
|
2012-12-18 17:40:49 -08:00
|
|
|
catkin_package(
|
|
|
|
|
INCLUDE_DIRS include
|
|
|
|
|
LIBRARIES pcl_ros_tf pcl_ros_io pcl_ros_filters
|
2013-01-17 15:49:30 -08:00
|
|
|
CATKIN_DEPENDS roscpp sensor_msgs tf sensor_msgs std_msgs
|
|
|
|
|
DEPENDS Eigen PCL
|
2012-12-18 17:40:49 -08:00
|
|
|
)
|
2012-10-23 19:45:04 -07:00
|
|
|
|
2012-09-13 13:26:12 +00:00
|
|
|
# ---[ Point Cloud Library - Transforms
|
2012-09-13 13:40:21 +00:00
|
|
|
add_library (pcl_ros_tf SHARED src/transforms.cpp)
|
2012-12-17 18:09:15 -08:00
|
|
|
target_link_libraries(pcl_ros_tf ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
2012-10-23 19:45:04 -07:00
|
|
|
add_dependencies(pcl_ros_tf ros_gencpp pcl_ros_copy)
|
2012-09-13 13:40:21 +00:00
|
|
|
|
2012-12-17 18:09:15 -08:00
|
|
|
############ NODELETS
|
|
|
|
|
|
|
|
|
|
# ---[ Point Cloud Library - IO
|
|
|
|
|
add_library (pcl_ros_io
|
|
|
|
|
src/pcl_ros/io/io.cpp
|
|
|
|
|
src/pcl_ros/io/concatenate_fields.cpp
|
|
|
|
|
src/pcl_ros/io/concatenate_data.cpp
|
|
|
|
|
src/pcl_ros/io/pcd_io.cpp
|
|
|
|
|
src/pcl_ros/io/bag_io.cpp
|
|
|
|
|
)
|
|
|
|
|
#rosbuild_add_compile_flags (pcl_ros_io ${SSE_FLAGS})
|
|
|
|
|
target_link_libraries (pcl_ros_io pcl_ros_tf ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
2012-12-17 21:17:31 -08:00
|
|
|
class_loader_hide_library_symbols(pcl_ros_io)
|
|
|
|
|
|
2013-05-11 03:29:09 +09:00
|
|
|
# ---[ PCL ROS - Features
|
|
|
|
|
add_library (pcl_ros_features
|
|
|
|
|
src/pcl_ros/features/feature.cpp
|
|
|
|
|
# Compilation is much faster if we include all the following CPP files in feature.cpp
|
2013-05-15 12:57:28 +09:00
|
|
|
src/pcl_ros/features/boundary.cpp
|
|
|
|
|
src/pcl_ros/features/fpfh.cpp
|
|
|
|
|
src/pcl_ros/features/fpfh_omp.cpp
|
|
|
|
|
src/pcl_ros/features/moment_invariants.cpp
|
|
|
|
|
src/pcl_ros/features/normal_3d.cpp
|
|
|
|
|
src/pcl_ros/features/normal_3d_omp.cpp
|
|
|
|
|
src/pcl_ros/features/pfh.cpp
|
|
|
|
|
src/pcl_ros/features/principal_curvatures.cpp
|
|
|
|
|
src/pcl_ros/features/vfh.cpp
|
2013-05-11 03:29:09 +09:00
|
|
|
)
|
|
|
|
|
#rosbuild_add_compile_flags (pcl_ros_features ${SSE_FLAGS})
|
|
|
|
|
target_link_libraries (pcl_ros_features ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
class_loader_hide_library_symbols(pcl_ros_features)
|
|
|
|
|
|
|
|
|
|
|
2012-12-17 18:09:15 -08:00
|
|
|
# ---[ PCL ROS - Filters
|
|
|
|
|
add_library (pcl_ros_filters
|
|
|
|
|
src/pcl_ros/filters/filter.cpp
|
|
|
|
|
src/pcl_ros/filters/passthrough.cpp
|
|
|
|
|
src/pcl_ros/filters/project_inliers.cpp
|
|
|
|
|
src/pcl_ros/filters/extract_indices.cpp
|
|
|
|
|
src/pcl_ros/filters/radius_outlier_removal.cpp
|
|
|
|
|
src/pcl_ros/filters/statistical_outlier_removal.cpp
|
|
|
|
|
src/pcl_ros/filters/voxel_grid.cpp
|
|
|
|
|
)
|
|
|
|
|
#add_compile_flags (pcl_ros_filters ${SSE_FLAGS})
|
|
|
|
|
target_link_libraries (pcl_ros_filters pcl_ros_tf ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
2012-12-17 21:17:31 -08:00
|
|
|
class_loader_hide_library_symbols(pcl_ros_filters)
|
|
|
|
|
|
2013-05-11 03:29:09 +09:00
|
|
|
# ---[ Point Cloud Library - Segmentation
|
|
|
|
|
add_library (pcl_ros_segmentation
|
|
|
|
|
src/pcl_ros/segmentation/segmentation.cpp
|
|
|
|
|
src/pcl_ros/segmentation/segment_differences.cpp
|
2013-05-15 12:57:28 +09:00
|
|
|
src/pcl_ros/segmentation/extract_clusters.cpp
|
2013-05-11 03:29:09 +09:00
|
|
|
src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
|
|
|
|
|
src/pcl_ros/segmentation/sac_segmentation.cpp
|
|
|
|
|
)
|
|
|
|
|
#rosbuild_add_compile_flags (pcl_ros_segmentation ${SSE_FLAGS})
|
|
|
|
|
target_link_libraries (pcl_ros_segmentation pcl_segmentation pcl_ros_tf ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
class_loader_hide_library_symbols(pcl_ros_segmentation)
|
|
|
|
|
|
|
|
|
|
# ---[ Point Cloud Library - Surface
|
|
|
|
|
add_library (pcl_ros_surface
|
|
|
|
|
src/pcl_ros/surface/surface.cpp
|
|
|
|
|
# Compilation is much faster if we include all the following CPP files in surface.cpp
|
|
|
|
|
src/pcl_ros/surface/convex_hull.cpp
|
2013-05-15 12:57:28 +09:00
|
|
|
src/pcl_ros/surface/moving_least_squares.cpp
|
2013-05-11 03:29:09 +09:00
|
|
|
)
|
|
|
|
|
#rosbuild_add_compile_flags (pcl_ros_surface ${SSE_FLAGS})
|
|
|
|
|
target_link_libraries (pcl_ros_surface ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
class_loader_hide_library_symbols(pcl_ros_surface)
|
|
|
|
|
|
2012-12-17 18:09:15 -08:00
|
|
|
############ TOOLS
|
|
|
|
|
|
|
|
|
|
add_executable (pcd_to_pointcloud tools/pcd_to_pointcloud.cpp)
|
|
|
|
|
target_link_libraries (pcd_to_pointcloud pcl_io ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
add_executable (pointcloud_to_pcd tools/pointcloud_to_pcd.cpp)
|
|
|
|
|
target_link_libraries (pointcloud_to_pcd pcl_io ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
2012-12-17 18:54:03 -08:00
|
|
|
add_executable ( bag_to_pcd tools/bag_to_pcd.cpp)
|
2012-12-17 18:09:15 -08:00
|
|
|
target_link_libraries (bag_to_pcd pcl_io pcl_ros_tf ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
add_executable (convert_pcd_to_image tools/convert_pcd_to_image.cpp)
|
|
|
|
|
target_link_libraries (convert_pcd_to_image pcl_io pcl_common ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
add_executable (convert_pointcloud_to_image tools/convert_pointcloud_to_image.cpp)
|
|
|
|
|
target_link_libraries (convert_pointcloud_to_image pcl_io ${PCL_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES})
|
|
|
|
|
|
|
|
|
|
|
2012-10-04 16:58:35 +02:00
|
|
|
install(DIRECTORY include/${PROJECT_NAME}/
|
|
|
|
|
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
2012-09-13 13:40:21 +00:00
|
|
|
)
|
2012-09-13 13:26:12 +00:00
|
|
|
|
2013-05-11 03:29:09 +09:00
|
|
|
install(TARGETS pcl_ros_tf pcl_ros_io pcl_ros_features pcl_ros_filters pcl_ros_surface pcl_ros_segmentation pcd_to_pointcloud pointcloud_to_pcd bag_to_pcd convert_pcd_to_image convert_pointcloud_to_image
|
2012-10-11 17:45:51 +02:00
|
|
|
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
|
|
|
|
|
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
|
|
|
|
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
|
2012-09-13 13:40:21 +00:00
|
|
|
)
|
2012-12-17 18:54:03 -08:00
|
|
|
|
2013-02-05 12:31:26 -08:00
|
|
|
# these target locations are deprecated and will be dropped in Hydro!
|
2013-04-22 11:32:02 -07:00
|
|
|
#install(TARGETS pcd_to_pointcloud pointcloud_to_pcd bag_to_pcd convert_pcd_to_image convert_pointcloud_to_image
|
|
|
|
|
# DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})
|
2012-12-17 18:54:03 -08:00
|
|
|
|
|
|
|
|
install(FILES pcl_nodelets.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
|
|
|
|
|
|
|
|
|
|
|