@@ -46,30 +46,24 @@ VoxelGridBasedEuclideanCluster::VoxelGridBasedEuclideanCluster(
46
46
47
47
// After processing all clusters, publish a summary of diagnostics.
48
48
void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary (
49
- const std::vector<std::string> & warnings ,
49
+ size_t skipped_cluster_count ,
50
50
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & pointcloud_msg)
51
51
{
52
52
if (!diagnostics_interface_ptr_) {
53
53
return ;
54
54
}
55
55
diagnostics_interface_ptr_->clear ();
56
-
57
- std::stringstream summary;
58
- if (!warnings.empty ()) {
59
- summary << warnings.size ()
60
- << " clusters skipped because cluster size exceeds the maximum allowed "
61
- << max_cluster_size_ << " \n " ;
62
- for (const auto & warn : warnings) {
63
- summary << " - " << warn << " \n " ;
64
- }
56
+ std::string summary;
57
+ if (skipped_cluster_count > 0 ) {
58
+ summary = std::to_string (skipped_cluster_count) + " clusters skipped because cluster point size exceeds the maximum allowed "
59
+ + std::to_string (max_cluster_size_);
65
60
diagnostics_interface_ptr_->add_key_value (" is_cluster_data_size_within_range" , false );
66
61
} else {
67
62
diagnostics_interface_ptr_->add_key_value (" is_cluster_data_size_within_range" , true );
68
63
}
69
64
diagnostics_interface_ptr_->update_level_and_message (
70
- warnings.empty () ? static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::OK)
71
- : static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::WARN),
72
- summary.str ());
65
+ skipped_cluster_count > 0 ? static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::WARN) : static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::OK),
66
+ summary);
73
67
diagnostics_interface_ptr_->publish (pointcloud_msg->header .stamp );
74
68
}
75
69
@@ -168,8 +162,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
168
162
169
163
// build output and check cluster size
170
164
{
171
- // At the start, create a container to collect warnings.
172
- std::vector<std::string> warning_messages;
165
+ size_t skipped_cluster_count = 0 ; // Count the skipped clusters
173
166
for (size_t i = 0 ; i < temporary_clusters.size (); ++i) {
174
167
auto & i_cluster_data_size = clusters_data_size.at (i);
175
168
int cluster_size = static_cast <int >(i_cluster_data_size / point_step);
@@ -179,8 +172,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
179
172
}
180
173
if (cluster_size > max_cluster_size_) {
181
174
// Cluster size exceeds the maximum threshold; log a warning.
182
- warning_messages.push_back (
183
- " Cluster " + std::to_string (i) + " (" + std::to_string (cluster_size) + " )." );
175
+ skipped_cluster_count++;
184
176
continue ;
185
177
}
186
178
const auto & cluster = temporary_clusters.at (i);
@@ -205,8 +197,8 @@ bool VoxelGridBasedEuclideanCluster::cluster(
205
197
objects.feature_objects .push_back (feature_object);
206
198
}
207
199
objects.header = pointcloud_msg->header ;
208
-
209
- publishDiagnosticsSummary (warning_messages, pointcloud_msg);
200
+ // Publish the diagnostics summary.
201
+ publishDiagnosticsSummary (skipped_cluster_count, pointcloud_msg);
210
202
}
211
203
212
204
return true ;
0 commit comments