Skip to content

Commit

Permalink
fix(image_projection_based_fusion): revert the swap of postprocess an…
Browse files Browse the repository at this point in the history
…d publish (autowarefoundation#4400)

fix: revert the swap of postprocess and publish

Signed-off-by: tzhong518 <[email protected]>
  • Loading branch information
tzhong518 authored and yukke42 committed Jul 27, 2023
1 parent 0d7cb36 commit 0219394
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions perception/image_projection_based_fusion/src/fusion_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,8 +166,8 @@ void FusionNode<Msg, Obj>::subCallback(const typename Msg::ConstSharedPtr input_
if (sub_std_pair_.second != nullptr) {
stop_watch_ptr_->toc("processing_time", true);
timer_->cancel();
publish(*(sub_std_pair_.second));
postprocess(*(sub_std_pair_.second));
publish(*(sub_std_pair_.second));
sub_std_pair_.second = nullptr;
std::fill(is_fused_.begin(), is_fused_.end(), false);

Expand Down Expand Up @@ -260,8 +260,8 @@ void FusionNode<Msg, Obj>::subCallback(const typename Msg::ConstSharedPtr input_
// Msg
if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast<int>(rois_number_)) {
timer_->cancel();
publish(*output_msg);
postprocess(*output_msg);
publish(*output_msg);
std::fill(is_fused_.begin(), is_fused_.end(), false);
sub_std_pair_.second = nullptr;

Expand Down Expand Up @@ -322,8 +322,8 @@ void FusionNode<Msg, Obj>::roiCallback(

if (std::count(is_fused_.begin(), is_fused_.end(), true) == static_cast<int>(rois_number_)) {
timer_->cancel();
publish(*(sub_std_pair_.second));
postprocess(*(sub_std_pair_.second));
publish(*(sub_std_pair_.second));
std::fill(is_fused_.begin(), is_fused_.end(), false);
sub_std_pair_.second = nullptr;

Expand Down Expand Up @@ -362,8 +362,8 @@ void FusionNode<Msg, Obj>::timer_callback()
if (sub_std_pair_.second != nullptr) {
stop_watch_ptr_->toc("processing_time", true);

publish(*(sub_std_pair_.second));
postprocess(*(sub_std_pair_.second));
publish(*(sub_std_pair_.second));

// add processing time for debug
if (debug_publisher_) {
Expand Down

0 comments on commit 0219394

Please sign in to comment.