Robotics StackExchange | Archived questions

PCL catkin_make error : undefined reference to `pcl::Filter<pcl::PCLPointCloud2>

This is the .cpp code:

#include <ros/ros.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <boost/foreach.hpp>
#include <pcl/filters/crop_box.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/point_cloud2_iterator.h>

 ros::Publisher pub;

 void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
 {

 pcl::PCLPointCloud2* cloud = new pcl::PCLPointCloud2;
 pcl::PCLPointCloud2ConstPtr cloudPtr(cloud);
 pcl::PCLPointCloud2 cloud_filtered;

 // Do data processing here...
 pcl_conversions::toPCL(*cloud_msg, *cloud);

 pcl::CropBox<pcl::PCLPointCloud2> boxFilter;
 boxFilter.setInputCloud(cloudPtr);
 boxFilter.setMin(Eigen::Vector4f(1.0, 1.0, 1.0, 0));
 boxFilter.setMax(Eigen::Vector4f(4.0, 4.0, 4.0, 0));
 boxFilter.setTranslation(Eigen::Vector3f(0.0, 0.0, 0.0));
 boxFilter.filter(cloud_filtered);

 sensor_msgs::PointCloud2 output;
 pcl_conversions::fromPCL(cloud_filtered, output);

 for (sensor_msgs::PointCloud2ConstIterator<float> it(output, "x"); it != it.end(); ++it) {
     // TODO: do something with the values of x, y, z

     std::cout <<  it[0] << "/ ";
     std::cout <<  it[1]<< "/ ";
     std::cout <<  it[2]<< "/ ";
     std::cout << std::endl;
 }

 // Publish the data.
 pub.publish (output);

 }

 int main (int argc, char** argv)
{
// Initialize ROS
ros::init (argc, argv, "CROP");
ros::NodeHandle nh;

// Create a ROS subscriber for the input point cloud
ros::Subscriber sub = nh.subscribe ("/camera/depth/points", 1, cloud_cb);

// Create a ROS publisher for the output point cloud
pub = nh.advertise<sensor_msgs::PointCloud2> ("/Cloud_Cropped", 1);

// Spin
ros::spin ();
}

This is my CMakeLists.txt:

cmake_minimum_required(VERSION 2.8)
project(pcl_ros)

## Find system dependencies
find_package(cmake_modules REQUIRED)
find_package(Boost REQUIRED COMPONENTS system filesystem thread)
find_package(Eigen3 REQUIRED)
find_package(PCL REQUIRED)

if(NOT "${PCL_LIBRARIES}" STREQUAL "")
  # For debian: https://github.com/ros-perception/perception_pcl/issues/139
  list(REMOVE_ITEM PCL_LIBRARIES
    "vtkGUISupportQt"
    "vtkGUISupportQtOpenGL"
    "vtkGUISupportQtSQL"
    "vtkGUISupportQtWebkit"
    "vtkViewsQt"
    "vtkRenderingQt")
endif()

# Remove include dirs which does not exist in some platforms.
# https://github.com/ros-perception/perception_pcl/issues/172
# https://github.com/ros-perception/perception_pcl/issues/206
if(NOT "${PCL_INCLUDE_DIRS}" STREQUAL "")
  foreach(item ${PCL_INCLUDE_DIRS})
    set(patterns "/usr/include/.*-linux-gnu/freetype2" "/usr/include/hdf5/openmpi")
    foreach(pattern ${patterns})
      string(REGEX MATCH ${pattern} match ${item})
      if(match)
        list(REMOVE_ITEM PCL_INCLUDE_DIRS ${match})
      endif()
    endforeach()
  endforeach()
endif()

## Find catkin packages
find_package(catkin REQUIRED COMPONENTS
  dynamic_reconfigure
  genmsg
  nodelet
  nodelet_topic_tools
  pcl_conversions
  pcl_msgs
  pluginlib
  rosbag
  rosconsole
  roscpp
  roslib
  sensor_msgs
  std_msgs
  tf
  tf2_eigen
)

## Add include directories
include_directories(include
  ${Boost_INCLUDE_DIRS}
  ${catkin_INCLUDE_DIRS}
  ${EIGEN3_INCLUDE_DIRS}
  ${PCL_INCLUDE_DIRS}
)

## Generate dynamic_reconfigure
generate_dynamic_reconfigure_options(
  cfg/EuclideanClusterExtraction.cfg
  cfg/ExtractIndices.cfg
  cfg/ExtractPolygonalPrismData.cfg
  cfg/Feature.cfg
  cfg/Filter.cfg
  cfg/MLS.cfg
  cfg/SACSegmentation.cfg
  cfg/SACSegmentationFromNormals.cfg
  cfg/SegmentDifferences.cfg
  cfg/StatisticalOutlierRemoval.cfg
  cfg/RadiusOutlierRemoval.cfg
  cfg/VoxelGrid.cfg
  cfg/CropBox.cfg
)

## Declare the catkin package
catkin_package(
  INCLUDE_DIRS include
  LIBRARIES
    pcl_ros_filters
    pcl_ros_io
    pcl_ros_tf
  CATKIN_DEPENDS
    dynamic_reconfigure
    message_filters
    nodelet
    nodelet_topic_tools
    pcl_conversions
    pcl_msgs
    rosbag
    roscpp
    sensor_msgs
    std_msgs
    tf
  DEPENDS
    Boost
    EIGEN3
    PCL
)

## Declare the pcl_ros_tf library
add_library(pcl_ros_tf src/transforms.cpp)
target_link_libraries(pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_tf ${catkin_EXPORTED_TARGETS})

## Nodelets

## Declare the pcl_ros_io library
add_library(pcl_ros_io
  src/pcl_ros/io/bag_io.cpp
  src/pcl_ros/io/concatenate_data.cpp
  src/pcl_ros/io/concatenate_fields.cpp
  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} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})
class_loader_hide_library_symbols(pcl_ros_io)

## Declare the pcl_ros_features library
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
  src/pcl_ros/features/boundary.cpp
  src/pcl_ros/features/fpfh.cpp
  src/pcl_ros/features/fpfh_omp.cpp
  src/pcl_ros/features/shot.cpp
  src/pcl_ros/features/shot_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
)
target_link_libraries (pcl_ros_features ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_features ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_features)


## Declare the pcl_ros_filters library
add_library(pcl_ros_filters
  src/pcl_ros/filters/extract_indices.cpp
  src/pcl_ros/filters/filter.cpp
  src/pcl_ros/filters/passthrough.cpp
  src/pcl_ros/filters/project_inliers.cpp
  src/pcl_ros/filters/radius_outlier_removal.cpp
  src/pcl_ros/filters/statistical_outlier_removal.cpp
  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} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_filters ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_filters)

## Declare the pcl_ros_segmentation library
add_library (pcl_ros_segmentation
  src/pcl_ros/segmentation/extract_clusters.cpp
  src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
  src/pcl_ros/segmentation/sac_segmentation.cpp
  src/pcl_ros/segmentation/segment_differences.cpp
  src/pcl_ros/segmentation/segmentation.cpp
)
target_link_libraries(pcl_ros_segmentation pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})
add_dependencies(pcl_ros_segmentation ${PROJECT_NAME}_gencfg)
class_loader_hide_library_symbols(pcl_ros_segmentation)

## Declare the pcl_ros_surface library
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
  src/pcl_ros/surface/moving_least_squares.cpp
)
target_link_libraries(pcl_ros_surface ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_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 ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})

add_executable(pointcloud_to_pcd tools/pointcloud_to_pcd.cpp)
target_link_libraries(pointcloud_to_pcd ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARY_DIRS} ${PCL_LIBRARIES})

add_executable(bag_to_pcd tools/bag_to_pcd.cpp)
target_link_libraries(bag_to_pcd pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARY_DIRS} ${PCL_LIBRARIES})

add_executable(convert_pcd_to_image tools/convert_pcd_to_image.cpp)
target_link_libraries(convert_pcd_to_image ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})

add_executable(convert_pointcloud_to_image tools/convert_pointcloud_to_image.cpp)
target_link_libraries(convert_pointcloud_to_image ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${PCL_LIBRARIES})

## Nikkolas Edit // If Errors delete this
add_executable(my_pcl_pub src/my_pcl_pub.cpp)
target_link_libraries(my_pcl_pub ${catkin_LIBRARIES})
add_dependencies(my_pcl_pub pcl_ros_generate_messages_cpp)

add_executable(my_pcl_sub src/my_pcl_sub.cpp)
target_link_libraries(my_pcl_sub ${catkin_LIBRARIES})
add_dependencies(my_pcl_sub pcl_ros_generate_messages_cpp)

add_executable(my_cam_sub src/my_cam_sub.cpp)
target_link_libraries(my_cam_sub ${catkin_LIBRARIES})
add_dependencies(my_cam_sub pcl_ros_generate_messages_cpp)

## Downloads

catkin_download(table_scene_lms400.pcd http://download.ros.org/data/pcl/table_scene_lms400.pcd
  DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/samples/data
  MD5 546b5b4822fb1de21b0cf83d41ad6683
)
add_custom_target(download ALL DEPENDS download_extra_data)

#############
## Testing ##
#############

if(CATKIN_ENABLE_TESTING)
  find_package(rostest REQUIRED)
  add_rostest_gtest(test_tf_message_filter_pcl tests/test_tf_message_filter_pcl.launch src/test/test_tf_message_filter_pcl.cpp)
  target_link_libraries(test_tf_message_filter_pcl ${catkin_LIBRARIES} ${GTEST_LIBRARIES})
  add_rostest(samples/pcl_ros/features/sample_normal_3d.launch ARGS gui:=false)
  add_rostest(samples/pcl_ros/filters/sample_statistical_outlier_removal.launch ARGS gui:=false)
  add_rostest(samples/pcl_ros/filters/sample_voxel_grid.launch ARGS gui:=false)
  add_rostest(samples/pcl_ros/segmentation/sample_extract_clusters.launch ARGS gui:=false)
  add_rostest(samples/pcl_ros/surface/sample_convex_hull.launch ARGS gui:=false)
endif(CATKIN_ENABLE_TESTING)


install(DIRECTORY include/${PROJECT_NAME}/
  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

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
  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)

install(DIRECTORY plugins samples
  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})

Terminal Error:

CMakeFiles/my_cam_sub.dir/src/my_cam_sub.cpp.o: In function `pcl::FilterIndices<pcl::PCLPointCloud2>::filter(pcl::PCLPointCloud2&)':
my_cam_sub.cpp:(.text._ZN3pcl13FilterIndicesINS_14PCLPointCloud2EE6filterERS1_[_ZN3pcl13FilterIndicesINS_14PCLPointCloud2EE6filterERS1_]+0x1f): undefined reference to `pcl::Filter<pcl::PCLPointCloud2>::filter(pcl::PCLPointCloud2&)'
CMakeFiles/my_cam_sub.dir/src/my_cam_sub.cpp.o: In function `pcl::CropBox<pcl::PCLPointCloud2>::CropBox(bool)':
my_cam_sub.cpp:(.text._ZN3pcl7CropBoxINS_14PCLPointCloud2EEC2Eb[_ZN3pcl7CropBoxINS_14PCLPointCloud2EEC5Eb]+0x34): undefined reference to `vtable for pcl::CropBox<pcl::PCLPointCloud2>'
CMakeFiles/my_cam_sub.dir/src/my_cam_sub.cpp.o: In function `pcl::CropBox<pcl::PCLPointCloud2>::~CropBox()':
my_cam_sub.cpp:(.text._ZN3pcl7CropBoxINS_14PCLPointCloud2EED2Ev[_ZN3pcl7CropBoxINS_14PCLPointCloud2EED5Ev]+0xd): undefined reference to `vtable for pcl::CropBox<pcl::PCLPointCloud2>'
collect2: error: ld returned 1 exit status
perception_pcl/pcl_ros/CMakeFiles/my_cam_sub.dir/build.make:287: recipe for target '/home/nikkolas/catkin_test/devel/lib/pcl_ros/my_cam_sub' failed
make[2]: *** [/home/nikkolas/catkin_test/devel/lib/pcl_ros/my_cam_sub] Error 1
CMakeFiles/Makefile2:4214: recipe for target 'perception_pcl/pcl_ros/CMakeFiles/my_cam_sub.dir/all' failed
make[1]: *** [perception_pcl/pcl_ros/CMakeFiles/my_cam_sub.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

Does anyone know why I get this back on the terminal while running catkin_make in the root folder?

Ubuntu 16.04 ROS Kinetic

Asked by Nikkolas Edi on 2020-01-30 12:45:07 UTC

Comments

Does adding ${PCL_LIBRARIES} to your my_cam_sub target_link_libraries help?

Asked by Rufus on 2020-10-13 04:18:06 UTC

Answers

project(pcl_ros)

Is your package named pcl_ros? If so and unless you're modifying the existing package of the same name, avoid using that name as it's already taken by well-known library.

Your CMakeLists.txt has many targets and yet haven't mentioned the name of the .cpp file you showed, so I can't tell which target is the one in question.

undefined reference to indicates the builder (e.g. catkin, colcon, or g++ that is wrapped by them) doesn't know where the header that is declared to be included in your code can be found. I assume those in the error are the ones provided by the original pcl_ros package. So I'd:

  1. Rename your pkg to something else other than pcl_ros
  2. Add pcl_ros in find_package list.

Asked by 130s on 2023-06-09 06:54:39 UTC

Comments