From 18bf3d062946aa3df91d9e6e86dfe9d7407abc79 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Fri, 27 Dec 2024 17:54:07 +0900 Subject: [PATCH] refactor: review member and method's access Signed-off-by: Taekjin LEE --- .../fusion_node.hpp | 46 ++++++++++--------- 1 file changed, 25 insertions(+), 21 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 c0a373d4ca239..f9b5521c9024c 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 @@ -90,15 +90,12 @@ class FusionNode : public rclcpp::Node explicit FusionNode( const std::string & node_name, const rclcpp::NodeOptions & options, int queue_size); -protected: +private: // Common process methods void cameraInfoCallback( const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const std::size_t camera_id); - // callback for main subscription - void subCallback(const typename Msg3D::ConstSharedPtr input_msg); - // callback for roi subscription - void roiCallback(const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); + // callback for timer void timer_callback(); void setPeriod(const int64_t new_period); @@ -115,6 +112,29 @@ class FusionNode : public rclcpp::Node return true; } + // camera projection + float approx_grid_cell_w_size_; + float approx_grid_cell_h_size_; + + // timer + rclcpp::TimerBase::SharedPtr timer_; + double timeout_ms_{}; + double match_threshold_ms_{}; + + std::vector::SharedPtr> rois_subs_; + std::vector::SharedPtr> camera_info_subs_; + + // cache for fusion + int64_t cached_det3d_msg_timestamp_; + typename Msg3D::SharedPtr cached_det3d_msg_ptr_; + std::mutex mutex_cached_msgs_; + +protected: + // callback for main subscription + void subCallback(const typename Msg3D::ConstSharedPtr input_msg); + // callback for roi subscription + void roiCallback(const typename Msg2D::ConstSharedPtr input_roi_msg, const std::size_t roi_i); + // Custom process methods virtual void preprocess(Msg3D & output_msg); virtual void fuseOnSingleImage( @@ -131,24 +151,8 @@ class FusionNode : public rclcpp::Node // 2d detection management std::vector> det2d_list_; - // camera projection - float approx_grid_cell_w_size_; - float approx_grid_cell_h_size_; - - // timer - rclcpp::TimerBase::SharedPtr timer_; - double timeout_ms_{}; - double match_threshold_ms_{}; - /** \brief A vector of subscriber. */ typename rclcpp::Subscription::SharedPtr sub_; - std::vector::SharedPtr> rois_subs_; - std::vector::SharedPtr> camera_info_subs_; - - // cache for fusion - int64_t cached_det3d_msg_timestamp_; - typename Msg3D::SharedPtr cached_det3d_msg_ptr_; - std::mutex mutex_cached_msgs_; // parameters for out_of_scope filter float filter_scope_min_x_;