Skip to content

Commit 9df90bc

Browse files
fix(euclidean_cluster): fix euclidean cluster params (#7662)
* fix(euclidean_cluster): fix max and min cluster size Signed-off-by: beginningfan <beginning.fan@autocore.ai> * fix(gnss_poser): fix a typo Signed-off-by: beginningfan <beginning.fan@autocore.ai> * fix(euclidean_cluster): fix min cluster size Signed-off-by: beginningfan <beginning.fan@autocore.ai> * style(pre-commit): autofix --------- Signed-off-by: beginningfan <beginning.fan@autocore.ai> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 6029eae commit 9df90bc

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
106106
temporary_cluster.height = pointcloud_msg->height;
107107
temporary_cluster.fields = pointcloud_msg->fields;
108108
temporary_cluster.point_step = point_step;
109-
temporary_cluster.data.resize(max_cluster_size_ * point_step);
109+
temporary_cluster.data.resize(cluster.indices.size() * point_step);
110110
clusters_data_size.push_back(0);
111111
}
112112

@@ -124,6 +124,10 @@ bool VoxelGridBasedEuclideanCluster::cluster(
124124
&temporary_clusters.at(map[index]).data[cluster_data_size],
125125
&pointcloud_msg->data[i * point_step], point_step);
126126
cluster_data_size += point_step;
127+
if (cluster_data_size == temporary_clusters.at(map[index]).data.size()) {
128+
temporary_clusters.at(map[index])
129+
.data.resize(temporary_clusters.at(map[index]).data.size() * 2);
130+
}
127131
}
128132
}
129133

0 commit comments

Comments
 (0)