From 15ce10e7d5c6a22c7d3559a859fa066fce34cb15 Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 5 Feb 2025 15:07:04 +0900 Subject: [PATCH] chore(autoware_traffic_light_multi_camera_fusion): created Schema file and updated ReadME file for parameters setting (#9994) * feat(autoware_traffic_light_multi_camera_fusion): Created Schema file and updated ReadME file for parameters setting Signed-off-by: vish0012 * style(pre-commit): autofix * fix: updated param file , schema and node.cpp file for traffic_light_multi_camera_fusion as per review comments Signed-off-by: vish0012 * style(pre-commit): autofix * Update traffic_light_multi_camera_fusion_node.cpp updated code as per suggestion * style(pre-commit): autofix --------- Signed-off-by: vish0012 Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../README.md | 7 +-- ...affic_light_multi_camera_fusion.param.yaml | 1 - ...ffic_light_multi_camera_fusion.schema.json | 46 +++++++++++++++++++ ...traffic_light_multi_camera_fusion_node.cpp | 6 +-- 4 files changed, 50 insertions(+), 10 deletions(-) create mode 100644 perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json diff --git a/perception/autoware_traffic_light_multi_camera_fusion/README.md b/perception/autoware_traffic_light_multi_camera_fusion/README.md index b54c623f5d750..ff260546fd0cb 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/README.md +++ b/perception/autoware_traffic_light_multi_camera_fusion/README.md @@ -34,9 +34,4 @@ You don't need to configure these topics manually. Just provide the `camera_name ## Node parameters -| Parameter | Type | Description | -| ---------------------- | --------------- | ------------------------------------------------ | -| `camera_namespaces` | vector\ | Camera Namespaces to be fused | -| `message_lifespan` | double | The maximum timestamp span to be fused | -| `approximate_sync` | bool | Whether work in Approximate Synchronization Mode | -| `perform_group_fusion` | bool | Whether perform Group Fusion | +{{ json_to_markdown("perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json") }} diff --git a/perception/autoware_traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml b/perception/autoware_traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml index 4e9459ce4a71c..62f8d47bf7525 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml +++ b/perception/autoware_traffic_light_multi_camera_fusion/config/traffic_light_multi_camera_fusion.param.yaml @@ -3,4 +3,3 @@ camera_namespaces: ["camera6", "camera7"] message_lifespan: 0.09 approximate_sync: false - perform_group_fusion: true diff --git a/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json b/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json new file mode 100644 index 0000000000000..bdd6dca516fa5 --- /dev/null +++ b/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json @@ -0,0 +1,46 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_traffic_light_multi_camera_fusion parameter", + "type": "object", + "definitions": { + "autoware_traffic_light_multi_camera_fusion": { + "type": "object", + "properties": { + "camera_namespaces": { + "type": "array", + "description": "Camera namespaces to be fused.", + "items": { + "type": "string" + }, + "default": [] + }, + "message_lifespan": { + "type": "number", + "description": "The maximum timestamp span to be fused.", + "default": 0.0 + }, + "approximate_sync": { + "type": "boolean", + "description": "Whether to work in Approximate Synchronization Mode.", + "default": false + } + }, + "required": ["camera_namespaces", "message_lifespan", "approximate_sync"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/autoware_traffic_light_multi_camera_fusion" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp index 15211920bc7f2..8655e3fabe334 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp @@ -148,9 +148,9 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) using std::placeholders::_3; std::vector camera_namespaces = - this->declare_parameter("camera_namespaces", std::vector{}); - is_approximate_sync_ = this->declare_parameter("approximate_sync", false); - message_lifespan_ = this->declare_parameter("message_lifespan", 0.09); + this->declare_parameter>("camera_namespaces"); + is_approximate_sync_ = this->declare_parameter("approximate_sync"); + message_lifespan_ = this->declare_parameter("message_lifespan"); for (const std::string & camera_ns : camera_namespaces) { std::string signal_topic = camera_ns + "/classification/traffic_signals"; std::string roi_topic = camera_ns + "/detection/rois";