Skip to content

Commit 9f70a47

Browse files
style(pre-commit): autofix
1 parent 7739960 commit 9f70a47

File tree

1 file changed

+6
-4
lines changed

1 file changed

+6
-4
lines changed

perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -55,14 +55,16 @@ void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary(
5555
diagnostics_interface_ptr_->clear();
5656
std::string summary;
5757
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_);
6061
diagnostics_interface_ptr_->add_key_value("is_cluster_data_size_within_range", false);
6162
} else {
6263
diagnostics_interface_ptr_->add_key_value("is_cluster_data_size_within_range", true);
6364
}
6465
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),
6668
summary);
6769
diagnostics_interface_ptr_->publish(pointcloud_msg->header.stamp);
6870
}
@@ -198,7 +200,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
198200
}
199201
objects.header = pointcloud_msg->header;
200202
// Publish the diagnostics summary.
201-
publishDiagnosticsSummary(skipped_cluster_count, pointcloud_msg);
203+
publishDiagnosticsSummary(skipped_cluster_count, pointcloud_msg);
202204
}
203205

204206
return true;

0 commit comments

Comments
 (0)