From d8646c23739e69ee167016f56b72583fef8e8cfd Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 26 Dec 2024 18:41:32 +0900 Subject: [PATCH] Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE --- .../fusion_node.hpp | 12 +++++++----- .../src/fusion_node.cpp | 18 ++++++++---------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp index 69367434c6d73..d7b3e539a390e 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp @@ -165,11 +165,7 @@ class FusionNode : public rclcpp::Node typename Msg3D::SharedPtr cached_det3d_msg_ptr_; std::mutex mutex_det3d_msg_; - // output publisher - typename rclcpp::Publisher::SharedPtr pub_ptr_; - - // debugger - std::shared_ptr debugger_; + // parameters for out_of_scope filter float filter_scope_min_x_; float filter_scope_max_x_; float filter_scope_min_y_; @@ -177,6 +173,12 @@ class FusionNode : public rclcpp::Node float filter_scope_min_z_; float filter_scope_max_z_; + // output publisher + typename rclcpp::Publisher::SharedPtr pub_ptr_; + + // debugger + std::shared_ptr debugger_; + /** \brief processing time publisher. **/ std::unique_ptr> stop_watch_ptr_; std::unique_ptr debug_publisher_; diff --git a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp index 83f2226be0e5a..2f321f29971a6 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -106,9 +106,6 @@ FusionNode::FusionNode( std::bind(&FusionNode::subCallback, this, std::placeholders::_1); sub_ = this->create_subscription("input", rclcpp::QoS(1).best_effort(), sub_callback); - // // publisher - // pub_ptr_ = this->create_publisher("output", rclcpp::QoS{1}); - // Set timer const auto period_ns = std::chrono::duration_cast( std::chrono::duration(timeout_ms_)); @@ -159,6 +156,14 @@ FusionNode::FusionNode( det2d_list_.at(roi_i).input_offset_ms = input_offset_ms.at(roi_i); } + // parameters for out_of_scope filter + filter_scope_min_x_ = declare_parameter("filter_scope_min_x"); + filter_scope_max_x_ = declare_parameter("filter_scope_max_x"); + filter_scope_min_y_ = declare_parameter("filter_scope_min_y"); + filter_scope_max_y_ = declare_parameter("filter_scope_max_y"); + filter_scope_min_z_ = declare_parameter("filter_scope_min_z"); + filter_scope_max_z_ = declare_parameter("filter_scope_max_z"); + // debugger if (declare_parameter("debug_mode", false)) { std::vector input_camera_topics; @@ -193,13 +198,6 @@ FusionNode::FusionNode( stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } - - filter_scope_min_x_ = declare_parameter("filter_scope_min_x"); - filter_scope_max_x_ = declare_parameter("filter_scope_max_x"); - filter_scope_min_y_ = declare_parameter("filter_scope_min_y"); - filter_scope_max_y_ = declare_parameter("filter_scope_max_y"); - filter_scope_min_z_ = declare_parameter("filter_scope_min_z"); - filter_scope_max_z_ = declare_parameter("filter_scope_max_z"); } template