Skip to content

Commit

Permalink
revert mutex related changes
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Dec 27, 2024
1 parent 3c73ba9 commit a01f84f
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,6 @@ struct Det2dStatus
double input_offset_ms = 0.0;
// cache
std::map<int64_t, typename Msg2D::ConstSharedPtr> cached_det2d_msgs;
std::unique_ptr<std::mutex> mtx_ptr;
};

template <class Msg3D, class Msg2D, class ExportObj>
Expand Down Expand Up @@ -108,26 +107,13 @@ class FusionNode : public rclcpp::Node
// 2d detection management methods
bool checkAllDet2dFused()

Check warning on line 108 in perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/fusion_node.hpp#L108

Added line #L108 was not covered by tests
{
std::lock_guard<std::mutex> lock_det2d_flags(mutex_det2d_flags_);
for (const auto & det2d : det2d_list_) {
if (!det2d.is_fused) {
return false;
}
}
return true;
}
void setDet2dFused(Det2dStatus<Msg2D> & det2d)
{
std::lock_guard<std::mutex> lock_det2d_flags(mutex_det2d_flags_);
det2d.is_fused = true;
}
void clearAllDet2dFlags()
{
std::lock_guard<std::mutex> lock_det2d_flags(mutex_det2d_flags_);
for (auto & det2d : det2d_list_) {
det2d.is_fused = false;
}
}

// Custom process methods
virtual void preprocess(Msg3D & output_msg);
Expand All @@ -144,7 +130,6 @@ class FusionNode : public rclcpp::Node

// 2d detection management
std::vector<Det2dStatus<Msg2D>> det2d_list_;
std::mutex mutex_det2d_flags_;

// camera projection
float approx_grid_cell_w_size_;
Expand All @@ -163,7 +148,7 @@ class FusionNode : public rclcpp::Node
// cache for fusion
int64_t cached_det3d_msg_timestamp_;
typename Msg3D::SharedPtr cached_det3d_msg_ptr_;
std::mutex mutex_det3d_msg_;
std::mutex mutex_cached_msgs_;

// parameters for out_of_scope filter
float filter_scope_min_x_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,6 @@ FusionNode<Msg3D, Msg2D, ExportObj>::FusionNode(
// 2d detection status initialization
det2d_list_.resize(rois_number_);
for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) {
det2d_list_.at(roi_i).mtx_ptr = std::make_unique<std::mutex>();
det2d_list_.at(roi_i).id = roi_i;
det2d_list_.at(roi_i).project_to_unrectified_image =

Check warning on line 152 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L151-L152

Added lines #L151 - L152 were not covered by tests
point_project_to_unrectified_image.at(roi_i);
Expand Down Expand Up @@ -261,13 +260,16 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::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<std::mutex> lock_det3d(mutex_det3d_msg_);
exportProcess();

// reset flags
clearAllDet2dFlags();
for (auto & det2d : det2d_list_) {
det2d.is_fused = false;

Check warning on line 267 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L267

Added line #L267 was not covered by tests
}
}

std::lock_guard<std::mutex> lock(mutex_cached_msgs_);

// TIMING: reset timer to the timeout time
auto period = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::duration<double, std::milli>(timeout_ms_));
Expand All @@ -291,7 +293,6 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(
// for loop for each roi
for (auto & det2d : det2d_list_) {
const auto roi_i = det2d.id;
std::lock_guard<std::mutex> lock_det2d(*(det2d.mtx_ptr));

// check camera info
if (det2d.camera_projector_ptr == nullptr) {
Expand Down Expand Up @@ -333,7 +334,7 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(

fuseOnSingleImage(*det3d_msg, det2d, *(det2d_msgs[matched_stamp]), *output_msg);
det2d_msgs.erase(matched_stamp);
setDet2dFused(det2d);
det2d.is_fused = true;

// add timestamp interval for debug
if (debug_publisher_) {
Expand All @@ -348,15 +349,16 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::subCallback(
}

// PROCESS: check if the fused message is ready to publish
std::lock_guard<std::mutex> lock_det3d(mutex_det3d_msg_);
cached_det3d_msg_timestamp_ = timestamp_nsec;

Check warning on line 352 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L352

Added line #L352 was not covered by tests
cached_det3d_msg_ptr_ = output_msg;
if (checkAllDet2dFused()) {
// if all camera fused, postprocess and publish the main message
exportProcess();

// reset flags
clearAllDet2dFlags();
for (auto & det2d : det2d_list_) {
det2d.is_fused = false;

Check warning on line 360 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L360

Added line #L360 was not covered by tests
}
} else {
// if all of rois are not collected, publish the old Msg(if exists) and cache the
// current Msg

Check notice on line 364 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

subCallback increases in cyclomatic complexity from 20 to 21, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 364 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Deep, Nested Complexity

subCallback is no longer above the threshold for nested complexity depth. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
Expand All @@ -374,14 +376,11 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(
stop_watch_ptr_->toc("processing_time", true);

auto & det2d = det2d_list_.at(roi_i);
std::lock_guard<std::mutex> lock_det2d(*(det2d.mtx_ptr));

int64_t timestamp_nsec =

Check warning on line 380 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L380

Added line #L380 was not covered by tests
(*det2d_msg).header.stamp.sec * static_cast<int64_t>(1e9) + (*det2d_msg).header.stamp.nanosec;
// if cached Msg exist, try to match
if (cached_det3d_msg_ptr_ != nullptr) {
std::lock_guard<std::mutex> lock_det3d(mutex_det3d_msg_);

int64_t new_stamp =
cached_det3d_msg_timestamp_ + det2d.input_offset_ms * static_cast<int64_t>(1e6);

Check warning on line 385 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L384-L385

Added lines #L384 - L385 were not covered by tests
int64_t interval = abs(timestamp_nsec - new_stamp);
Expand All @@ -401,7 +400,7 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(
}
// PROCESS: fuse the main message with the roi message
fuseOnSingleImage(*(cached_det3d_msg_ptr_), det2d, *det2d_msg, *(cached_det3d_msg_ptr_));
setDet2dFused(det2d);
det2d.is_fused = true;

if (debug_publisher_) {
double timestamp_interval_ms = (timestamp_nsec - cached_det3d_msg_timestamp_) / 1e6;

Check warning on line 406 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L406

Added line #L406 was not covered by tests
Expand All @@ -416,7 +415,9 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::roiCallback(
if (checkAllDet2dFused()) {
exportProcess();
// reset flags
clearAllDet2dFlags();
for (auto & det2d : det2d_list_) {

Check failure on line 418 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View workflow job for this annotation

GitHub Actions / cppcheck-differential

Local variable 'det2d' shadows outer variable [shadowVariable]
det2d.is_fused = false;

Check warning on line 419 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L419

Added line #L419 was not covered by tests
}
}
processing_time_ms = processing_time_ms + stop_watch_ptr_->toc("processing_time", true);
return;
Expand All @@ -440,17 +441,19 @@ void FusionNode<Msg3D, Msg2D, ExportObj>::timer_callback()

using std::chrono_literals::operator""ms;
timer_->cancel();
if (mutex_det3d_msg_.try_lock()) {
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
clearAllDet2dFlags();
for (auto & det2d : det2d_list_) {
det2d.is_fused = false;

Check warning on line 453 in perception/autoware_image_projection_based_fusion/src/fusion_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/fusion_node.cpp#L453

Added line #L453 was not covered by tests
}

mutex_det3d_msg_.unlock();
mutex_cached_msgs_.unlock();
} else {
// TIMING: retry the process after 10ms
try {
Expand Down

0 comments on commit a01f84f

Please sign in to comment.