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): add intensity field #6791

Merged
Original file line number Diff line number Diff line change
Expand Up @@ -186,15 +186,16 @@ class RayGroundFilterComponent : public pointcloud_preprocessor::Filter
* @param out_removed_indices_cloud_ptr Resulting PointCloud with the indices removed
*/
void ExtractPointsIndices(
const pcl::PointCloud<PointType_>::Ptr in_cloud_ptr, const pcl::PointIndices & in_indices,
pcl::PointCloud<PointType_>::Ptr out_only_indices_cloud_ptr,
pcl::PointCloud<PointType_>::Ptr out_removed_indices_cloud_ptr);
const PointCloud2::ConstSharedPtr in_cloud_ptr, pcl::PointIndices & in_indices,
PointCloud2::SharedPtr out_only_indices_cloud_ptr,
PointCloud2::SharedPtr out_removed_indices_cloud_ptr);

boost::optional<float> calcPointVehicleIntersection(const Point & point);

void setVehicleFootprint(
const double min_x, const double max_x, const double min_y, const double max_y);

void initializePointCloud2(
const PointCloud2::ConstSharedPtr & in_cloud_ptr, PointCloud2::SharedPtr & out_cloud_msg_ptr);
/** \brief Parameter service callback result : needed to be hold */
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -284,19 +284,36 @@
const Eigen::Affine3d plane_affine = getPlaneAffine(*segment_ground_cloud_ptr, plane_normal);
pcl::PointCloud<PointType>::Ptr no_ground_cloud_ptr(new pcl::PointCloud<PointType>);

int x_offset = input->fields[pcl::getFieldIndex(*input, "x")].offset;
int y_offset = input->fields[pcl::getFieldIndex(*input, "y")].offset;
int z_offset = input->fields[pcl::getFieldIndex(*input, "z")].offset;
int point_step = input->point_step;

sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr(
new sensor_msgs::msg::PointCloud2);
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;
size_t output_size = 0;
// use not downsampled pointcloud for extract pointcloud that higher than height threshold
for (const auto & p : current_sensor_cloud_ptr->points) {
const Eigen::Vector3d transformed_point =
plane_affine.inverse() * Eigen::Vector3d(p.x, p.y, p.z);
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]);
const Eigen::Vector3d transformed_point = plane_affine.inverse() * Eigen::Vector3d(x, y, z);
if (std::abs(transformed_point.z()) > height_threshold_) {
no_ground_cloud_ptr->points.push_back(p);
std::memcpy(
&no_ground_cloud_msg_ptr->data[output_size], &input->data[global_size], point_step);
output_size += point_step;
Comment on lines +300 to +307
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The node crashes here, so please fix it.

}
}
no_ground_cloud_msg_ptr->data.resize(output_size);
no_ground_cloud_msg_ptr->height = input->height;
no_ground_cloud_msg_ptr->width = output_size / point_step / input->height;
no_ground_cloud_msg_ptr->row_step = output_size / input->height;
no_ground_cloud_msg_ptr->is_dense = input->is_dense;
no_ground_cloud_msg_ptr->is_bigendian = input->is_bigendian;

Check warning on line 316 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 77 to 93 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.
sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr(
new sensor_msgs::msg::PointCloud2);
pcl::toROSMsg(*no_ground_cloud_ptr, *no_ground_cloud_msg_ptr);
no_ground_cloud_msg_ptr->header = input->header;
sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_transformed_msg_ptr(
new sensor_msgs::msg::PointCloud2);
if (!transformPointCloud(
Expand Down
64 changes: 47 additions & 17 deletions perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.25 to 5.33, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -257,20 +257,53 @@
// return (true);
// }

void RayGroundFilterComponent::ExtractPointsIndices(
const pcl::PointCloud<PointType_>::Ptr in_cloud_ptr, const pcl::PointIndices & in_indices,
pcl::PointCloud<PointType_>::Ptr out_only_indices_cloud_ptr,
pcl::PointCloud<PointType_>::Ptr out_removed_indices_cloud_ptr)
void RayGroundFilterComponent::initializePointCloud2(
const PointCloud2::ConstSharedPtr & in_cloud_ptr, PointCloud2::SharedPtr & out_cloud_msg_ptr)
{
pcl::ExtractIndices<PointType_> extract_ground;
extract_ground.setInputCloud(in_cloud_ptr);
extract_ground.setIndices(pcl::make_shared<pcl::PointIndices>(in_indices));

extract_ground.setNegative(false); // true removes the indices, false leaves only the indices
extract_ground.filter(*out_only_indices_cloud_ptr);
out_cloud_msg_ptr->header = in_cloud_ptr->header;
out_cloud_msg_ptr->height = in_cloud_ptr->height;
out_cloud_msg_ptr->fields = in_cloud_ptr->fields;
out_cloud_msg_ptr->is_bigendian = in_cloud_ptr->is_bigendian;
out_cloud_msg_ptr->point_step = in_cloud_ptr->point_step;
out_cloud_msg_ptr->is_dense = in_cloud_ptr->is_dense;
out_cloud_msg_ptr->data.resize(in_cloud_ptr->data.size());
}

extract_ground.setNegative(true); // true removes the indices, false leaves only the indices
extract_ground.filter(*out_removed_indices_cloud_ptr);
void RayGroundFilterComponent::ExtractPointsIndices(
YoshiRi marked this conversation as resolved.
Show resolved Hide resolved
const PointCloud2::ConstSharedPtr in_cloud_ptr, pcl::PointIndices & in_indices,
PointCloud2::SharedPtr ground_cloud_msg_ptr, PointCloud2::SharedPtr no_ground_cloud_msg_ptr)
{
initializePointCloud2(in_cloud_ptr, ground_cloud_msg_ptr);
initializePointCloud2(in_cloud_ptr, no_ground_cloud_msg_ptr);
int point_step = in_cloud_ptr->point_step;
size_t ground_count = 0;
size_t no_ground_count = 0;
std::vector<bool> is_ground_idx(in_cloud_ptr->width, false);
for (const auto & idx : in_indices.indices) {
if (std::size_t(idx) >= is_ground_idx.size()) {
continue;
}
is_ground_idx[idx] = true;
}
for (size_t i = 0; i < is_ground_idx.size(); ++i) {
if (is_ground_idx[i]) {
std::memcpy(
&ground_cloud_msg_ptr->data[ground_count * point_step], &in_cloud_ptr->data[i * point_step],
point_step);
ground_count++;
} else {
std::memcpy(
&no_ground_cloud_msg_ptr->data[no_ground_count * point_step],
&in_cloud_ptr->data[i * point_step], point_step);
no_ground_count++;
}
}
ground_cloud_msg_ptr->data.resize(ground_count * point_step);
no_ground_cloud_msg_ptr->data.resize(no_ground_count * point_step);
ground_cloud_msg_ptr->width = ground_count;
no_ground_cloud_msg_ptr->width = no_ground_count;
ground_cloud_msg_ptr->row_step = ground_count * point_step;
no_ground_cloud_msg_ptr->row_step = no_ground_count * point_step;

Check warning on line 306 in perception/ground_segmentation/src/ray_ground_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

RayGroundFilterComponent::ExtractPointsIndices has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
}

void RayGroundFilterComponent::filter(
Expand Down Expand Up @@ -299,14 +332,11 @@
pcl::PointCloud<PointType_>::Ptr no_ground_cloud_ptr(new pcl::PointCloud<PointType_>);
pcl::PointCloud<pcl::PointXYZRGB>::Ptr radials_cloud_ptr(new pcl::PointCloud<pcl::PointXYZRGB>);

ExtractPointsIndices(
current_sensor_cloud_ptr, ground_indices, ground_cloud_ptr, no_ground_cloud_ptr);

sensor_msgs::msg::PointCloud2::SharedPtr no_ground_cloud_msg_ptr(
new sensor_msgs::msg::PointCloud2);
pcl::toROSMsg(*no_ground_cloud_ptr, *no_ground_cloud_msg_ptr);
no_ground_cloud_msg_ptr->header = input->header;
sensor_msgs::msg::PointCloud2::SharedPtr ground_cloud_msg_ptr(new sensor_msgs::msg::PointCloud2);

ExtractPointsIndices(input, ground_indices, ground_cloud_msg_ptr, no_ground_cloud_msg_ptr);
output = *no_ground_cloud_msg_ptr;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -581,8 +581,6 @@ void ScanGroundFilterComponent::extractObjectPoints(
std::memcpy(
&out_object_cloud.data[output_data_size], &in_cloud_ptr->data[i * in_cloud_ptr->point_step],
in_cloud_ptr->point_step * sizeof(uint8_t));
*reinterpret_cast<float *>(&out_object_cloud.data[output_data_size + intensity_offset_]) =
1; // set intensity to 1
output_data_size += in_cloud_ptr->point_step;
}
}
Expand Down Expand Up @@ -612,7 +610,7 @@ void ScanGroundFilterComponent::faster_filter(
output.row_step = no_ground_indices.indices.size() * input->point_step;
output.data.resize(output.row_step);
output.width = no_ground_indices.indices.size();
output.fields.assign(input->fields.begin(), input->fields.begin() + 3);
output.fields = input->fields;
output.is_dense = true;
output.height = input->height;
output.is_bigendian = input->is_bigendian;
Expand Down
Loading