Skip to content

Commit fe8f1c4

Browse files
feat(radar_crossing_objects_noise_filter): add radar_crossing_objects_filter (autowarefoundation#4127)
* feat(radar_crossing_objects_noise_filter): add radar_crossing_objects_noise_filter Signed-off-by: scepter914 <scepter914@gmail.com> * style(pre-commit): autofix * update README Signed-off-by: scepter914 <scepter914@gmail.com> * update README Signed-off-by: scepter914 <scepter914@gmail.com> * style(pre-commit): autofix * change default parameter Signed-off-by: scepter914 <scepter914@gmail.com> * update README Signed-off-by: scepter914 <scepter914@gmail.com> * update README Signed-off-by: scepter914 <scepter914@gmail.com> --------- Signed-off-by: scepter914 <scepter914@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 77a7616 commit fe8f1c4

File tree

9 files changed

+629
-0
lines changed

9 files changed

+629
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(radar_crossing_objects_noise_filter)
3+
4+
# Compile options
5+
if(NOT CMAKE_CXX_STANDARD)
6+
set(CMAKE_CXX_STANDARD 17)
7+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
8+
set(CMAKE_CXX_EXTENSIONS OFF)
9+
endif()
10+
11+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
12+
add_compile_options(-Wall -Wextra -Wpedantic)
13+
endif()
14+
15+
# Dependencies
16+
find_package(autoware_cmake REQUIRED)
17+
autoware_package()
18+
19+
# Targets
20+
ament_auto_add_library(radar_crossing_objects_noise_filter_node_component SHARED
21+
src/radar_crossing_objects_noise_filter_node/radar_crossing_objects_noise_filter_node.cpp
22+
)
23+
24+
rclcpp_components_register_node(radar_crossing_objects_noise_filter_node_component
25+
PLUGIN "radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode"
26+
EXECUTABLE radar_crossing_objects_noise_filter_node
27+
)
28+
29+
# Tests
30+
if(BUILD_TESTING)
31+
list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify)
32+
find_package(ament_lint_auto REQUIRED)
33+
ament_lint_auto_find_test_dependencies()
34+
endif()
35+
36+
# Package
37+
ament_auto_package(
38+
INSTALL_TO_SHARE
39+
launch
40+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
# radar_crossing_objects_noise_filter
2+
3+
This package contains a radar noise filter module for [autoware_auto_perception_msgs/msg/DetectedObject](https://gitlab.com/autowarefoundation/autoware.auto/autoware_auto_msgs/-/blob/master/autoware_auto_perception_msgs/msg/DetectedObject.idl).
4+
This package can filter the noise objects which cross to the ego vehicle.
5+
6+
## Algorithm
7+
8+
### Background
9+
10+
This package aim to filter the noise objects which cross from the ego vehicle.
11+
The reason why these objects are noise is as below.
12+
13+
- 1. The objects with doppler velocity can be trusted more than those with vertical velocity to it.
14+
15+
Radars can get velocity information of objects as doppler velocity, but cannot get vertical velocity to doppler velocity directory.
16+
Some radars can output the objects with not only doppler velocity but also vertical velocity by estimation.
17+
If the vertical velocity estimation is poor, it leads to output noise objects.
18+
In other words, the above situation is that the objects which has vertical twist viewed from ego vehicle can tend to be noise objects.
19+
20+
The example is below figure.
21+
Velocity estimation fails on static objects, resulting in ghost objects crossing in front of ego vehicles.
22+
23+
![vertical_velocity_objects](docs/vertical_velocity_objects.png)
24+
25+
- 2. Turning around by ego vehicle affect the output from radar.
26+
27+
When the ego vehicle turns around, the radars outputting at the object level sometimes fail to estimate the twist of objects correctly even if [radar_tracks_msgs_converter](https://github.com/autowarefoundation/autoware.universe/tree/main/perception/radar_tracks_msgs_converter) compensates by the ego vehicle twist.
28+
So if an object detected by radars has circular motion viewing from base_link, it is likely that the speed is estimated incorrectly and that the object is a static object.
29+
30+
The example is below figure.
31+
When the ego vehicle turn right, the surrounding objects have left circular motion.
32+
33+
![turning_around](docs/turning_around.png)
34+
35+
### Detail Algorithm
36+
37+
To filter the objects crossing to ego vehicle, this package filter the objects as below algorithm.
38+
39+
![algorithm](docs/radar_crossing_objects_noise_filter.drawio.svg)
40+
41+
```cpp
42+
// If velocity of an object is rather than the velocity_threshold,
43+
// and crossing_yaw is near to vertical
44+
// angle_threshold < crossing_yaw < pi - angle_threshold
45+
if (
46+
velocity > node_param_.velocity_threshold &&
47+
abs(std::cos(crossing_yaw)) < abs(std::cos(node_param_.angle_threshold))) {
48+
// Object is noise object;
49+
} else {
50+
// Object is not noise object;
51+
}
52+
```
53+
54+
## Input
55+
56+
| Name | Type | Description |
57+
| ----------------- | ----------------------------------------------------- | -------------- |
58+
| `~/input/objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Radar objects. |
59+
60+
## Output
61+
62+
| Name | Type | Description |
63+
| --------------------------- | ----------------------------------------------------- | ---------------- |
64+
| `~/output/noise_objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Noise objects |
65+
| `~/output/filtered_objects` | autoware_auto_perception_msgs/msg/DetectedObjects.msg | Filtered objects |
66+
67+
## Parameters
68+
69+
| Name | Type | Description | Default value |
70+
| :------------------- | :----- | :-------------------------------------------------------------------------------------------------------------------------------------------------- | :------------ |
71+
| `angle_threshold` | double | The angle threshold parameter to filter [rad]. This parameter has condition that 0 < `angle_threshold` < pi / 2. See algorithm chapter for details. | 1.0472 |
72+
| `velocity_threshold` | double | The velocity threshold parameter to filter [m/s]. See algorithm chapter for details. | 3.0 |

0 commit comments

Comments
 (0)