-
Notifications
You must be signed in to change notification settings - Fork 701
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
feat(euclidean_cluster): add diagnostics warning when cluster skipped #10278
base: main
Are you sure you want to change the base?
Changes from 3 commits
aa613d4
a5ef9bb
ac9620a
7739960
9f70a47
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||
---|---|---|---|---|---|---|---|---|---|---|
|
@@ -14,6 +14,8 @@ | |||||||||
|
||||||||||
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp" | ||||||||||
|
||||||||||
#include <rclcpp/node.hpp> | ||||||||||
|
||||||||||
#include <pcl/kdtree/kdtree.h> | ||||||||||
#include <pcl/segmentation/extract_clusters.h> | ||||||||||
|
||||||||||
|
@@ -41,6 +43,36 @@ | |||||||||
min_points_number_per_voxel_(min_points_number_per_voxel) | ||||||||||
{ | ||||||||||
} | ||||||||||
|
||||||||||
// After processing all clusters, publish a summary of diagnostics. | ||||||||||
void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary( | ||||||||||
const std::vector<std::string> & warnings, | ||||||||||
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud_msg) | ||||||||||
{ | ||||||||||
if (!diagnostics_interface_ptr_) { | ||||||||||
return; | ||||||||||
} | ||||||||||
diagnostics_interface_ptr_->clear(); | ||||||||||
|
||||||||||
std::stringstream summary; | ||||||||||
if (!warnings.empty()) { | ||||||||||
summary << warnings.size() | ||||||||||
<< " clusters skipped because cluster size exceeds the maximum allowed " | ||||||||||
<< max_cluster_size_ << " \n"; | ||||||||||
for (const auto & warn : warnings) { | ||||||||||
summary << " - " << warn << "\n"; | ||||||||||
} | ||||||||||
diagnostics_interface_ptr_->add_key_value("is_cluster_data_size_within_range", false); | ||||||||||
} else { | ||||||||||
diagnostics_interface_ptr_->add_key_value("is_cluster_data_size_within_range", true); | ||||||||||
} | ||||||||||
diagnostics_interface_ptr_->update_level_and_message( | ||||||||||
warnings.empty() ? static_cast<int8_t>(diagnostic_msgs::msg::DiagnosticStatus::OK) | ||||||||||
: static_cast<int8_t>(diagnostic_msgs::msg::DiagnosticStatus::WARN), | ||||||||||
summary.str()); | ||||||||||
diagnostics_interface_ptr_->publish(pointcloud_msg->header.stamp); | ||||||||||
} | ||||||||||
|
||||||||||
// TODO(badai-nguyen): remove this function when field copying also implemented for | ||||||||||
// euclidean_cluster.cpp | ||||||||||
bool VoxelGridBasedEuclideanCluster::cluster( | ||||||||||
|
@@ -136,34 +168,45 @@ | |||||||||
|
||||||||||
// build output and check cluster size | ||||||||||
{ | ||||||||||
// At the start, create a container to collect warnings. | ||||||||||
std::vector<std::string> warning_messages; | ||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||||||
for (size_t i = 0; i < temporary_clusters.size(); ++i) { | ||||||||||
auto & i_cluster_data_size = clusters_data_size.at(i); | ||||||||||
if (!(min_cluster_size_ <= static_cast<int>(i_cluster_data_size / point_step) && | ||||||||||
static_cast<int>(i_cluster_data_size / point_step) <= max_cluster_size_)) { | ||||||||||
int cluster_size = static_cast<int>(i_cluster_data_size / point_step); | ||||||||||
if (cluster_size < min_cluster_size_) { | ||||||||||
// Cluster size is below the minimum threshold; skip without messaging. | ||||||||||
continue; | ||||||||||
} | ||||||||||
if (cluster_size > max_cluster_size_) { | ||||||||||
// Cluster size exceeds the maximum threshold; log a warning. | ||||||||||
warning_messages.push_back( | ||||||||||
" Cluster " + std::to_string(i) + " (" + std::to_string(cluster_size) + ")."); | ||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Indicate current maximum value to user. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The diagnostics messages are modified in the latest commit as the following reasons
|
||||||||||
continue; | ||||||||||
} | ||||||||||
const auto & cluster = temporary_clusters.at(i); | ||||||||||
tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object; | ||||||||||
feature_object.feature.cluster = cluster; | ||||||||||
feature_object.feature.cluster.data.resize(i_cluster_data_size); | ||||||||||
feature_object.feature.cluster.header = pointcloud_msg->header; | ||||||||||
feature_object.feature.cluster.is_bigendian = pointcloud_msg->is_bigendian; | ||||||||||
feature_object.feature.cluster.is_dense = pointcloud_msg->is_dense; | ||||||||||
feature_object.feature.cluster.point_step = point_step; | ||||||||||
feature_object.feature.cluster.row_step = i_cluster_data_size / pointcloud_msg->height; | ||||||||||
feature_object.feature.cluster.width = | ||||||||||
i_cluster_data_size / point_step / pointcloud_msg->height; | ||||||||||
|
||||||||||
feature_object.object.kinematics.pose_with_covariance.pose.position = | ||||||||||
getCentroid(feature_object.feature.cluster); | ||||||||||
autoware_perception_msgs::msg::ObjectClassification classification; | ||||||||||
classification.label = autoware_perception_msgs::msg::ObjectClassification::UNKNOWN; | ||||||||||
classification.probability = 1.0f; | ||||||||||
feature_object.object.classification.emplace_back(classification); | ||||||||||
|
||||||||||
objects.feature_objects.push_back(feature_object); | ||||||||||
} | ||||||||||
objects.header = pointcloud_msg->header; | ||||||||||
|
||||||||||
publishDiagnosticsSummary(warning_messages, pointcloud_msg); | ||||||||||
Check warning on line 209 in perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp
|
||||||||||
} | ||||||||||
|
||||||||||
return true; | ||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Here is two option
diagnostics_cluster_max_size
or something similar.diagnostics_messages