Skip to content

Commit

Permalink
fix(euclidean_cluster): fix max_cluster_size bug (#7734)
Browse files Browse the repository at this point in the history
Signed-off-by: badai-nguyen <[email protected]>
  • Loading branch information
badai-nguyen authored Jul 3, 2024
1 parent 7c97a6b commit 3763857
Showing 1 changed file with 1 addition and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
voxel_grid_.getCentroidIndexAt(voxel_grid_.getGridCoordinates(point.x, point.y, point.z));
if (map.find(index) != map.end()) {
auto & cluster_data_size = clusters_data_size.at(map[index]);
if (cluster_data_size + point_step > std::size_t(max_cluster_size_ * point_step)) {
if (cluster_data_size > std::size_t(max_cluster_size_ * point_step)) {
continue;
}
std::memcpy(
Expand Down

0 comments on commit 3763857

Please sign in to comment.