Skip to content

Commit

Permalink
fix(ground_segmentation): fix bug (autowarefoundation#7771)
Browse files Browse the repository at this point in the history
  • Loading branch information
miursh authored and badai-nguyen committed Jul 3, 2024
1 parent a5d785b commit 3332ef8
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 3 deletions.
1 change: 1 addition & 0 deletions launch/tier4_perception_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<exec_depend>detected_object_feature_remover</exec_depend>
<exec_depend>detected_object_validation</exec_depend>
<exec_depend>detection_by_tracker</exec_depend>
<exec_depend>elevation_map_loader</exec_depend>
<exec_depend>euclidean_cluster</exec_depend>
<exec_depend>ground_segmentation</exec_depend>
<exec_depend>image_projection_based_fusion</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -292,12 +292,13 @@ void RANSACGroundFilterComponent::filter(
no_ground_cloud_msg_ptr->header = input->header;
no_ground_cloud_msg_ptr->fields = input->fields;
no_ground_cloud_msg_ptr->point_step = point_step;
no_ground_cloud_msg_ptr->data.resize(input->data.size());
size_t output_size = 0;
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
for (size_t global_size = 0; global_size < input->data.size(); global_size += point_step) {
float x = *reinterpret_cast<float *>(input->data[global_size + x_offset]);
float y = *reinterpret_cast<float *>(input->data[global_size + y_offset]);
float z = *reinterpret_cast<float *>(input->data[global_size + z_offset]);
float x = *reinterpret_cast<const float *>(&input->data[global_size + x_offset]);
float y = *reinterpret_cast<const float *>(&input->data[global_size + y_offset]);
float z = *reinterpret_cast<const float *>(&input->data[global_size + z_offset]);
const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z);
if (std::abs(transformed_point.z()) > height_threshold_) {
std::memcpy(
Expand Down

0 comments on commit 3332ef8

Please sign in to comment.