File tree 1 file changed +2
-7
lines changed
perception/autoware_euclidean_cluster/lib
1 file changed +2
-7
lines changed Original file line number Diff line number Diff line change @@ -65,7 +65,7 @@ void VoxelGridBasedEuclideanCluster::publishDiagnosticsSummary(
65
65
diagnostics_interface_ptr_->add_key_value (" is_cluster_data_size_within_range" , true );
66
66
}
67
67
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) ,
69
69
summary.str ());
70
70
diagnostics_interface_ptr_->publish (pointcloud_msg->header .stamp );
71
71
}
@@ -175,16 +175,11 @@ bool VoxelGridBasedEuclideanCluster::cluster(
175
175
// Cluster size is below the minimum threshold; skip without messaging.
176
176
continue ;
177
177
}
178
- if (cluster_size > max_cluster_size_ / 10 ) {
178
+ if (cluster_size > max_cluster_size_ ) {
179
179
// Cluster size exceeds the maximum threshold; log a warning.
180
180
warning_messages.push_back (" Cluster " + std::to_string (i) + " (" + std::to_string (cluster_size) + " )." );
181
181
continue ;
182
182
}
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
- // }
188
183
const auto & cluster = temporary_clusters.at (i);
189
184
tier4_perception_msgs::msg::DetectedObjectWithFeature feature_object;
190
185
feature_object.feature .cluster = cluster;
You can’t perform that action at this time.
0 commit comments