Skip to content

Commit b3c69b4

Browse files
feat(radar_object_clustering): created schema file and updated readme file for parameters settings (autowarefoundation#9966)
* feat: created schema files and upadted Readme file , yaml files Signed-off-by: vish0012 <vishalchhn42@gmail.com> * style(pre-commit): autofix * Update README.md Update README file --------- Signed-off-by: vish0012 <vishalchhn42@gmail.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 9d965fb commit b3c69b4

File tree

3 files changed

+89
-63
lines changed

3 files changed

+89
-63
lines changed

perception/autoware_radar_object_clustering/README.md

+1-58
Original file line numberDiff line numberDiff line change
@@ -65,61 +65,4 @@ So `is_fixed_size` parameter is recommended to set `true`, and size parameters i
6565

6666
### Parameter
6767

68-
- `angle_threshold` (double) [rad]
69-
- Default parameter is 0.174.
70-
- `distance_threshold` (double) [m]
71-
- Default parameter is 4.0.
72-
- `velocity_threshold` (double) [m/s]
73-
- Default parameter is 2.0.
74-
75-
These parameter are thresholds for angle, distance, and velocity to judge whether radar detections come from one object in "clustering" processing, which is written in detail at algorithm section.
76-
If all of the difference in angle/distance/velocity from two objects is less than the thresholds, then the two objects are merged to one clustered object.
77-
If these parameter is larger, more objects are merged to one clustered object.
78-
79-
These are used in `isSameObject` function as below.
80-
81-
```cpp
82-
83-
bool RadarObjectClusteringNode::isSameObject(
84-
const DetectedObject & object_1, const DetectedObject & object_2)
85-
{
86-
const double angle_diff = std::abs(autoware::universe_utils::normalizeRadian(
87-
tf2::getYaw(object_1.kinematics.pose_with_covariance.pose.orientation) -
88-
tf2::getYaw(object_2.kinematics.pose_with_covariance.pose.orientation)));
89-
const double velocity_diff = std::abs(
90-
object_1.kinematics.twist_with_covariance.twist.linear.x -
91-
object_2.kinematics.twist_with_covariance.twist.linear.x);
92-
const double distance = autoware::universe_utils::calcDistance2d(
93-
object_1.kinematics.pose_with_covariance.pose.position,
94-
object_2.kinematics.pose_with_covariance.pose.position);
95-
96-
if (
97-
distance < node_param_.distance_threshold && angle_diff < node_param_.angle_threshold &&
98-
velocity_diff < node_param_.velocity_threshold) {
99-
return true;
100-
} else {
101-
return false;
102-
}
103-
}
104-
```
105-
106-
- `is_fixed_label` (bool)
107-
- Default parameter is false.
108-
- `fixed_label` (string)
109-
- Default parameter is "UNKNOWN".
110-
111-
`is_fixed_label` is the flag to use fixed label.
112-
If it is true, the label of a clustered object is overwritten by the label set by `fixed_label` parameter.
113-
If the radar objects do not have label information, then it is recommended to use fixed label.
114-
115-
- `is_fixed_size` (bool)
116-
- Default parameter is false.
117-
- `size_x` (double) [m]
118-
- Default parameter is 4.0.
119-
- `size_y` (double) [m]
120-
- Default parameter is 1.5.
121-
- `size_z` (double) [m]
122-
- Default parameter is 1.5.
123-
124-
`is_fixed_size` is the flag to use fixed size parameters.
125-
If it is true, the size of a clustered object is overwritten by the label set by `size_x`, `size_y`, and `size_z` parameters.
68+
{{ json_to_markdown("perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml/schema/radar_object_clustering.schema.json") }}

perception/autoware_radar_object_clustering/config/radar_object_clustering.param.yaml

+5-5
Original file line numberDiff line numberDiff line change
@@ -2,14 +2,14 @@
22
ros__parameters:
33
# clustering parameter
44
angle_threshold: 0.174 # [rad] (10 deg)
5-
distance_threshold: 10.0 # [m]
6-
velocity_threshold: 4.0 # [m/s]
5+
distance_threshold: 4.0 # [m]
6+
velocity_threshold: 2.0 # [m/s]
77

88
# output object settings
99
# set false if you want to use the object information from radar
10-
is_fixed_label: true
11-
fixed_label: "CAR"
12-
is_fixed_size: true
10+
is_fixed_label: false
11+
fixed_label: "UNKNOWN"
12+
is_fixed_size: false
1313
size_x: 4.0 # [m]
1414
size_y: 1.5 # [m]
1515
size_z: 1.5 # [m]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Radar Object Clustering Parameters",
4+
"type": "object",
5+
"definitions": {
6+
"radar_object_clustering": {
7+
"type": "object",
8+
"properties": {
9+
"angle_threshold": {
10+
"type": "number",
11+
"description": "Threshold for angle to determine whether radar detections come from one object during clustering. Larger values merge more objects.",
12+
"default": 0.174
13+
},
14+
"distance_threshold": {
15+
"type": "number",
16+
"description": "Threshold for distance to determine whether radar detections come from one object during clustering. Larger values merge more objects.",
17+
"default": 4.0
18+
},
19+
"velocity_threshold": {
20+
"type": "number",
21+
"description": "Threshold for velocity to determine whether radar detections come from one object during clustering. Larger values merge more objects.",
22+
"default": 2.0
23+
},
24+
"is_fixed_label": {
25+
"type": "boolean",
26+
"description": "Flag to use a fixed label. If true, the label of a clustered object is overwritten by the `fixed_label` parameter.",
27+
"default": false
28+
},
29+
"fixed_label": {
30+
"type": "string",
31+
"description": "The fixed label to use when `is_fixed_label` is true.",
32+
"default": "UNKNOWN"
33+
},
34+
"is_fixed_size": {
35+
"type": "boolean",
36+
"description": "Flag to use fixed size parameters. If true, the size of a clustered object is overwritten by the `size_x`, `size_y`, and `size_z` parameters.",
37+
"default": false
38+
},
39+
"size_x": {
40+
"type": "number",
41+
"description": "Size of the clustered object in the x-dimension, used if `is_fixed_size` is true.",
42+
"default": 4.0
43+
},
44+
"size_y": {
45+
"type": "number",
46+
"description": "Size of the clustered object in the y-dimension, used if `is_fixed_size` is true.",
47+
"default": 1.5
48+
},
49+
"size_z": {
50+
"type": "number",
51+
"description": "Size of the clustered object in the z-dimension, used if `is_fixed_size` is true.",
52+
"default": 1.5
53+
}
54+
},
55+
"required": [
56+
"angle_threshold",
57+
"distance_threshold",
58+
"velocity_threshold",
59+
"is_fixed_label",
60+
"fixed_label",
61+
"is_fixed_size",
62+
"size_x",
63+
"size_y",
64+
"size_z"
65+
],
66+
"additionalProperties": false
67+
}
68+
},
69+
"properties": {
70+
"/**": {
71+
"type": "object",
72+
"properties": {
73+
"ros__parameters": {
74+
"$ref": "#/definitions/radar_object_clustering"
75+
}
76+
},
77+
"required": ["ros__parameters"],
78+
"additionalProperties": false
79+
}
80+
},
81+
"required": ["/**"],
82+
"additionalProperties": false
83+
}

0 commit comments

Comments
 (0)