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

feat(pointcloud_preprocessor): calculate visibility score in ring outlier filter #7011

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
56 changes: 48 additions & 8 deletions sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,40 @@ A method of operating scan in chronological order and removing noise based on th

![ring_outlier_filter](./image/outlier_filter-ring.drawio.svg)

Another feature of this node is that it calculates visibility score based on outlier pointcloud and publish score as a topic.

### visibility score calculation algorithm

The pointcloud is divided into vertical bins (rings) and horizontal bins (azimuth divisions).
The algorithm starts by splitting the input point cloud into separate rings based on the ring value of each point. Then, for each ring, it iterates through the points and calculates the frequency of points within each horizontal bin. The frequency is determined by incrementing a counter for the corresponding bin based on the point's azimuth value.
The frequency values are stored in a frequency image matrix, where each cell represents a specific ring and azimuth bin. After calculating the frequency image, the algorithm applies a noise threshold to create a binary image. Points with frequency values above the noise threshold are considered valid, while points below the threshold are considered noise.
Finally, the algorithm calculates the visibility score by counting the number of non-zero pixels in the frequency image and dividing it by the total number of pixels (vertical bins multiplied by horizontal bins).

```plantuml
@startuml
start
:Convert input point cloud to PCL format;
:Initialize vertical and horizontal bins;
:Split point cloud into rings;
while (For each ring) is (not empty)
:Calculate frequency of points in each azimuth bin;
:Update frequency image matrix;
endwhile
:Apply noise threshold to create binary image;
:Count non-zero pixels in frequency image;
:Calculate visibility score as complement of filled pixel ratio;
stop
@enduml
```

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).
Expand All @@ -22,14 +56,20 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref

### Core Parameters

| Name | Type | Default Value | Description |
| ---------------------------- | ------- | ------------- | -------------------------------------------------------------------------------------------------------- |
| `distance_ratio` | double | 1.03 | |
| `object_length_threshold` | double | 0.1 | |
| `num_points_threshold` | int | 4 | |
| `max_rings_num` | uint_16 | 128 | |
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud. Due to performance concerns, please set to false during experiments. |
| Name | Type | Default Value | Description |
| ---------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------- |
| `distance_ratio` | double | 1.03 | |
| `object_length_threshold` | double | 0.1 | |
| `num_points_threshold` | int | 4 | |
| `max_rings_num` | uint_16 | 128 | |
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments. |
| `min_azimuth_deg` | float | 0.0 | The left limit of azimuth for visibility score calculation |
| `max_azimuth_deg` | float | 360.0 | The right limit of azimuth for visibility score calculation |
| `max_distance` | float | 12.0 | The limit distance for visibility score calculation |
| `vertical_bins` | int | 128 | The number of vertical bin for visibility histogram |
| `horizontal_bins` | int | 36 | The number of horizontal bin for visibility histogram |
| `noise_threshold` | int | 2 | The threshold value for distinguishing noise from valid points in the frequency image |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,17 @@
#include "pointcloud_preprocessor/filter.hpp"
#include "pointcloud_preprocessor/transform_info.hpp"

#include <image_transport/image_transport.hpp>
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
#include <cv_bridge/cv_bridge.hpp>
#else
#include <cv_bridge/cv_bridge.h>
#endif

#include <memory>
#include <string>
#include <utility>
#include <vector>

Expand All @@ -42,6 +50,8 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output,
const TransformInfo & transform_info);

rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr visibility_pub_;

private:
/** \brief publisher of excluded pointcloud for debug reason. **/
rclcpp::Publisher<PointCloud2>::SharedPtr outlier_pointcloud_publisher_;
Expand All @@ -53,6 +63,15 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
size_t max_points_num_per_ring_;
bool publish_outlier_pointcloud_;

// for visibility score
int noise_threshold_;
int vertical_bins_;
int horizontal_bins_;

float min_azimuth_deg_;
float max_azimuth_deg_;
float max_distance_;

/** \brief Parameter service callback result : needed to be hold */
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

Expand All @@ -77,6 +96,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
void setUpPointCloudFormat(
const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size,
size_t num_fields);
float calculateVisibilityScore(const PointCloud2 & input);

public:
PCL_MAKE_ALIGNED_OPERATOR_NEW
Expand Down
1 change: 0 additions & 1 deletion sensing/pointcloud_preprocessor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_geometry</depend>
<depend>autoware_point_types</depend>
<depend>cgal</depend>
<depend>cv_bridge</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,16 +14,16 @@

#include "pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp"

#include "autoware_auto_geometry/common_3d.hpp"
#include "autoware_point_types/types.hpp"

#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <pcl/search/pcl_search.h>

#include <algorithm>
#include <vector>
namespace pointcloud_preprocessor
{
using autoware_point_types::PointXYZIRADRT;

RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions & options)
: Filter("RingOutlierFilter", options)
{
Expand All @@ -35,6 +35,8 @@
debug_publisher_ = std::make_unique<DebugPublisher>(this, "ring_outlier_filter");
outlier_pointcloud_publisher_ =
this->create_publisher<PointCloud2>("debug/ring_outlier_filter", 1);
visibility_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
"ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS());
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}
Expand All @@ -50,6 +52,13 @@
static_cast<size_t>(declare_parameter("max_points_num_per_ring", 4000));
publish_outlier_pointcloud_ =
static_cast<bool>(declare_parameter("publish_outlier_pointcloud", false));

min_azimuth_deg_ = static_cast<float>(declare_parameter("min_azimuth_deg", 0.0));
max_azimuth_deg_ = static_cast<float>(declare_parameter("max_azimuth_deg", 360.0));
max_distance_ = static_cast<float>(declare_parameter("max_distance", 12.0));
vertical_bins_ = static_cast<int>(declare_parameter("vertical_bins", 128));
horizontal_bins_ = static_cast<int>(declare_parameter("horizontal_bins", 36));
noise_threshold_ = static_cast<int>(declare_parameter("noise_threshold", 2));
}

using std::placeholders::_1;
Expand All @@ -73,170 +82,193 @@
output.data.resize(output.point_step * input->width);
size_t output_size = 0;

// Set up the noise points cloud, if noise points are to be published.
PointCloud2 outlier_points;
size_t outlier_points_size = 0;
if (publish_outlier_pointcloud_) {
outlier_points.point_step = sizeof(PointXYZI);
outlier_points.data.resize(outlier_points.point_step * input->width);
}
pcl::PointCloud<PointXYZIRADRT>::Ptr outlier_pcl(new pcl::PointCloud<PointXYZIRADRT>);

const auto ring_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::Ring)).offset;
const auto azimuth_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::Azimuth)).offset;
const auto distance_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::Distance)).offset;
const auto intensity_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::Intensity)).offset;
const auto return_type_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::ReturnType)).offset;
const auto time_stamp_offset =
input->fields.at(static_cast<size_t>(autoware_point_types::PointIndex::TimeStamp)).offset;

std::vector<std::vector<size_t>> ring2indices;
ring2indices.reserve(max_rings_num_);

for (uint16_t i = 0; i < max_rings_num_; i++) {
ring2indices.push_back(std::vector<size_t>());
ring2indices.back().reserve(max_points_num_per_ring_);
}

for (size_t data_idx = 0; data_idx < input->data.size(); data_idx += input->point_step) {
const uint16_t ring = *reinterpret_cast<const uint16_t *>(&input->data[data_idx + ring_offset]);
ring2indices[ring].push_back(data_idx);
}

// walk range: [walk_first_idx, walk_last_idx]
int walk_first_idx = 0;
int walk_last_idx = -1;

for (const auto & indices : ring2indices) {
if (indices.size() < 2) continue;

walk_first_idx = 0;
walk_last_idx = -1;

for (size_t idx = 0U; idx < indices.size() - 1; ++idx) {
const size_t & current_data_idx = indices[idx];
const size_t & next_data_idx = indices[idx + 1];
walk_last_idx = idx;

// if(std::abs(iter->distance - (iter+1)->distance) <= std::sqrt(iter->distance) * 0.08)

const float & current_azimuth =
*reinterpret_cast<const float *>(&input->data[current_data_idx + azimuth_offset]);
const float & next_azimuth =
*reinterpret_cast<const float *>(&input->data[next_data_idx + azimuth_offset]);
float azimuth_diff = next_azimuth - current_azimuth;
azimuth_diff = azimuth_diff < 0.f ? azimuth_diff + 36000.f : azimuth_diff;

const float & current_distance =
*reinterpret_cast<const float *>(&input->data[current_data_idx + distance_offset]);
const float & next_distance =
*reinterpret_cast<const float *>(&input->data[next_data_idx + distance_offset]);

if (
std::max(current_distance, next_distance) <
std::min(current_distance, next_distance) * distance_ratio_ &&
azimuth_diff < 100.f) {
continue; // Determined to be included in the same walk
}

if (isCluster(
input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]),
walk_last_idx - walk_first_idx + 1)) {
for (int i = walk_first_idx; i <= walk_last_idx; i++) {
auto output_ptr = reinterpret_cast<PointXYZI *>(&output.data[output_size]);
auto input_ptr = reinterpret_cast<const PointXYZI *>(&input->data[indices[i]]);

if (transform_info.need_transform) {
Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1);
p = transform_info.eigen_transform * p;
output_ptr->x = p[0];
output_ptr->y = p[1];
output_ptr->z = p[2];
} else {
*output_ptr = *input_ptr;
}
const float & intensity =
*reinterpret_cast<const float *>(&input->data[indices[i] + intensity_offset]);
output_ptr->intensity = intensity;

output_size += output.point_step;
}
} else if (publish_outlier_pointcloud_) {
for (int i = walk_first_idx; i <= walk_last_idx; i++) {
auto outlier_ptr =
reinterpret_cast<PointXYZI *>(&outlier_points.data[outlier_points_size]);
PointXYZIRADRT outlier_point;
auto input_ptr =
reinterpret_cast<const PointXYZI *>(&input->data[indices[walk_first_idx]]);
reinterpret_cast<const PointXYZIRADRT *>(&input->data[indices[walk_first_idx]]);
if (transform_info.need_transform) {
Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1);
p = transform_info.eigen_transform * p;
outlier_ptr->x = p[0];
outlier_ptr->y = p[1];
outlier_ptr->z = p[2];
outlier_point.x = p[0];
outlier_point.y = p[1];
outlier_point.z = p[2];
} else {
*outlier_ptr = *input_ptr;
outlier_point = *input_ptr;
}
const float & intensity = *reinterpret_cast<const float *>(
&input->data[indices[walk_first_idx] + intensity_offset]);
outlier_ptr->intensity = intensity;

outlier_points_size += outlier_points.point_step;
outlier_point.intensity = *reinterpret_cast<const float *>(
&input->data[indices[walk_first_idx] + intensity_offset]);
outlier_point.ring = *reinterpret_cast<const uint16_t *>(
&input->data[indices[walk_first_idx] + ring_offset]);
outlier_point.azimuth = *reinterpret_cast<const float *>(
&input->data[indices[walk_first_idx] + azimuth_offset]);
outlier_point.distance = *reinterpret_cast<const float *>(
&input->data[indices[walk_first_idx] + distance_offset]);
outlier_point.return_type = *reinterpret_cast<const uint8_t *>(
&input->data[indices[walk_first_idx] + return_type_offset]);
outlier_point.time_stamp = *reinterpret_cast<const float *>(
&input->data[indices[walk_first_idx] + time_stamp_offset]);
outlier_pcl->push_back(outlier_point);
}
}

walk_first_idx = idx + 1;
}

if (walk_first_idx > walk_last_idx) continue;

if (isCluster(
input, std::make_pair(indices[walk_first_idx], indices[walk_last_idx]),
walk_last_idx - walk_first_idx + 1)) {
for (int i = walk_first_idx; i <= walk_last_idx; i++) {
auto output_ptr = reinterpret_cast<PointXYZI *>(&output.data[output_size]);
auto input_ptr = reinterpret_cast<const PointXYZI *>(&input->data[indices[i]]);

if (transform_info.need_transform) {
Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1);
p = transform_info.eigen_transform * p;
output_ptr->x = p[0];
output_ptr->y = p[1];
output_ptr->z = p[2];
} else {
*output_ptr = *input_ptr;
}
const float & intensity =
*reinterpret_cast<const float *>(&input->data[indices[i] + intensity_offset]);
output_ptr->intensity = intensity;

output_size += output.point_step;
}
} else if (publish_outlier_pointcloud_) {
for (int i = walk_first_idx; i < walk_last_idx; i++) {
auto outlier_ptr = reinterpret_cast<PointXYZI *>(&outlier_points.data[outlier_points_size]);
auto input_ptr = reinterpret_cast<const PointXYZI *>(&input->data[indices[i]]);
PointXYZIRADRT outlier_point;

auto input_ptr = reinterpret_cast<const PointXYZIRADRT *>(&input->data[indices[i]]);
if (transform_info.need_transform) {
Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1);
p = transform_info.eigen_transform * p;
outlier_ptr->x = p[0];
outlier_ptr->y = p[1];
outlier_ptr->z = p[2];
outlier_point.x = p[0];
outlier_point.y = p[1];
outlier_point.z = p[2];
} else {
*outlier_ptr = *input_ptr;
outlier_point = *input_ptr;
}
const float & intensity =
outlier_point.intensity =
*reinterpret_cast<const float *>(&input->data[indices[i] + intensity_offset]);
outlier_ptr->intensity = intensity;
outlier_points_size += outlier_points.point_step;
outlier_point.ring =
*reinterpret_cast<const uint16_t *>(&input->data[indices[i] + ring_offset]);
outlier_point.azimuth =
*reinterpret_cast<const float *>(&input->data[indices[i] + azimuth_offset]);
outlier_point.distance =
*reinterpret_cast<const float *>(&input->data[indices[i] + distance_offset]);
outlier_point.return_type =
*reinterpret_cast<const uint8_t *>(&input->data[indices[i] + return_type_offset]);
outlier_point.time_stamp =
*reinterpret_cast<const float *>(&input->data[indices[i] + time_stamp_offset]);
outlier_pcl->push_back(outlier_point);
}
}
}

setUpPointCloudFormat(input, output, output_size, /*num_fields=*/4);

if (publish_outlier_pointcloud_) {
setUpPointCloudFormat(input, outlier_points, outlier_points_size, /*num_fields=*/4);
outlier_pointcloud_publisher_->publish(outlier_points);
PointCloud2 outlier;
pcl::toROSMsg(*outlier_pcl, outlier);
outlier.header = input->header;
outlier_pointcloud_publisher_->publish(outlier);

tier4_debug_msgs::msg::Float32Stamped visibility_msg;
visibility_msg.data = calculateVisibilityScore(outlier);
visibility_msg.stamp = input->header.stamp;
visibility_pub_->publish(visibility_msg);

Check notice on line 271 in sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

RingOutlierFilterComponent::faster_filter decreases in cyclomatic complexity from 29 to 28, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}

// add processing time for debug
Expand Down Expand Up @@ -288,6 +320,24 @@
RCLCPP_DEBUG(
get_logger(), "Setting new publish_outlier_pointcloud to: %d.", publish_outlier_pointcloud_);
}
if (get_param(p, "vertical_bins", vertical_bins_)) {
RCLCPP_DEBUG(get_logger(), "Setting new vertical_bins to: %d.", vertical_bins_);
}
if (get_param(p, "horizontal_bins", horizontal_bins_)) {
RCLCPP_DEBUG(get_logger(), "Setting new horizontal_bins to: %d.", horizontal_bins_);
}
if (get_param(p, "noise_threshold", noise_threshold_)) {
RCLCPP_DEBUG(get_logger(), "Setting new noise_threshold to: %d.", noise_threshold_);
}
if (get_param(p, "max_azimuth_deg", max_azimuth_deg_)) {
RCLCPP_DEBUG(get_logger(), "Setting new max_azimuth_deg to: %f.", max_azimuth_deg_);
}
if (get_param(p, "min_azimuth_deg", min_azimuth_deg_)) {
RCLCPP_DEBUG(get_logger(), "Setting new min_azimuth_deg to: %f.", min_azimuth_deg_);
}
if (get_param(p, "max_distance", max_distance_)) {
RCLCPP_DEBUG(get_logger(), "Setting new max_distance to: %f.", max_distance_);
}

Check warning on line 340 in sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

RingOutlierFilterComponent::paramCallback has a cyclomatic complexity of 11, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
Expand Down Expand Up @@ -319,6 +369,61 @@
"intensity", 1, sensor_msgs::msg::PointField::FLOAT32);
}

float RingOutlierFilterComponent::calculateVisibilityScore(
const sensor_msgs::msg::PointCloud2 & input)
{
pcl::PointCloud<PointXYZIRADRT>::Ptr input_cloud(new pcl::PointCloud<PointXYZIRADRT>);
pcl::fromROSMsg(input, *input_cloud);

const uint32_t vertical_bins = vertical_bins_;
const uint32_t horizontal_bins = horizontal_bins_;
const float max_azimuth = max_azimuth_deg_ * 100.0;
const float min_azimuth = min_azimuth_deg_ * 100.0;

const uint32_t horizontal_resolution =
static_cast<uint32_t>((max_azimuth - min_azimuth) / horizontal_bins);

std::vector<pcl::PointCloud<PointXYZIRADRT>> ring_point_clouds(vertical_bins);
cv::Mat frequency_image(cv::Size(horizontal_bins, vertical_bins), CV_8UC1, cv::Scalar(0));

// Split points into rings
for (const auto & point : input_cloud->points) {
ring_point_clouds.at(point.ring).push_back(point);
}

// Calculate frequency for each bin in each ring
for (const auto & ring_points : ring_point_clouds) {
if (ring_points.empty()) continue;

const uint ring_id = ring_points.front().ring;
std::vector<int> frequency_in_ring(horizontal_bins, 0);

for (const auto & point : ring_points.points) {
if (point.azimuth < min_azimuth || point.azimuth >= max_azimuth) continue;
if (point.distance >= max_distance_) continue;

const uint bin_index =
static_cast<uint>((point.azimuth - min_azimuth) / horizontal_resolution);

frequency_in_ring[bin_index]++;
frequency_in_ring[bin_index] =
std::min(frequency_in_ring[bin_index], 255); // Ensure value is within uchar range

frequency_image.at<uchar>(ring_id, bin_index) =
static_cast<uchar>(frequency_in_ring[bin_index]);
}
}

cv::Mat binary_image;
cv::inRange(frequency_image, noise_threshold_, 255, binary_image);

const int num_pixels = cv::countNonZero(frequency_image);
const float num_filled_pixels =
static_cast<float>(num_pixels) / static_cast<float>(vertical_bins * horizontal_bins);

return 1.0f - num_filled_pixels;
}

Check warning on line 425 in sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

RingOutlierFilterComponent::calculateVisibilityScore has a cyclomatic complexity of 11, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 425 in sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

RingOutlierFilterComponent::calculateVisibilityScore 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.

} // namespace pointcloud_preprocessor

#include <rclcpp_components/register_node_macro.hpp>
Expand Down
Loading