Skip to content

Commit 5d2ac41

Browse files
refactor(radar_tracks_msgs_converter)
Rework parameters Signed-off-by: kaspermeck-arm <kasper.mecklenburg@arm.com> Change-Id: If28e9c97bc6db3b522c680f215b3f8cb95ec58b7
1 parent c09c176 commit 5d2ac41

File tree

3 files changed

+60
-30
lines changed

3 files changed

+60
-30
lines changed

perception/radar_tracks_msgs_converter/README.md

+1-28
Original file line numberDiff line numberDiff line change
@@ -52,31 +52,4 @@ Autoware objects label is defined in [ObjectClassification.idl](https://gitlab.c
5252

5353
### Parameters
5454

55-
- `update_rate_hz` (double) [hz]
56-
- Default parameter is 20.0
57-
58-
This parameter is update rate for the `onTimer` function.
59-
This parameter should be same as the frame rate of input topics.
60-
61-
- `new_frame_id` (string)
62-
- Default parameter is "base_link"
63-
64-
This parameter is the header frame_id of the output topic.
65-
66-
- `use_twist_compensation` (bool)
67-
- Default parameter is "true"
68-
69-
This parameter is the flag to use the compensation to linear of ego vehicle's twist.
70-
If the parameter is true, then the twist of the output objects' topic is compensated by the ego vehicle linear motion.
71-
72-
- `use_twist_yaw_compensation` (bool)
73-
- Default parameter is "false"
74-
75-
This parameter is the flag to use the compensation to yaw rotation of ego vehicle's twist.
76-
If the parameter is true, then the ego motion compensation will also consider yaw motion of the ego vehicle.
77-
78-
- `static_object_speed_threshold` (float) [m/s]
79-
- Default parameter is 1.0
80-
81-
This parameter is the threshold to determine the flag `is_stationary`.
82-
If the velocity is lower than this parameter, the flag `is_stationary` of DetectedObject is set to `true` and dealt as a static object.
55+
{{ json_to_markdown("perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }}

perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,13 @@
33
<arg name="input/odometry" default="/localization/kinematic_state"/>
44
<arg name="output/radar_detected_objects" default="output/radar_detected_objects"/>
55
<arg name="output/radar_tracked_objects" default="output/radar_tracked_objects"/>
6-
<arg name="param_path" default="$(find-pkg-share radar_tracks_msgs_converter)/config/radar_tracks_msgs_converter.param.yaml"/>
6+
<arg name="config_file" default="$(find-pkg-share radar_tracks_msgs_converter)/config/radar_tracks_msgs_converter.param.yaml"/>
77

88
<node pkg="radar_tracks_msgs_converter" exec="radar_tracks_msgs_converter_node" name="radar_tracks_msgs_converter" output="screen">
99
<remap from="~/input/radar_objects" to="$(var input/radar_objects)"/>
1010
<remap from="~/input/odometry" to="$(var input/odometry)"/>
1111
<remap from="~/output/radar_detected_objects" to="$(var output/radar_detected_objects)"/>
1212
<remap from="~/output/radar_tracked_objects" to="$(var output/radar_tracked_objects)"/>
13-
<param from="$(var param_path)"/>
13+
<param from="$(var config_file)"/>
1414
</node>
1515
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Radar Tracks Msgs Converter node",
4+
"type": "object",
5+
"definitions": {
6+
"radar_tracks_msgs_converter": {
7+
"type": "object",
8+
"properties": {
9+
"update_rate_hz": {
10+
"type": "number",
11+
"description": "The update rate [hz] for the `onTimer` function. Should be the same as the frame rate of input topics.",
12+
"default": "20.0",
13+
"minimum": 0.0
14+
},
15+
"new_frame_id": {
16+
"type": "string",
17+
"description": "The header frame_id of the output topic.",
18+
"default": "base_link"
19+
},
20+
"use_twist_compensation": {
21+
"type": "boolean",
22+
"description": "Flag to enable the compensation to linear of ego vehicle's twist. If true, the twist of the output objects' topic is compensated by the ego vehicle linear motion.",
23+
"default": "false"
24+
},
25+
"use_twist_yaw_compensation": {
26+
"type": "boolean",
27+
"description": "Flag to enable the compensation to yaw rotation of ego vehicle's twist. If true, the ego motion compensation will also consider yaw motion of the ego vehicle.",
28+
"default": "false"
29+
},
30+
"static_object_speed_threshold": {
31+
"type": "number",
32+
"description": "Threshold to determine the flag `is_stationary`. If the velocity is lower than this parameter, the flag `is_stationary` of DetectedObject is set to `true` and dealt as a static object.",
33+
"default": "1.0"
34+
}
35+
},
36+
"required": [
37+
"update_rate_hz",
38+
"new_frame_id",
39+
"use_twist_compensation",
40+
"use_twist_yaw_compensation",
41+
"static_object_speed_threshold"
42+
]
43+
}
44+
},
45+
"properties": {
46+
"/**": {
47+
"type": "object",
48+
"properties": {
49+
"ros__parameters": {
50+
"$ref": "#/definitions/radar_tracks_msgs_converter"
51+
}
52+
},
53+
"required": ["ros__parameters"]
54+
}
55+
},
56+
"required": ["/**"]
57+
}

0 commit comments

Comments
 (0)