From 0c8e7dafce90ff7621267b38f7be543ab3218a19 Mon Sep 17 00:00:00 2001 From: Daisuke Sato <43101027+daisukes@users.noreply.github.com> Date: Fri, 27 Jan 2023 18:50:45 -0500 Subject: [PATCH] Migrate extract_indices filter (#394) * - migrate extract_indices filter - add test to check if filter node/component output result Signed-off-by: Daisuke Sato * add test_depend to package.xml Signed-off-by: Daisuke Sato * add launch_testing_ros as test_depend too Signed-off-by: Daisuke Sato * fixed test not to depend on ros2cli Signed-off-by: Daisuke Sato --------- Signed-off-by: Daisuke Sato --- pcl_ros/CMakeLists.txt | 8 +- .../pcl_ros/filters/extract_indices.hpp | 26 ++--- pcl_ros/package.xml | 6 + .../src/pcl_ros/filters/extract_indices.cpp | 66 ++++++----- pcl_ros/tests/filters/CMakeLists.txt | 35 ++++++ pcl_ros/tests/filters/dummy_topics.cpp | 109 ++++++++++++++++++ .../tests/filters/test_filter_component.py | 90 +++++++++++++++ .../tests/filters/test_filter_executable.py | 60 ++++++++++ 8 files changed, 358 insertions(+), 42 deletions(-) create mode 100644 pcl_ros/tests/filters/CMakeLists.txt create mode 100644 pcl_ros/tests/filters/dummy_topics.cpp create mode 100644 pcl_ros/tests/filters/test_filter_component.py create mode 100644 pcl_ros/tests/filters/test_filter_executable.py diff --git a/pcl_ros/CMakeLists.txt b/pcl_ros/CMakeLists.txt index 5952e859..5e79bf6b 100644 --- a/pcl_ros/CMakeLists.txt +++ b/pcl_ros/CMakeLists.txt @@ -26,6 +26,7 @@ find_package(tf2_ros REQUIRED) set(dependencies pcl_conversions rclcpp + rclcpp_components sensor_msgs geometry_msgs tf2 @@ -81,7 +82,7 @@ ament_target_dependencies(pcl_ros_tf # ### Declare the pcl_ros_filters library add_library(pcl_ros_filters SHARED -# src/pcl_ros/filters/extract_indices.cpp + 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 @@ -92,6 +93,10 @@ add_library(pcl_ros_filters SHARED ) target_link_libraries(pcl_ros_filters pcl_ros_tf ${PCL_LIBRARIES}) ament_target_dependencies(pcl_ros_filters ${dependencies}) +rclcpp_components_register_node(pcl_ros_filters + PLUGIN "pcl_ros::ExtractIndices" + EXECUTABLE filter_extract_indices_node +) class_loader_hide_library_symbols(pcl_ros_filters) # ### Declare the pcl_ros_segmentation library @@ -163,6 +168,7 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() find_package(ament_cmake_gtest REQUIRED) + add_subdirectory(tests/filters) #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) diff --git a/pcl_ros/include/pcl_ros/filters/extract_indices.hpp b/pcl_ros/include/pcl_ros/filters/extract_indices.hpp index 95740f60..bb752f2d 100644 --- a/pcl_ros/include/pcl_ros/filters/extract_indices.hpp +++ b/pcl_ros/include/pcl_ros/filters/extract_indices.hpp @@ -40,9 +40,9 @@ // PCL includes #include - +#include +#include #include "pcl_ros/filters/filter.hpp" -#include "pcl_ros/ExtractIndicesConfig.hpp" namespace pcl_ros { @@ -53,9 +53,6 @@ namespace pcl_ros class ExtractIndices : public Filter { protected: - /** \brief Pointer to a dynamic reconfigure service. */ - boost::shared_ptr> srv_; - /** \brief Call the actual filter. * \param input the input point cloud dataset * \param indices the input set of indices to use from \a input @@ -63,10 +60,10 @@ protected: */ inline void filter( - const PointCloud2::ConstPtr & input, const IndicesPtr & indices, + const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices, PointCloud2 & output) { - boost::mutex::scoped_lock lock(mutex_); + std::lock_guard lock(mutex_); pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2); pcl_conversions::toPCL(*(input), *(pcl_input)); impl_.setInputCloud(pcl_input); @@ -76,16 +73,13 @@ protected: pcl_conversions::moveFromPCL(pcl_output, output); } - /** \brief Child initialization routine. - * \param nh ROS node handle - * \param has_service set to true if the child has a Dynamic Reconfigure service + /** \brief Parameter callback + * \param params parameter values to set */ - virtual bool - child_init(ros::NodeHandle & nh, bool & has_service); + rcl_interfaces::msg::SetParametersResult + config_callback(const std::vector & params); - /** \brief Dynamic reconfigure service callback. */ - void - config_callback(pcl_ros::ExtractIndicesConfig & config, uint32_t level); + OnSetParametersCallbackHandle::SharedPtr callback_handle_; private: /** \brief The PCL filter implementation used. */ @@ -93,6 +87,8 @@ private: public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + explicit ExtractIndices(const rclcpp::NodeOptions & options); }; } // namespace pcl_ros diff --git a/pcl_ros/package.xml b/pcl_ros/package.xml index 566b1b6d..12e1def6 100644 --- a/pcl_ros/package.xml +++ b/pcl_ros/package.xml @@ -49,6 +49,12 @@ ament_lint_auto ament_lint_common ament_cmake_gtest + ament_cmake_pytest + launch + launch_ros + launch_testing + launch_testing_ros + sensor_msgs