Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore(blockage_diag): add dust diagnostic option param #6645

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
blockage_count_threshold: 50
blockage_buffering_frames: 2
blockage_buffering_interval: 1
enable_dust_diag: false
publish_debug_image: false
dust_ratio_threshold: 0.2
dust_count_threshold: 10
dust_kernel_size: 2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,8 @@ class BlockageDiagComponent : public pointcloud_preprocessor::Filter
bool is_channel_order_top2down_;
int blockage_buffering_frames_;
int blockage_buffering_interval_;
bool enable_dust_diag_;
bool publish_debug_image_;
int dust_kernel_size_;
int dust_buffering_frames_;
int dust_buffering_interval_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@
blockage_count_threshold_ = declare_parameter<int>("blockage_count_threshold");
blockage_buffering_frames_ = declare_parameter<int>("blockage_buffering_frames");
blockage_buffering_interval_ = declare_parameter<int>("blockage_buffering_interval");
publish_debug_image_ = declare_parameter<bool>("publish_debug_image");
enable_dust_diag_ = declare_parameter<bool>("enable_dust_diag");

Check warning on line 41 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L40-L41

Added lines #L40 - L41 were not covered by tests
dust_ratio_threshold_ = declare_parameter<float>("dust_ratio_threshold");
dust_count_threshold_ = declare_parameter<int>("dust_count_threshold");
dust_kernel_size_ = declare_parameter<int>("dust_kernel_size");
Expand All @@ -59,26 +61,33 @@
updater_.add(
std::string(this->get_namespace()) + ": blockage_validation", this,
&BlockageDiagComponent::onBlockageChecker);
updater_.add(
std::string(this->get_namespace()) + ": dust_validation", this,
&BlockageDiagComponent::dustChecker);
if (enable_dust_diag_) {
updater_.add(
std::string(this->get_namespace()) + ": dust_validation", this,

Check warning on line 66 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L64-L66

Added lines #L64 - L66 were not covered by tests
&BlockageDiagComponent::dustChecker);

ground_dust_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS());
if (publish_debug_image_) {

Check warning on line 71 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L69-L71

Added lines #L69 - L71 were not covered by tests
single_frame_dust_mask_pub =
image_transport::create_publisher(this, "blockage_diag/debug/single_frame_dust_mask_image");

Check warning on line 73 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L73

Added line #L73 was not covered by tests
multi_frame_dust_mask_pub =
image_transport::create_publisher(this, "blockage_diag/debug/multi_frame_dust_mask_image");

Check warning on line 75 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L75

Added line #L75 was not covered by tests
blockage_dust_merged_pub =
image_transport::create_publisher(this, "blockage_diag/debug/blockage_dust_merged_image");

Check warning on line 77 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L77

Added line #L77 was not covered by tests
}
}
updater_.setPeriod(0.1);
single_frame_dust_mask_pub =
image_transport::create_publisher(this, "blockage_diag/debug/single_frame_dust_mask_image");
multi_frame_dust_mask_pub =
image_transport::create_publisher(this, "blockage_diag/debug/multi_frame_dust_mask_image");
lidar_depth_map_pub_ =
image_transport::create_publisher(this, "blockage_diag/debug/lidar_depth_map");
blockage_mask_pub_ =
image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image");
blockage_dust_merged_pub =
image_transport::create_publisher(this, "blockage_diag/debug/blockage_dust_merged_image");
if (publish_debug_image_) {

Check warning on line 81 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L81

Added line #L81 was not covered by tests
lidar_depth_map_pub_ =
image_transport::create_publisher(this, "blockage_diag/debug/lidar_depth_map");

Check warning on line 83 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L83

Added line #L83 was not covered by tests
blockage_mask_pub_ =
image_transport::create_publisher(this, "blockage_diag/debug/blockage_mask_image");

Check warning on line 85 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L85

Added line #L85 was not covered by tests
}
ground_blockage_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/ground_blockage_ratio", rclcpp::SensorDataQoS());
sky_blockage_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/sky_blockage_ratio", rclcpp::SensorDataQoS());
ground_dust_ratio_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
"blockage_diag/debug/ground_dust_ratio", rclcpp::SensorDataQoS());
using std::placeholders::_1;
set_param_res_ = this->add_on_set_parameters_callback(
std::bind(&BlockageDiagComponent::paramCallback, this, _1));
Expand Down Expand Up @@ -283,93 +292,95 @@
sky_blockage_count_ = 0;
}
// dust
cv::Mat ground_depth_map = lidar_depth_map_8u(
cv::Rect(0, horizontal_ring_id_, ideal_horizontal_bins, vertical_bins - horizontal_ring_id_));
cv::Mat sky_blank(horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0));
cv::Mat ground_blank(
vertical_bins - horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0));
cv::Mat single_dust_img(
cv::Size(lidar_depth_map_8u.rows, lidar_depth_map_8u.cols), CV_8UC1, cv::Scalar(0));
cv::Mat single_dust_ground_img = ground_depth_map.clone();
cv::inRange(single_dust_ground_img, 0, 1, single_dust_ground_img);
cv::Mat dust_element = getStructuringElement(
cv::MORPH_RECT, cv::Size(2 * dust_kernel_size_ + 1, 2 * dust_kernel_size_ + 1),
cv::Point(-1, -1));
cv::dilate(single_dust_ground_img, single_dust_ground_img, dust_element);
cv::erode(single_dust_ground_img, single_dust_ground_img, dust_element);
cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img);
cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1);
cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img);
cv::Mat binarized_dust_mask_(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
cv::Mat multi_frame_dust_mask(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
cv::Mat multi_frame_ground_dust_result(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
if (enable_dust_diag_) {

Check warning on line 295 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L295

Added line #L295 was not covered by tests
cv::Mat ground_depth_map = lidar_depth_map_8u(
cv::Rect(0, horizontal_ring_id_, ideal_horizontal_bins, vertical_bins - horizontal_ring_id_));
cv::Mat sky_blank(horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0));

Check warning on line 298 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L297-L298

Added lines #L297 - L298 were not covered by tests
cv::Mat ground_blank(
vertical_bins - horizontal_ring_id_, ideal_horizontal_bins, CV_8UC1, cv::Scalar(0));

Check warning on line 300 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L300

Added line #L300 was not covered by tests
cv::Mat single_dust_img(
cv::Size(lidar_depth_map_8u.rows, lidar_depth_map_8u.cols), CV_8UC1, cv::Scalar(0));
cv::Mat single_dust_ground_img = ground_depth_map.clone();
cv::inRange(single_dust_ground_img, 0, 1, single_dust_ground_img);

Check warning on line 304 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L302-L304

Added lines #L302 - L304 were not covered by tests
cv::Mat dust_element = getStructuringElement(
cv::MORPH_RECT, cv::Size(2 * dust_kernel_size_ + 1, 2 * dust_kernel_size_ + 1),
cv::Point(-1, -1));
cv::dilate(single_dust_ground_img, single_dust_ground_img, dust_element);
cv::erode(single_dust_ground_img, single_dust_ground_img, dust_element);
cv::inRange(single_dust_ground_img, 254, 255, single_dust_ground_img);
cv::Mat ground_mask(cv::Size(ideal_horizontal_bins, horizontal_ring_id_), CV_8UC1);
cv::vconcat(sky_blank, single_dust_ground_img, single_dust_img);

Check warning on line 312 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L306-L312

Added lines #L306 - L312 were not covered by tests

if (dust_buffering_interval_ == 0) {
single_dust_img.copyTo(multi_frame_ground_dust_result);
dust_buffering_frame_counter_ = 0;
} else {
binarized_dust_mask_ = single_dust_img / 255;
if (dust_buffering_frame_counter_ >= dust_buffering_interval_) {
dust_mask_buffer.push_back(binarized_dust_mask_);
dust_buffering_frame_counter_ = 0;
tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg;
ground_dust_ratio_ = static_cast<float>(cv::countNonZero(single_dust_ground_img)) /
(single_dust_ground_img.cols * single_dust_ground_img.rows);
ground_dust_ratio_msg.data = ground_dust_ratio_;
ground_dust_ratio_msg.stamp = now();
ground_dust_ratio_pub_->publish(ground_dust_ratio_msg);
if (ground_dust_ratio_ > dust_ratio_threshold_) {
if (dust_frame_count_ < 2 * dust_count_threshold_) {
dust_frame_count_++;

Check warning on line 322 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L315-L322

Added lines #L315 - L322 were not covered by tests
}
} else {
dust_buffering_frame_counter_++;
}
for (const auto & binarized_dust_mask : dust_mask_buffer) {
multi_frame_dust_mask += binarized_dust_mask;
dust_frame_count_ = 0;

Check warning on line 325 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L325

Added line #L325 was not covered by tests
}
cv::inRange(
multi_frame_dust_mask, dust_mask_buffer.size() - 1, dust_mask_buffer.size(),
multi_frame_ground_dust_result);
}
cv::Mat single_frame_ground_dust_colorized(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));
cv::applyColorMap(single_dust_img, single_frame_ground_dust_colorized, cv::COLORMAP_JET);
cv::Mat multi_frame_ground_dust_colorized;
cv::Mat blockage_dust_merged_img(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));
cv::Mat blockage_dust_merged_mask(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
blockage_dust_merged_img.setTo(
cv::Vec3b(0, 0, 255), time_series_blockage_result); // red:blockage
blockage_dust_merged_img.setTo(
cv::Vec3b(0, 255, 255), multi_frame_ground_dust_result); // yellow:dust
sensor_msgs::msg::Image::SharedPtr single_frame_dust_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", single_frame_ground_dust_colorized)
.toImageMsg();
single_frame_dust_mask_pub.publish(single_frame_dust_mask_msg);
sensor_msgs::msg::Image::SharedPtr multi_frame_dust_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", multi_frame_ground_dust_colorized)
.toImageMsg();
multi_frame_dust_mask_pub.publish(multi_frame_dust_mask_msg);
sensor_msgs::msg::Image::SharedPtr lidar_depth_map_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "mono16", full_size_depth_map).toImageMsg();
lidar_depth_map_msg->header = input->header;
lidar_depth_map_pub_.publish(lidar_depth_map_msg);
cv::Mat blockage_mask_colorized;
cv::applyColorMap(time_series_blockage_result, blockage_mask_colorized, cv::COLORMAP_JET);
sensor_msgs::msg::Image::SharedPtr blockage_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_mask_colorized).toImageMsg();
blockage_mask_msg->header = input->header;
blockage_mask_pub_.publish(blockage_mask_msg);
cv::Mat blockage_dust_merged_colorized(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));
blockage_dust_merged_img.copyTo(blockage_dust_merged_colorized);
sensor_msgs::msg::Image::SharedPtr blockage_dust_merged_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_dust_merged_colorized)
.toImageMsg();
if (ground_dust_ratio_ > dust_ratio_threshold_) {
if (dust_frame_count_ < 2 * dust_count_threshold_) {
dust_frame_count_++;

if (publish_debug_image_) {

Check warning on line 328 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L328

Added line #L328 was not covered by tests
cv::Mat binarized_dust_mask_(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));

Check warning on line 330 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L330

Added line #L330 was not covered by tests
cv::Mat multi_frame_dust_mask(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));

Check warning on line 332 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L332

Added line #L332 was not covered by tests
cv::Mat multi_frame_ground_dust_result(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));

Check warning on line 334 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L334

Added line #L334 was not covered by tests

if (dust_buffering_interval_ == 0) {
single_dust_img.copyTo(multi_frame_ground_dust_result);
dust_buffering_frame_counter_ = 0;

Check warning on line 338 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L336-L338

Added lines #L336 - L338 were not covered by tests
} else {
binarized_dust_mask_ = single_dust_img / 255;
if (dust_buffering_frame_counter_ >= dust_buffering_interval_) {
dust_mask_buffer.push_back(binarized_dust_mask_);
dust_buffering_frame_counter_ = 0;

Check warning on line 343 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L340-L343

Added lines #L340 - L343 were not covered by tests
} else {
dust_buffering_frame_counter_++;

Check warning on line 345 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L345

Added line #L345 was not covered by tests
}
for (const auto & binarized_dust_mask : dust_mask_buffer) {
multi_frame_dust_mask += binarized_dust_mask;

Check warning on line 348 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L347-L348

Added lines #L347 - L348 were not covered by tests
}
cv::inRange(
multi_frame_dust_mask, dust_mask_buffer.size() - 1, dust_mask_buffer.size(),

Check warning on line 351 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L350-L351

Added lines #L350 - L351 were not covered by tests
multi_frame_ground_dust_result);
}
cv::Mat single_frame_ground_dust_colorized(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));
cv::applyColorMap(single_dust_img, single_frame_ground_dust_colorized, cv::COLORMAP_JET);
cv::Mat multi_frame_ground_dust_colorized;

Check warning on line 357 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L355-L357

Added lines #L355 - L357 were not covered by tests
cv::Mat blockage_dust_merged_img(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));

Check warning on line 359 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L359

Added line #L359 was not covered by tests
cv::Mat blockage_dust_merged_mask(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));
blockage_dust_merged_img.setTo(
cv::Vec3b(0, 0, 255), time_series_blockage_result); // red:blockage
blockage_dust_merged_img.setTo(
cv::Vec3b(0, 255, 255), multi_frame_ground_dust_result); // yellow:dust

Check warning on line 365 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L361-L365

Added lines #L361 - L365 were not covered by tests
sensor_msgs::msg::Image::SharedPtr single_frame_dust_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", single_frame_ground_dust_colorized)
.toImageMsg();
single_frame_dust_mask_pub.publish(single_frame_dust_mask_msg);

Check warning on line 369 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L367-L369

Added lines #L367 - L369 were not covered by tests
sensor_msgs::msg::Image::SharedPtr multi_frame_dust_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", multi_frame_ground_dust_colorized)
.toImageMsg();
multi_frame_dust_mask_pub.publish(multi_frame_dust_mask_msg);

Check warning on line 373 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L371-L373

Added lines #L371 - L373 were not covered by tests
cv::Mat blockage_dust_merged_colorized(
cv::Size(ideal_horizontal_bins, vertical_bins), CV_8UC3, cv::Scalar(0, 0, 0));
blockage_dust_merged_img.copyTo(blockage_dust_merged_colorized);

Check warning on line 376 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L375-L376

Added lines #L375 - L376 were not covered by tests
sensor_msgs::msg::Image::SharedPtr blockage_dust_merged_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_dust_merged_colorized)
.toImageMsg();

Check warning on line 379 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L378-L379

Added lines #L378 - L379 were not covered by tests
blockage_dust_merged_msg->header = input->header;
blockage_dust_merged_pub.publish(blockage_dust_merged_msg);

Check warning on line 381 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L381

Added line #L381 was not covered by tests
}
} else {
dust_frame_count_ = 0;
}
blockage_dust_merged_msg->header = input->header;
blockage_dust_merged_pub.publish(blockage_dust_merged_msg);

tier4_debug_msgs::msg::Float32Stamped ground_blockage_ratio_msg;
ground_blockage_ratio_msg.data = ground_blockage_ratio_;
Expand All @@ -380,14 +391,19 @@
sky_blockage_ratio_msg.data = sky_blockage_ratio_;
sky_blockage_ratio_msg.stamp = now();
sky_blockage_ratio_pub_->publish(sky_blockage_ratio_msg);
tier4_debug_msgs::msg::Float32Stamped blockage_ratio_msg;
tier4_debug_msgs::msg::Float32Stamped ground_dust_ratio_msg;
if (publish_debug_image_) {

Check warning on line 394 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L394

Added line #L394 was not covered by tests
sensor_msgs::msg::Image::SharedPtr lidar_depth_map_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "mono16", full_size_depth_map).toImageMsg();

Check warning on line 396 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L396

Added line #L396 was not covered by tests
lidar_depth_map_msg->header = input->header;
lidar_depth_map_pub_.publish(lidar_depth_map_msg);
cv::Mat blockage_mask_colorized;
cv::applyColorMap(time_series_blockage_result, blockage_mask_colorized, cv::COLORMAP_JET);

Check warning on line 400 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L398-L400

Added lines #L398 - L400 were not covered by tests
sensor_msgs::msg::Image::SharedPtr blockage_mask_msg =
cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", blockage_mask_colorized).toImageMsg();

Check warning on line 402 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L402

Added line #L402 was not covered by tests
blockage_mask_msg->header = input->header;
blockage_mask_pub_.publish(blockage_mask_msg);
}

Check warning on line 405 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp#L404-L405

Added lines #L404 - L405 were not covered by tests

Check warning on line 406 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

BlockageDiagComponent::filter increases in cyclomatic complexity from 24 to 27, 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 406 in sensing/pointcloud_preprocessor/src/blockage_diag/blockage_diag_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Bumpy Road Ahead

BlockageDiagComponent::filter increases from 7 to 8 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
ground_dust_ratio_ = static_cast<float>(cv::countNonZero(single_dust_ground_img)) /
(single_dust_ground_img.cols * single_dust_ground_img.rows);
ground_dust_ratio_msg.data = ground_dust_ratio_;
ground_dust_ratio_msg.stamp = now();
ground_dust_ratio_pub_->publish(ground_dust_ratio_msg);
pcl::toROSMsg(*pcl_input, output);
output.header = input->header;
}
Expand Down
Loading