From e4e666d34f4a663e555a13e09a0aa9f616ce7022 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Thu, 26 Dec 2024 18:19:49 +0900 Subject: [PATCH] fix: resolve cppcheck issue shadowVariable Signed-off-by: Taekjin LEE --- .../image_projection_based_fusion/fusion_node.hpp | 6 +++--- .../src/fusion_node.cpp | 10 +++++----- 2 files changed, 8 insertions(+), 8 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 9696b39801a3b..69367434c6d73 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 @@ -108,7 +108,7 @@ class FusionNode : public rclcpp::Node // 2d detection management methods bool checkAllDet2dFused() { - std::lock_guard lock(mutex_det2d_flags_); + std::lock_guard lock_det2d_flags(mutex_det2d_flags_); for (const auto & det2d : det2d_list_) { if (!det2d.is_fused) { return false; @@ -118,12 +118,12 @@ class FusionNode : public rclcpp::Node } void setDet2dFused(Det2dManager & det2d) { - std::lock_guard lock(mutex_det2d_flags_); + std::lock_guard lock_det2d_flags(mutex_det2d_flags_); det2d.is_fused = true; } void clearAllDet2dFlags() { - std::lock_guard lock(mutex_det2d_flags_); + std::lock_guard lock_det2d_flags(mutex_det2d_flags_); for (auto & det2d : det2d_list_) { det2d.is_fused = false; } 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 cdac56d4e9b0c..83f2226be0e5a 100644 --- a/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/fusion_node.cpp @@ -263,7 +263,7 @@ void FusionNode::subCallback( // PROCESS: if the main message is remained (and roi is not collected all) publish the main // message may processed partially with arrived 2d rois stop_watch_ptr_->toc("processing_time", true); - std::lock_guard lock(mutex_det3d_msg_); + std::lock_guard lock_det3d(mutex_det3d_msg_); exportProcess(); // reset flags @@ -293,7 +293,7 @@ void FusionNode::subCallback( // for loop for each roi for (auto & det2d : det2d_list_) { const auto roi_i = det2d.id; - std::lock_guard lock(*(det2d.mtx_ptr)); + std::lock_guard lock_det2d(*(det2d.mtx_ptr)); // check camera info if (det2d.camera_projector_ptr == nullptr) { @@ -350,7 +350,7 @@ void FusionNode::subCallback( } // PROCESS: check if the fused message is ready to publish - std::lock_guard lock(mutex_det3d_msg_); + std::lock_guard lock_det3d(mutex_det3d_msg_); cached_det3d_msg_timestamp_ = timestamp_nsec; cached_det3d_msg_ptr_ = output_msg; if (checkAllDet2dFused()) { @@ -376,13 +376,13 @@ void FusionNode::roiCallback( stop_watch_ptr_->toc("processing_time", true); auto & det2d = det2d_list_.at(roi_i); - std::lock_guard lock(*(det2d.mtx_ptr)); + std::lock_guard lock_det2d(*(det2d.mtx_ptr)); int64_t timestamp_nsec = (*det2d_msg).header.stamp.sec * static_cast(1e9) + (*det2d_msg).header.stamp.nanosec; // if cached Msg exist, try to match if (cached_det3d_msg_ptr_ != nullptr) { - std::lock_guard lock(mutex_det3d_msg_); + std::lock_guard lock_det3d(mutex_det3d_msg_); int64_t new_stamp = cached_det3d_msg_timestamp_ + det2d.input_offset_ms * static_cast(1e6);