Skip to content

Commit eb34b95

Browse files
committed
fix: multi-blockage-diag in 1 container died bug fix
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 6f44db2 commit eb34b95

File tree

2 files changed

+6
-4
lines changed

2 files changed

+6
-4
lines changed

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/blockage_diag/blockage_diag_nodelet.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@
3333
#include <cv_bridge/cv_bridge.h>
3434
#endif
3535

36+
#include <boost/circular_buffer.hpp>
37+
3638
#include <string>
3739
#include <vector>
3840

@@ -91,6 +93,8 @@ class BlockageDiagComponent : public pointcloud_preprocessor::Filter
9193
int dust_frame_count_ = 0;
9294
double max_distance_range_{200.0};
9395
double horizontal_resolution_{0.4};
96+
boost::circular_buffer<cv::Mat> no_return_mask_buffer{1};
97+
boost::circular_buffer<cv::Mat> dust_mask_buffer{1};
9498

9599
public:
96100
PCL_MAKE_ALIGNED_OPERATOR_NEW

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -16,8 +16,6 @@
1616

1717
#include "autoware_point_types/types.hpp"
1818

19-
#include <boost/circular_buffer.hpp>
20-
2119
#include <algorithm>
2220
#include <numeric>
2321

@@ -47,6 +45,8 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options
4745
max_distance_range_ = declare_parameter<double>("max_distance_range");
4846
horizontal_resolution_ = declare_parameter<double>("horizontal_resolution");
4947
}
48+
dust_mask_buffer.set_capacity(dust_buffering_frames_);
49+
no_return_mask_buffer.set_capacity(blockage_buffering_frames_);
5050
if (vertical_bins_ <= horizontal_ring_id_) {
5151
RCLCPP_ERROR(
5252
this->get_logger(),
@@ -214,7 +214,6 @@ void BlockageDiagComponent::filter(
214214
cv::Point(blockage_kernel_, blockage_kernel_));
215215
cv::erode(no_return_mask, erosion_dst, blockage_element);
216216
cv::dilate(erosion_dst, no_return_mask, blockage_element);
217-
static boost::circular_buffer<cv::Mat> no_return_mask_buffer(blockage_buffering_frames_);
218217
cv::Mat time_series_blockage_result(
219218
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
220219
cv::Mat time_series_blockage_mask(
@@ -292,7 +291,6 @@ void BlockageDiagComponent::filter(
292291
cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img);
293292
cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1);
294293
cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img);
295-
static boost::circular_buffer<cv::Mat> dust_mask_buffer(dust_buffering_frames_);
296294
cv::Mat binarized_dust_mask_(
297295
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
298296
cv::Mat multi_frame_dust_mask(

0 commit comments

Comments
 (0)