|
16 | 16 |
|
17 | 17 | #include "autoware_point_types/types.hpp"
|
18 | 18 |
|
19 |
| -#include <boost/circular_buffer.hpp> |
20 |
| - |
21 | 19 | #include <algorithm>
|
22 | 20 | #include <numeric>
|
23 | 21 |
|
@@ -47,6 +45,8 @@ BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options
|
47 | 45 | max_distance_range_ = declare_parameter<double>("max_distance_range");
|
48 | 46 | horizontal_resolution_ = declare_parameter<double>("horizontal_resolution");
|
49 | 47 | }
|
| 48 | + dust_mask_buffer.set_capacity(dust_buffering_frames_); |
| 49 | + no_return_mask_buffer.set_capacity(blockage_buffering_frames_); |
50 | 50 | if (vertical_bins_ <= horizontal_ring_id_) {
|
51 | 51 | RCLCPP_ERROR(
|
52 | 52 | this->get_logger(),
|
@@ -214,7 +214,6 @@ void BlockageDiagComponent::filter(
|
214 | 214 | cv::Point(blockage_kernel_, blockage_kernel_));
|
215 | 215 | cv::erode(no_return_mask, erosion_dst, blockage_element);
|
216 | 216 | cv::dilate(erosion_dst, no_return_mask, blockage_element);
|
217 |
| - static boost::circular_buffer<cv::Mat> no_return_mask_buffer(blockage_buffering_frames_); |
218 | 217 | cv::Mat time_series_blockage_result(
|
219 | 218 | cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
|
220 | 219 | cv::Mat time_series_blockage_mask(
|
@@ -292,7 +291,6 @@ void BlockageDiagComponent::filter(
|
292 | 291 | cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img);
|
293 | 292 | cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1);
|
294 | 293 | cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img);
|
295 |
| - static boost::circular_buffer<cv::Mat> dust_mask_buffer(dust_buffering_frames_); |
296 | 294 | cv::Mat binarized_dust_mask_(
|
297 | 295 | cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
|
298 | 296 | cv::Mat multi_frame_dust_mask(
|
|
0 commit comments