Skip to content

Commit

Permalink
fix(euclidean_cluster): fix euclidean cluster params (#7662)
Browse files Browse the repository at this point in the history
* fix(euclidean_cluster): fix max and min cluster size

Signed-off-by: beginningfan <[email protected]>

* fix(gnss_poser): fix a typo

Signed-off-by: beginningfan <[email protected]>

* fix(euclidean_cluster): fix min cluster size

Signed-off-by: beginningfan <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: beginningfan <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
beginningfan and pre-commit-ci[bot] authored Jul 1, 2024
1 parent 6029eae commit 9df90bc
Showing 1 changed file with 5 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ bool VoxelGridBasedEuclideanCluster::cluster(
temporary_cluster.height = pointcloud_msg->height;
temporary_cluster.fields = pointcloud_msg->fields;
temporary_cluster.point_step = point_step;
temporary_cluster.data.resize(max_cluster_size_ * point_step);
temporary_cluster.data.resize(cluster.indices.size() * point_step);
clusters_data_size.push_back(0);
}

Expand All @@ -124,6 +124,10 @@ bool VoxelGridBasedEuclideanCluster::cluster(
&temporary_clusters.at(map[index]).data[cluster_data_size],
&pointcloud_msg->data[i * point_step], point_step);
cluster_data_size += point_step;
if (cluster_data_size == temporary_clusters.at(map[index]).data.size()) {
temporary_clusters.at(map[index])
.data.resize(temporary_clusters.at(map[index]).data.size() * 2);
}
}
}

Expand Down

0 comments on commit 9df90bc

Please sign in to comment.