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

Revert "perf(ring_outlier_filter): a cache friendly impl (continuation of VRichardJP's work)" #6145

Closed
wants to merge 1 commit 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
13 changes: 7 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,13 @@ 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_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` |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,29 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
double object_length_threshold_;
int num_points_threshold_;
uint16_t max_rings_num_;
size_t max_points_num_per_ring_;

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

/** \brief Parameter service callback */
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

bool isCluster(
const PointCloud2ConstPtr & input, std::pair<int, int> data_idx_both_ends, int walk_size)
{
if (walk_size > num_points_threshold_) return true;

auto first_point = reinterpret_cast<const PointXYZI *>(&input->data[data_idx_both_ends.first]);
auto last_point = reinterpret_cast<const PointXYZI *>(&input->data[data_idx_both_ends.second]);

const auto x = first_point->x - last_point->x;
const auto y = first_point->y - last_point->y;
const auto z = first_point->z - last_point->z;

return x * x + y * y + z * z >= object_length_threshold_ * object_length_threshold_;
}

public:
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit RingOutlierFilterComponent(const rclcpp::NodeOptions & options);
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 @@ -31,7 +31,6 @@
<depend>pcl_msgs</depend>
<depend>pcl_ros</depend>
<depend>point_cloud_msg_wrapper</depend>
<depend>range-v3</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
Loading
Loading