Skip to content

Commit e843b53

Browse files
calculate visibility score in ring outlier filter
Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 113ad51 commit e843b53

File tree

3 files changed

+30
-14
lines changed

3 files changed

+30
-14
lines changed

sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md

+16-8
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,8 @@ A method of operating scan in chronological order and removing noise based on th
1010

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

13+
Another feature of this node is that it calculates visibility based on outlier pointcloud and publish score as a topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle.
14+
1315
## Inputs / Outputs
1416

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

2325
### Core Parameters
2426

25-
| Name | Type | Default Value | Description |
26-
| ---------------------------- | ------- | ------------- | -------------------------------------------------------------------------------------------------------- |
27-
| `distance_ratio` | double | 1.03 | |
28-
| `object_length_threshold` | double | 0.1 | |
29-
| `num_points_threshold` | int | 4 | |
30-
| `max_rings_num` | uint_16 | 128 | |
31-
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
32-
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud. Due to performance concerns, please set to false during experiments. |
27+
| Name | Type | Default Value | Description |
28+
| ---------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------- |
29+
| `distance_ratio` | double | 1.03 | |
30+
| `object_length_threshold` | double | 0.1 | |
31+
| `num_points_threshold` | int | 4 | |
32+
| `max_rings_num` | uint_16 | 128 | |
33+
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
34+
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments. |
35+
| `min_azimuth_deg` | float | 0.0 | The left limit of azimuth for visibility score calculation |
36+
| `max_azimuth_deg` | float | 360.0 | The right limit of azimuth for visibility score calculation |
37+
| `max_distance` | float | 12.0 | The limit distance for for visibility score calculation |
38+
| `vertical_bins` | int | 128 | The number of vertical bin for visibility histogram |
39+
| `horizontal_bins` | int | 36 | The number of horizontal bin for visibility histogram |
40+
| `noise_threshold` | int | 2 | The parameter for determining whether it is noise |
3341

3442
## Assumptions / Known limits
3543

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,6 @@
3030

3131
#include <memory>
3232
#include <string>
33-
#include <unordered_map>
3433
#include <utility>
3534
#include <vector>
3635

@@ -69,7 +68,6 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
6968
int noise_threshold_;
7069
int vertical_bins_;
7170
int horizontal_bins_;
72-
float max_azimuth_diff_;
7371

7472
float min_azimuth_deg_;
7573
float max_azimuth_deg_;

sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

+14-4
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,6 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
3535
debug_publisher_ = std::make_unique<DebugPublisher>(this, "ring_outlier_filter");
3636
outlier_pointcloud_publisher_ =
3737
this->create_publisher<PointCloud2>("debug/ring_outlier_filter", 1);
38-
image_pub_ =
39-
image_transport::create_publisher(this, "ring_outlier_filter/debug/frequency_image");
4038
visibility_pub_ = create_publisher<tier4_debug_msgs::msg::Float32Stamped>(
4139
"ring_outlier_filter/debug/visibility", rclcpp::SensorDataQoS());
4240
stop_watch_ptr_->tic("cyclic_time");
@@ -325,8 +323,20 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba
325323
if (get_param(p, "vertical_bins", vertical_bins_)) {
326324
RCLCPP_DEBUG(get_logger(), "Setting new vertical_bins to: %d.", vertical_bins_);
327325
}
328-
if (get_param(p, "max_azimuth_diff", max_azimuth_diff_)) {
329-
RCLCPP_DEBUG(get_logger(), "Setting new max_azimuth_diff to: %f.", max_azimuth_diff_);
326+
if (get_param(p, "horizontal_bins", horizontal_bins_)) {
327+
RCLCPP_DEBUG(get_logger(), "Setting new horizontal_bins to: %d.", horizontal_bins_);
328+
}
329+
if (get_param(p, "noise_threshold", noise_threshold_)) {
330+
RCLCPP_DEBUG(get_logger(), "Setting new noise_threshold to: %d.", noise_threshold_);
331+
}
332+
if (get_param(p, "max_azimuth_deg", max_azimuth_deg_)) {
333+
RCLCPP_DEBUG(get_logger(), "Setting new max_azimuth_deg to: %f.", max_azimuth_deg_);
334+
}
335+
if (get_param(p, "min_azimuth_deg", min_azimuth_deg_)) {
336+
RCLCPP_DEBUG(get_logger(), "Setting new min_azimuth_deg to: %f.", min_azimuth_deg_);
337+
}
338+
if (get_param(p, "max_distance", max_distance_)) {
339+
RCLCPP_DEBUG(get_logger(), "Setting new max_distance to: %f.", max_distance_);
330340
}
331341

332342
rcl_interfaces::msg::SetParametersResult result;

0 commit comments

Comments
 (0)