From 5d2ac41c7aafc9e4929ba04598437452afe587cb Mon Sep 17 00:00:00 2001 From: kaspermeck-arm Date: Thu, 29 Feb 2024 19:21:40 -0800 Subject: [PATCH 1/4] refactor(radar_tracks_msgs_converter) Rework parameters Signed-off-by: kaspermeck-arm Change-Id: If28e9c97bc6db3b522c680f215b3f8cb95ec58b7 --- .../radar_tracks_msgs_converter/README.md | 29 +--------- .../radar_tracks_msgs_converter.launch.xml | 4 +- .../radar_tracks_msgs_converter.schema.json | 57 +++++++++++++++++++ 3 files changed, 60 insertions(+), 30 deletions(-) create mode 100644 perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index b55755fb96f92..76ea80a881a5b 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -52,31 +52,4 @@ Autoware objects label is defined in [ObjectClassification.idl](https://gitlab.c ### Parameters -- `update_rate_hz` (double) [hz] - - Default parameter is 20.0 - -This parameter is update rate for the `onTimer` function. -This parameter should be same as the frame rate of input topics. - -- `new_frame_id` (string) - - Default parameter is "base_link" - -This parameter is the header frame_id of the output topic. - -- `use_twist_compensation` (bool) - - Default parameter is "true" - -This parameter is the flag to use the compensation to linear of ego vehicle's twist. -If the parameter is true, then the twist of the output objects' topic is compensated by the ego vehicle linear motion. - -- `use_twist_yaw_compensation` (bool) - - Default parameter is "false" - -This parameter is the flag to use the compensation to yaw rotation of ego vehicle's twist. -If the parameter is true, then the ego motion compensation will also consider yaw motion of the ego vehicle. - -- `static_object_speed_threshold` (float) [m/s] - - Default parameter is 1.0 - -This parameter is the 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. +{{ json_to_markdown("perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }} diff --git a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml index 1aa4d51703b0c..97fb5748efecc 100644 --- a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml +++ b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml @@ -3,13 +3,13 @@ - + - + diff --git a/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json new file mode 100644 index 0000000000000..ee01647d613b6 --- /dev/null +++ b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json @@ -0,0 +1,57 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Radar Tracks Msgs Converter node", + "type": "object", + "definitions": { + "radar_tracks_msgs_converter": { + "type": "object", + "properties": { + "update_rate_hz": { + "type": "number", + "description": "The update rate [hz] for the `onTimer` function. Should be the same as the frame rate of input topics.", + "default": "20.0", + "minimum": 0.0 + }, + "new_frame_id": { + "type": "string", + "description": "The header frame_id of the output topic.", + "default": "base_link" + }, + "use_twist_compensation": { + "type": "boolean", + "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.", + "default": "false" + }, + "use_twist_yaw_compensation": { + "type": "boolean", + "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.", + "default": "false" + }, + "static_object_speed_threshold": { + "type": "number", + "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.", + "default": "1.0" + } + }, + "required": [ + "update_rate_hz", + "new_frame_id", + "use_twist_compensation", + "use_twist_yaw_compensation", + "static_object_speed_threshold" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/radar_tracks_msgs_converter" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} \ No newline at end of file From 82036400117ecb7d1cf7dae0f6acb38feef1d1ec Mon Sep 17 00:00:00 2001 From: Ryohsuke Mitsudome Date: Fri, 1 Mar 2024 16:48:08 +0900 Subject: [PATCH 2/4] fix: restore parameter description and make json schema description simpler Signed-off-by: Ryohsuke Mitsudome --- .../radar_tracks_msgs_converter/README.md | 33 +++++++++++++++++++ .../radar_tracks_msgs_converter.schema.json | 10 +++--- 2 files changed, 38 insertions(+), 5 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index 76ea80a881a5b..3992e5933c54e 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -52,4 +52,37 @@ Autoware objects label is defined in [ObjectClassification.idl](https://gitlab.c ### Parameters +#### Parameter Summary {{ json_to_markdown("perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }} + +#### Parameter Description + +- `update_rate_hz` (double) [hz] + - Default parameter is 20.0 + +This parameter is update rate for the `onTimer` function. +This parameter should be same as the frame rate of input topics. + +- `new_frame_id` (string) + - Default parameter is "base_link" + +This parameter is the header frame_id of the output topic. + +- `use_twist_compensation` (bool) + - Default parameter is "true" + +This parameter is the flag to use the compensation to linear of ego vehicle's twist. +If the parameter is true, then the twist of the output objects' topic is compensated by the ego vehicle linear motion. + +- `use_twist_yaw_compensation` (bool) + - Default parameter is "false" + +This parameter is the flag to use the compensation to yaw rotation of ego vehicle's twist. +If the parameter is true, then the ego motion compensation will also consider yaw motion of the ego vehicle. + +- `static_object_speed_threshold` (float) [m/s] + - Default parameter is 1.0 + +This parameter is the 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. + diff --git a/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json index ee01647d613b6..767235f2e1666 100644 --- a/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json +++ b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json @@ -8,28 +8,28 @@ "properties": { "update_rate_hz": { "type": "number", - "description": "The update rate [hz] for the `onTimer` function. Should be the same as the frame rate of input topics.", + "description": "The update rate [hz] of the output topic", "default": "20.0", "minimum": 0.0 }, "new_frame_id": { "type": "string", - "description": "The header frame_id of the output topic.", + "description": "The header frame_id of the output topic", "default": "base_link" }, "use_twist_compensation": { "type": "boolean", - "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.", + "description": "Flag to enable the linear compensation of ego vehicle's twist", "default": "false" }, "use_twist_yaw_compensation": { "type": "boolean", - "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.", + "description": "Flag to enable the compensation of yaw rotation of ego vehicle's twist", "default": "false" }, "static_object_speed_threshold": { "type": "number", - "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.", + "description": "Threshold to treat detected objects as static objects", "default": "1.0" } }, From dc26b46919845bf06b0a9e3d9300444bfc41e89e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Sat, 2 Mar 2024 00:25:57 +0000 Subject: [PATCH 3/4] style(pre-commit): autofix --- perception/radar_tracks_msgs_converter/README.md | 2 +- .../schema/radar_tracks_msgs_converter.schema.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/README.md b/perception/radar_tracks_msgs_converter/README.md index 3992e5933c54e..e976e342e3d9f 100644 --- a/perception/radar_tracks_msgs_converter/README.md +++ b/perception/radar_tracks_msgs_converter/README.md @@ -53,6 +53,7 @@ Autoware objects label is defined in [ObjectClassification.idl](https://gitlab.c ### Parameters #### Parameter Summary + {{ json_to_markdown("perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json") }} #### Parameter Description @@ -85,4 +86,3 @@ If the parameter is true, then the ego motion compensation will also consider ya This parameter is the 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. - diff --git a/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json index 767235f2e1666..396dbcd413ee8 100644 --- a/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json +++ b/perception/radar_tracks_msgs_converter/schema/radar_tracks_msgs_converter.schema.json @@ -54,4 +54,4 @@ } }, "required": ["/**"] -} \ No newline at end of file +} From 78671eafa7d4cd5b5efea1c2b5b82cf602e7ab13 Mon Sep 17 00:00:00 2001 From: kaspermeck-arm Date: Mon, 4 Mar 2024 06:36:18 -0800 Subject: [PATCH 4/4] Updated param file path Signed-off-by: kaspermeck-arm Change-Id: Ic6b6fd98ba2c0e2a5510ff08cf563877d1205bb9 --- .../launch/radar_tracks_msgs_converter.launch.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml index 97fb5748efecc..1aa4d51703b0c 100644 --- a/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml +++ b/perception/radar_tracks_msgs_converter/launch/radar_tracks_msgs_converter.launch.xml @@ -3,13 +3,13 @@ - + - +