Skip to content

Commit

Permalink
docs: update readme of outlier filter (autowarefoundation#758) (autow…
Browse files Browse the repository at this point in the history
…arefoundation#208)

* docs: update readme of outlier filter (autowarefoundation#758)

* add outlier filter readme template

* wip

* wip

* replace image to drawio.svg

* delete doc of occupancy_grid_map_filter in outlier_filter

* update voxel_grid_outlier_filter

* remove occupancy grid map outlier filter svg

* update readme

* fix ring outlier filter image

* add dual_return_outlier_filter readme

* fix readme

* update dual-return-outlier-filter readme

Co-authored-by: yukke42 <muramatsuyusuke9542@gmail.com>

* Update sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md

* ci(pre-commit): autofix

Co-authored-by: Taichi Higashide <taichi.higashide@tier4.jp>
Co-authored-by: yukke42 <muramatsuyusuke9542@gmail.com>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Tomoya Kimura <tomoya.kimura@tier4.jp>
  • Loading branch information
5 people authored Dec 22, 2021
1 parent 1a20fcb commit e345381
Show file tree
Hide file tree
Showing 11 changed files with 230 additions and 45 deletions.
62 changes: 62 additions & 0 deletions sensing/pointcloud_preprocessor/docs/dual-return-outlier-filter.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
# dual_return_outlier_filter

## Purpose

The purpose is to remove point cloud noise such as fog and rain and publish visibility as a diagnostic topic.

## Inner-workings / Algorithms

This node can remove rain and fog by considering the light reflected from the object in two stages according to the attenuation factor. The `dual_return_outlier_filter` is named because it removes noise using data that contains two types of return values separated by attenuation factor, as shown in the figure below.

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

Therefore, in order to use this node, the sensor driver must publish custom data including `return_type`. please refer to [PointXYZIRADT](https://github.com/tier4/AutowareArchitectureProposal.iv/blob/5d8dff0db51634f0c42d2a3e87ca423fbee84348/sensing/preprocessor/pointcloud/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp#L86-L96) data structure.

Another feature of this node is that it publishes visibility as a diagnostic 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.

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

The figure below describe how the node works.
![outlier_filter-dual_return_detail](./image/outlier_filter-dual_return_detail.drawio.svg)

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Output

| Name | Type | Description |
| ---------------------------------------------- | --------------------------------------- | ------------------------------------------------------- |
| `/dual_return_outlier_filter/frequency_image` | `sensor_msgs::msg::Image` | The histogram image that represent visibility |
| `/dual_return_outlier_filter/visibility` | `tier4_debug_msgs::msg::Float32Stamped` | A representation of visibility with a value from 0 to 1 |
| `/dual_return_outlier_filter/pointcloud_noise` | `sensor_msgs::msg::Pointcloud2` | The pointcloud removed as noise |

## Parameters

### Node Parameters

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Core Parameters

| Name | Type | Description |
| ---------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------- |
| `vertical_bins` | int | The number of vertical bin for visibility histogram |
| `max_azimuth_diff` | float | Threshold for ring_outlier_filter |
| `weak_first_distance_ratio` | double | Threshold for ring_outlier_filter |
| `general_distance_ratio` | double | Threshold for ring_outlier_filter |
| `weak_first_local_noise_threshold` | int | The parameter for determining whether it is noise |
| `visibility_threshold` | float | When the percentage of white pixels in the binary histogram falls below this parameter the diagnostic status becomes WARN |

## Assumptions / Known limits

Not recommended for use as it is under development.
Input data must be `PointXYZIRADT` type data including `return_type`.

## (Optional) Error detection and handling

## (Optional) Performance characterization

## References/External links

## (Optional) Future extensions / Unimplemented parts
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
52 changes: 7 additions & 45 deletions sensing/pointcloud_preprocessor/docs/outlier-filter.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,52 +2,16 @@

## Purpose

The `outlier_filter` is a node that removes points caused by hardware problems, rain drops and small insects as a noise.
The `outlier_filter` is a package for filtering outlier of points.

## Inner-workings / Algorithms

### Dual Return Outlier Filter

WIP

### Radius Search 2d Outlier Filter [1]

WIP

### Ring Outlier Filter

WIP

### Voxel Grid Outlier Filter

WIP

## Inputs / Outputs

### Input

| Name | Type | Description |
| -------------------- | ------------------------- | ----------------------------------------- |
| `~/input/pointcloud` | `sensor_msgs/PointCloud2` | Obstacle point cloud with ground removed. |

### Output

| Name | Type | Description |
| ----------------------------------- | ------------------------- | --------------------------------------------- |
| `~/output/pointcloud` | `sensor_msgs/PointCloud2` | Point cloud with outliers removed. trajectory |
| `~/output/debug/outlier/pointcloud` | `sensor_msgs/PointCloud2` | Point clouds removed as outliers. |

## Parameters

| Name | Type | Description |
| ------------------------------------------------------- | ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `map_frame` | string | map frame id |
| `base_link_frame` | string | base link frame id |
| `enable_debugger` | bool | Whether to output the point cloud for debugging. |
| `radius_search_2d_filter/search_radius` | float | Radius when calculating the density |
| `radius_search_2d_filter/min_points_and_distance_ratio` | float | Threshold value of the number of point clouds per radius when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink. |
| `radius_search_2d_filter/min_points` | int | Minimum number of point clouds per radius |
| `radius_search_2d_filter/max_points` | int | Maximum number of point clouds per radius |
| Filter Name | Description | Detail |
| ---------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------- |
| radius search 2d outlier filter | A method of removing point cloud noise based on the number of points existing within a certain radius | [link](./radius-search-2d-outlier-filter.md) |
| ring outlier filter | A method of operating scan in chronological order and removing noise based on the rate of change in the distance between points | [link](./ring-outlier-filter.md) |
| voxel grid outlier filter | A method of removing point cloud noise based on the number of points existing within a voxel | [link](./voxel-grid-outlier-filter.md) |
| dual return outlier filter (under development) | A method of removing rain and fog by considering the light reflected from the object in two stages according to the attenuation factor. | [link](./dual-return-outlier-filter.md) |

## Assumptions / Known limits

Expand All @@ -57,6 +21,4 @@ WIP

## (Optional) References/External links

[1] <https://pcl.readthedocs.io/projects/tutorials/en/latest/remove_outliers.html>

## (Optional) Future extensions / Unimplemented parts
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
# radius_search_2d_outlier_filter

## Purpose

The purpose is to remove point cloud noise such as insects and rain.

## Inner-workings / Algorithms

> RadiusOutlierRemoval filter which removes all indices in its input cloud that don’t have at least some number of neighbors within a certain range.
The description above is quoted from [1]. `pcl::search::KdTree` [2] is used to implement this package.

![radius_search_2d_outlier_filter_picture](./image/outlier_filter-radius_search_2d.drawio.svg)

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

## Parameters

### Node Parameters

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Core Parameters

| Name | Type | Description |
| --------------- | ------ | ------------------------------------------------------------------------------------------------------------------------ |
| `min_neighbors` | int | If points in the circle centered on reference point is less than `min_neighbors`, a reference point is judged as outlier |
| `search_radius` | double | Searching number of points included in `search_radius` |

## Assumptions / Known limits

Since the method is to count the number of points contained in the cylinder with the direction of gravity as the direction of the cylinder axis, it is a prerequisite that the ground has been removed.

## (Optional) Error detection and handling

## (Optional) Performance characterization

## References/External links

[1] <https://pcl.readthedocs.io/projects/tutorials/en/latest/remove_outliers.html>

[2] <https://pcl.readthedocs.io/projects/tutorials/en/latest/kdtree_search.html#kdtree-search>

## (Optional) Future extensions / Unimplemented parts
50 changes: 50 additions & 0 deletions sensing/pointcloud_preprocessor/docs/ring-outlier-filter.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
# ring_outlier_filter

## Purpose

The purpose is to remove point cloud noise such as insects and rain.

## Inner-workings / Algorithms

A method of operating scan in chronological order and removing noise based on the rate of change in the distance between points

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

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

## Parameters

### Node Parameters

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Core Parameters

| Name | Type | Default Value | Description |
| ------------------------- | ------ | ------------- | ----------- |
| `distance_ratio` | double | 1.03 | |
| `object_length_threshold` | double | 0.1 | |
| `num_points_threshold` | int | 4 | |

## Assumptions / Known limits

It is a prerequisite to input a scan point cloud in chronological order. In this repository it is defined as blow structure (please refer to [PointXYZIRADT](https://github.com/tier4/AutowareArchitectureProposal.iv/blob/5d8dff0db51634f0c42d2a3e87ca423fbee84348/sensing/preprocessor/pointcloud/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp#L53-L62)).

- X: x
- Y: y
- z: z
- I: intensity
- R: ring
- A :azimuth
- D: distance
- T: time_stamp

## (Optional) Error detection and handling

## (Optional) Performance characterization

## (Optional) References/External links

## (Optional) Future extensions / Unimplemented parts
41 changes: 41 additions & 0 deletions sensing/pointcloud_preprocessor/docs/voxel-grid-outlier-filter.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# voxel_grid_outlier_filter

## Purpose

The purpose is to remove point cloud noise such as insects and rain.

## Inner-workings / Algorithms

Removing point cloud noise based on the number of points existing within a voxel.
The [radius_search_2d_outlier_filter](./radius-search-2d-outlier-filter.md) is better for accuracy, but this method has the advantage of low calculation cost.

![voxel_grid_outlier_filter_picture](./image/outlier_filter-voxel_grid.drawio.svg)

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

## Parameters

### Node Parameters

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Core Parameters

| Name | Type | Default Value | Description |
| ------------------------ | ------ | ------------- | ------------------------------------------ |
| `voxel_size_x` | double | 0.3 | the voxel size along x-axis [m] |
| `voxel_size_y` | double | 0.3 | the voxel size along y-axis [m] |
| `voxel_size_z` | double | 0.1 | the voxel size along z-axis [m] |
| `voxel_points_threshold` | int | 2 | the minimum number of points in each voxel |

## Assumptions / Known limits

## (Optional) Error detection and handling

## (Optional) Performance characterization

## (Optional) References/External links

## (Optional) Future extensions / Unimplemented parts

0 comments on commit e345381

Please sign in to comment.