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(ring_outlier_filter): change a parameter to be less misleading #4981

Closed
wants to merge 3 commits into from
Closed
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
12 changes: 6 additions & 6 deletions sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md
Original file line number Diff line number Diff line change
Expand Up @@ -22,12 +22,12 @@ 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 | |
| Name | Type | Default Value | Description |
| ------------------------- | ------- | ------------- | ---------------------------- |
| `distance_ratio` | double | 1.03 | |
| `object_length_threshold` | double | 0.1 | |
| `num_points_threshold` | int | 4 | |
| `max_ring_index` | uint_16 | 128 | `128` corresponds to vls128. |
Copy link
Contributor

Choose a reason for hiding this comment

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

For index, I am not sure if it is 127 or 128 when using vls128. max_rings_num would be easier to understand if it is 128.

Copy link
Contributor

Choose a reason for hiding this comment

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

related comment: #4981 (comment)
cc @taikitanaka3

Copy link
Contributor

Choose a reason for hiding this comment

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

@yukkysaito

In a project using Autoware, max_rings_num was set to 128 (i.e. the range of ring index was set to be 0~127), but actually the maximum value of ring index was 128.
To prevent this kind of thing, the parameter name should be changed to be less misleading.

Based on this explanation, wouldn't it be more appropriate to use 'max_rings_index' rather than 'max_rings_num'?

Copy link
Contributor

@yukkysaito yukkysaito Oct 27, 2023

Choose a reason for hiding this comment

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

@tkimura4 If it weren't for the description, I would think that vls128 would be correct to specify 127 based on the name max_ring_index.
Wouldn't it be better to fix the index set to 128?


## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
double distance_ratio_;
double object_length_threshold_;
int num_points_threshold_;
uint16_t max_rings_num_;
uint16_t max_ring_index_;

/** \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 @@ -47,7 +47,7 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions
object_length_threshold_ =
static_cast<double>(declare_parameter("object_length_threshold", 0.1));
num_points_threshold_ = static_cast<int>(declare_parameter("num_points_threshold", 4));
max_rings_num_ = static_cast<uint16_t>(declare_parameter("max_rings_num", 128));
max_ring_index_ = static_cast<uint16_t>(declare_parameter("max_ring_index", 128));
}

using std::placeholders::_1;
Expand Down Expand Up @@ -173,11 +173,11 @@ void RingOutlierFilterComponent::faster_filter(
size_t latest_walk_id = -1UL; // ID given to the latest walk created

// initialize each ring with two empty walks (first and current walk)
rings.resize(max_rings_num_, RingWalkInfo{{-1UL, 0, 0, 0, 0, 0}, {-1UL, 0, 0, 0, 0, 0}});
rings.resize(max_ring_index_ + 1, RingWalkInfo{{-1UL, 0, 0, 0, 0, 0}, {-1UL, 0, 0, 0, 0, 0}});
// points are initially associated to no walk (-1UL)
points_walk_id.resize(input->width * input->height, -1UL);
walks_cluster_status.reserve(
max_rings_num_ * 2); // In the worst case, this could grow to the number of input points
(max_ring_index_ + 1) * 2); // In the worst case, this could grow to the number of input points

int invalid_ring_count = 0;

Expand All @@ -191,8 +191,8 @@ void RingOutlierFilterComponent::faster_filter(
std::memcpy(&curr_azimuth, &raw_p.data()[azimuth_offset], sizeof(curr_azimuth));
std::memcpy(&curr_distance, &raw_p.data()[distance_offset], sizeof(curr_distance));

if (ring_idx >= max_rings_num_) {
// Either the data is corrupted or max_rings_num_ is not set correctly
if (ring_idx > max_ring_index_) {
// Either the data is corrupted or max_ring_index_ is not set correctly
// Note: point_walk_id == -1 so the point will be filtered out
++invalid_ring_count;
continue;
Expand Down Expand Up @@ -334,8 +334,8 @@ void RingOutlierFilterComponent::faster_filter(

if (invalid_ring_count > 0) {
RCLCPP_WARN(
get_logger(), "%d points had ring index over max_rings_num (%d) and have been ignored.",
invalid_ring_count, max_rings_num_);
get_logger(), "%d points had ring index over max_ring_index (%d) and have been ignored.",
invalid_ring_count, max_ring_index_);
}

// add processing time for debug
Expand Down