Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(ground_segmentation): fix bug #7771

Merged
merged 5 commits into from
Jul 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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 @@
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]);

Check warning on line 301 in perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

RANSACGroundFilterComponent::filter increases from 93 to 94 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

Check warning on line 301 in perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp

View check run for this annotation

Codecov / codecov/patch

perception/ground_segmentation/src/ransac_ground_filter_nodelet.cpp#L300-L301

Added lines #L300 - L301 were not covered by tests
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
Loading