From fd23b61e8c81ef22deacc4ef29970bf1fe460629 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 9 Jan 2025 09:10:40 +0900 Subject: [PATCH] fix(image_projection_based_fusion): remove mutex (#9862) refactor: Refactor fusion_node.hpp and fusion_node.cpp for improved code organization and readability Signed-off-by: Taekjin LEE --- .../fusion_node.hpp | 2 -- .../src/fusion_node.cpp | 30 +++++-------------- 2 files changed, 8 insertions(+), 24 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 b8881bc6abff7..e05339771f667 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 @@ -40,7 +40,6 @@ #include #include -#include #include #include #include @@ -127,7 +126,6 @@ class FusionNode : public rclcpp::Node // cache for fusion int64_t cached_det3d_msg_timestamp_; typename Msg3D::SharedPtr cached_det3d_msg_ptr_; - std::mutex mutex_cached_msgs_; protected: void setDet2DStatus(std::size_t rois_number); 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 310c68f12db88..700d249831000 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -280,8 +280,6 @@ void FusionNode::subCallback( } } - std::lock_guard lock(mutex_cached_msgs_); - // TIMING: reset timer to the timeout time auto period = std::chrono::duration_cast( std::chrono::duration(timeout_ms_)); @@ -447,28 +445,16 @@ void FusionNode::timer_callback() using std::chrono_literals::operator""ms; timer_->cancel(); - if (mutex_cached_msgs_.try_lock()) { - // PROCESS: if timeout, postprocess cached msg - if (cached_det3d_msg_ptr_ != nullptr) { - stop_watch_ptr_->toc("processing_time", true); - exportProcess(); - } - // reset flags whether the message is fused or not - for (auto & det2d : det2d_list_) { - det2d.is_fused = false; - } + // PROCESS: if timeout, postprocess cached msg + if (cached_det3d_msg_ptr_ != nullptr) { + stop_watch_ptr_->toc("processing_time", true); + exportProcess(); + } - mutex_cached_msgs_.unlock(); - } else { - // TIMING: retry the process after 10ms - try { - std::chrono::nanoseconds period = 10ms; - setPeriod(period.count()); - } catch (rclcpp::exceptions::RCLError & ex) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5000, "%s", ex.what()); - } - timer_->reset(); + // reset flags whether the message is fused or not + for (auto & det2d : det2d_list_) { + det2d.is_fused = false; } }