Skip to content

Commit

Permalink
fix build with PCL 1.13
Browse files Browse the repository at this point in the history
- 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.
  • Loading branch information
v4hn committed Nov 18, 2024
1 parent 93a9871 commit c394e94
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 2 deletions.
2 changes: 1 addition & 1 deletion jsk_pcl_ros_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down
5 changes: 5 additions & 0 deletions jsk_pcl_ros_utils/src/normal_flip_to_frame_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion jsk_pcl_ros_utils/src/pointcloud_to_pcd_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace jsk_pcl_ros_utils

void PointCloudToPCD::savePCD()
{
pcl::PCLPointCloud2::ConstPtr cloud;
boost::shared_ptr<const pcl::PCLPointCloud2> cloud;
cloud = ros::topic::waitForMessage<pcl::PCLPointCloud2>("input", *pnh_);
if ((cloud->width * cloud->height) == 0)
{
Expand Down

0 comments on commit c394e94

Please sign in to comment.