Skip to content

Commit a5ef9bb

Browse files
author
lei.gu
committed
remove temporary code
1 parent aa613d4 commit a5ef9bb

File tree

1 file changed

+2
-7
lines changed

1 file changed

+2
-7
lines changed

perception/autoware_euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp

+2-7
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary(
6565
diagnostics_interface_ptr_->add_key_value("is_cluster_data_size_within_range", true);
6666
}
6767
diagnostics_interface_ptr_->update_level_and_message(
68-
warnings.empty() ? diagnostic_msgs::msg::DiagnosticStatus::OK : diagnostic_msgs::msg::DiagnosticStatus::WARN,
68+
warnings.empty() ? static_cast<int8_t>(diagnostic_msgs::msg::DiagnosticStatus::OK) : static_cast<int8_t>(diagnostic_msgs::msg::DiagnosticStatus::WARN),
6969
summary.str());
7070
diagnostics_interface_ptr_->publish(pointcloud_msg->header.stamp);
7171
}
@@ -175,16 +175,11 @@ bool VoxelGridBasedEuclideanCluster::cluster(
175175
// Cluster size is below the minimum threshold; skip without messaging.
176176
continue;
177177
}
178-
if (cluster_size > max_cluster_size_ /10) {
178+
if (cluster_size > max_cluster_size_ ) {
179179
// Cluster size exceeds the maximum threshold; log a warning.
180180
warning_messages.push_back(" Cluster " + std::to_string(i) + " (" + std::to_string(cluster_size) + ").");
181181
continue;
182182
}
183-
184-
// if (!(min_cluster_size_ <= static_cast<int>(i_cluster_data_size / point_step) &&
185-
// static_cast<int>(i_cluster_data_size / point_step) <= max_cluster_size_)) {
186-
// continue;
187-
// }
188183
const auto & cluster = temporary_clusters.at(i);
189184
tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object;
190185
feature_object.feature.cluster = cluster;

0 commit comments

Comments
 (0)