From c394e94add20890c53e03f1478b25c83ea531682 Mon Sep 17 00:00:00 2001 From: v4hn Date: Mon, 18 Nov 2024 17:40:26 +0100 Subject: [PATCH] fix build with PCL 1.13 - PCL_LIBRARIES has to be added explicitly to pull in VTK, which is required in `pointcloud_to_stl_nodelet.cpp` by using `pcl::io::savePolygonFileSTL(ss.str(),triangles)`. (the respective header includes VTK headers) - define pcl_isfinite again which got removed from PCL for compatibility with old versions - ros::topic::waitForMessage still returns a boost::shared_ptr. --- jsk_pcl_ros_utils/CMakeLists.txt | 2 +- jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp | 5 +++++ jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp | 2 +- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/jsk_pcl_ros_utils/CMakeLists.txt b/jsk_pcl_ros_utils/CMakeLists.txt index 231dda1b06..e9eb0eff92 100644 --- a/jsk_pcl_ros_utils/CMakeLists.txt +++ b/jsk_pcl_ros_utils/CMakeLists.txt @@ -223,7 +223,7 @@ jsk_pcl_util_nodelet(src/marker_array_voxel_to_pointcloud_nodelet.cpp add_library(jsk_pcl_ros_utils SHARED ${jsk_pcl_util_nodelet_sources}) add_dependencies(jsk_pcl_ros_utils ${PROJECT_NAME}_gencfg) target_link_libraries(jsk_pcl_ros_utils - ${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp) + ${catkin_LIBRARIES} ${pcl_ros_LIBRARIES} ${PCL_LIBRARIES} ${OpenCV_LIBRARIES} yaml-cpp) get_property(dirs DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} PROPERTY INCLUDE_DIRECTORIES) diff --git a/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp b/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp index 77309bb8cb..36a59b2f88 100644 --- a/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp @@ -64,6 +64,11 @@ namespace jsk_pcl_ros_utils sub_.shutdown(); } +// pcl removed the method by 1.13, no harm in defining it ourselves to use below +#if __cplusplus >= 201103L +#define pcl_isfinite(x) std::isfinite(x) +#endif + void NormalFlipToFrame::flip(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) { vital_checker_->poke(); diff --git a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp index fe9be68586..e123b5057c 100644 --- a/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp +++ b/jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp @@ -60,7 +60,7 @@ namespace jsk_pcl_ros_utils void PointCloudToPCD::savePCD() { - pcl::PCLPointCloud2::ConstPtr cloud; + boost::shared_ptr cloud; cloud = ros::topic::waitForMessage("input", *pnh_); if ((cloud->width * cloud->height) == 0) {