From fc5ec80d9ffc17fb02b87b2fc56dd2fd2876b90e Mon Sep 17 00:00:00 2001 From: Ismet Atabay <56237550+ismetatabay@users.noreply.github.com> Date: Thu, 20 Jul 2023 17:10:49 +0300 Subject: [PATCH] refactor(image_projection_based_fusion): convert input topic names to ROS parameters (#4247) * init commit Signed-off-by: ismetatabay * style(pre-commit): autofix Signed-off-by: ismetatabay * update pointpainting and roi_detected_object_fusion_launch Signed-off-by: ismetatabay * correct argument and param definitions Signed-off-by: ismetatabay --------- Signed-off-by: ismetatabay Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../debugger.hpp | 5 +- .../fusion_node.hpp | 6 ++- .../launch/pointpainting_fusion.launch.xml | 52 +++++++++--------- .../launch/roi_cluster_fusion.launch.xml | 52 +++++++++--------- .../roi_detected_object_fusion.launch.xml | 54 ++++++++++--------- .../src/debugger.cpp | 7 +-- .../src/fusion_node.cpp | 25 +++++++-- 7 files changed, 114 insertions(+), 87 deletions(-) diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp index 37a0925fb5501..8a6ac7672b3a8 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/debugger.hpp @@ -28,6 +28,7 @@ #include #include +#include #include namespace image_projection_based_fusion @@ -39,7 +40,8 @@ class Debugger { public: explicit Debugger( - rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size); + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size, + std::vector input_camera_topics); void publishImage(const std::size_t image_id, const rclcpp::Time & stamp); @@ -55,6 +57,7 @@ class Debugger rclcpp::Node * node_ptr_; std::shared_ptr image_transport_; + std::vector input_camera_topics_; std::vector image_subs_; std::vector image_pubs_; std::vector> image_buffers_; diff --git a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp index 4b33783653708..016633fa4ef92 100644 --- a/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp +++ b/perception/image_projection_based_fusion/include/image_projection_based_fusion/fusion_node.hpp @@ -100,13 +100,15 @@ class FusionNode : public rclcpp::Node rclcpp::TimerBase::SharedPtr timer_; double timeout_ms_{}; double match_threshold_ms_{}; + std::vector input_rois_topics_; + std::vector input_camera_info_topics_; + std::vector input_camera_topics_; /** \brief A vector of subscriber. */ typename rclcpp::Subscription::SharedPtr sub_; std::vector::SharedPtr> rois_subs_; - /** \brief Input point cloud topics. */ - std::vector input_topics_; + // offsets between cameras and the lidars std::vector input_offset_ms_; // cache for fusion diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 28c607fd8bc0c..a31f246fb5af1 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -38,32 +38,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -80,6 +54,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index d136cc9393703..71588eb42780e 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -44,32 +44,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - @@ -84,6 +58,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index 03e4abed5ecd0..dd71ca462f666 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -34,33 +34,8 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - + @@ -70,6 +45,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/image_projection_based_fusion/src/debugger.cpp b/perception/image_projection_based_fusion/src/debugger.cpp index b22c70dfcb9c9..3f52a0de1f09d 100644 --- a/perception/image_projection_based_fusion/src/debugger.cpp +++ b/perception/image_projection_based_fusion/src/debugger.cpp @@ -39,14 +39,15 @@ void drawRoiOnImage( namespace image_projection_based_fusion { Debugger::Debugger( - rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size) -: node_ptr_(node_ptr) + rclcpp::Node * node_ptr, const std::size_t image_num, const std::size_t image_buffer_size, + std::vector input_camera_topics) +: node_ptr_(node_ptr), input_camera_topics_{input_camera_topics} { image_buffers_.resize(image_num); image_buffer_size_ = image_buffer_size; for (std::size_t img_i = 0; img_i < image_num; ++img_i) { auto sub = image_transport::create_subscription( - node_ptr, "input/image_raw" + std::to_string(img_i), + node_ptr, input_camera_topics.at(img_i), std::bind(&Debugger::imageCallback, this, std::placeholders::_1, img_i), "raw", rmw_qos_profile_sensor_data); image_subs_.push_back(sub); diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 656adaac252fc..03f625603ba91 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -60,6 +60,24 @@ FusionNode::FusionNode( match_threshold_ms_ = declare_parameter("match_threshold_ms"); timeout_ms_ = declare_parameter("timeout_ms"); + input_rois_topics_.resize(rois_number_); + input_camera_topics_.resize(rois_number_); + input_camera_info_topics_.resize(rois_number_); + + for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) { + input_rois_topics_.at(roi_i) = declare_parameter( + "input/rois" + std::to_string(roi_i), + "/perception/object_recognition/detection/rois" + std::to_string(roi_i)); + + input_camera_info_topics_.at(roi_i) = declare_parameter( + "input/camera_info" + std::to_string(roi_i), + "/sensing/camera/camera" + std::to_string(roi_i) + "/camera_info"); + + input_camera_topics_.at(roi_i) = declare_parameter( + "input/image" + std::to_string(roi_i), + "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); + } + input_offset_ms_ = declare_parameter("input_offset_ms", std::vector{}); if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) { throw std::runtime_error("The number of offsets does not match the number of topics."); @@ -71,7 +89,7 @@ FusionNode::FusionNode( std::function fnc = std::bind(&FusionNode::cameraInfoCallback, this, std::placeholders::_1, roi_i); camera_info_subs_.at(roi_i) = this->create_subscription( - "input/camera_info" + std::to_string(roi_i), rclcpp::QoS{1}.best_effort(), fnc); + input_camera_info_topics_.at(roi_i), rclcpp::QoS{1}.best_effort(), fnc); } // sub rois @@ -82,7 +100,7 @@ FusionNode::FusionNode( std::function roi_callback = std::bind(&FusionNode::roiCallback, this, std::placeholders::_1, roi_i); rois_subs_.at(roi_i) = this->create_subscription( - "input/rois" + std::to_string(roi_i), rclcpp::QoS{1}.best_effort(), roi_callback); + input_rois_topics_.at(roi_i), rclcpp::QoS{1}.best_effort(), roi_callback); } // subscribers @@ -103,7 +121,8 @@ FusionNode::FusionNode( if (declare_parameter("debug_mode", false)) { std::size_t image_buffer_size = static_cast(declare_parameter("image_buffer_size", 15)); - debugger_ = std::make_shared(this, rois_number_, image_buffer_size); + debugger_ = + std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); } // initialize debug tool