Skip to content

Commit a28bbd2

Browse files
badai-nguyenbeginningfanpre-commit-ci[bot]miursh
authored
fix(euclidean_cluster, ground_segmentation): cherry-pick bug fix PRs (#1378)
* fix(euclidean_cluster): fix euclidean cluster params (autowarefoundation#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> * fix(euclidean_cluster): fix max_cluster_size bug (autowarefoundation#7734) Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix(ground_segmentation): fix bug (autowarefoundation#7771) --------- Signed-off-by: beginningfan <beginning.fan@autocore.ai> Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: beginningfan <103237402+beginningfan@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com>
1 parent 4cc01c3 commit a28bbd2

File tree

3 files changed

+11
-5
lines changed

3 files changed

+11
-5
lines changed

Diff for: launch/tier4_perception_launch/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
<exec_depend>detected_object_feature_remover</exec_depend>
2020
<exec_depend>detected_object_validation</exec_depend>
2121
<exec_depend>detection_by_tracker</exec_depend>
22+
<exec_depend>elevation_map_loader</exec_depend>
2223
<exec_depend>euclidean_cluster</exec_depend>
2324
<exec_depend>ground_segmentation</exec_depend>
2425
<exec_depend>image_projection_based_fusion</exec_depend>

Diff for: perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp

+6-2
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

@@ -117,13 +117,17 @@ bool VoxelGridBasedEuclideanCluster::cluster(
117117
voxel_grid_.getCentroidIndexAt(voxel_grid_.getGridCoordinates(point.x, point.y, point.z));
118118
if (map.find(index) != map.end()) {
119119
auto & cluster_data_size = clusters_data_size.at(map[index]);
120-
if (cluster_data_size + point_step > std::size_t(max_cluster_size_ * point_step)) {
120+
if (cluster_data_size > std::size_t(max_cluster_size_ * point_step)) {
121121
continue;
122122
}
123123
std::memcpy(
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

Diff for: perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter(
292292
no_ground_cloud_msg_ptr->header = input->header;
293293
no_ground_cloud_msg_ptr->fields = input->fields;
294294
no_ground_cloud_msg_ptr->point_step = point_step;
295+
no_ground_cloud_msg_ptr->data.resize(input->data.size());
295296
size_t output_size = 0;
296297
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
297298
for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) {
298-
float x = *reinterpret_cast<float *>(input->data[global_size + x_offset]);
299-
float y = *reinterpret_cast<float *>(input->data[global_size + y_offset]);
300-
float z = *reinterpret_cast<float *>(input->data[global_size + z_offset]);
299+
float x = *reinterpret_cast<const float *>(&input->data[global_size + x_offset]);
300+
float y = *reinterpret_cast<const float *>(&input->data[global_size + y_offset]);
301+
float z = *reinterpret_cast<const float *>(&input->data[global_size + z_offset]);
301302
const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z);
302303
if (std::abs(transformed_point.z()) > height_threshold_) {
303304
std::memcpy(

0 commit comments

Comments
 (0)