@@ -55,14 +55,16 @@ void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary(
55
55
diagnostics_interface_ptr_->clear ();
56
56
std::string summary;
57
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_);
58
+ summary = std::to_string (skipped_cluster_count) +
59
+ " clusters skipped because cluster point size exceeds the maximum allowed " +
60
+ std::to_string (max_cluster_size_);
60
61
diagnostics_interface_ptr_->add_key_value (" is_cluster_data_size_within_range" , false );
61
62
} else {
62
63
diagnostics_interface_ptr_->add_key_value (" is_cluster_data_size_within_range" , true );
63
64
}
64
65
diagnostics_interface_ptr_->update_level_and_message (
65
- skipped_cluster_count > 0 ? static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::WARN) : static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::OK),
66
+ skipped_cluster_count > 0 ? static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::WARN)
67
+ : static_cast <int8_t >(diagnostic_msgs::msg::DiagnosticStatus::OK),
66
68
summary);
67
69
diagnostics_interface_ptr_->publish (pointcloud_msg->header .stamp );
68
70
}
@@ -198,7 +200,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
198
200
}
199
201
objects.header = pointcloud_msg->header ;
200
202
// Publish the diagnostics summary.
201
- publishDiagnosticsSummary (skipped_cluster_count, pointcloud_msg);
203
+ publishDiagnosticsSummary (skipped_cluster_count, pointcloud_msg);
202
204
}
203
205
204
206
return true ;
0 commit comments