From 2f91cac74f7f557427b1fbd1af5e94f35ed1131a Mon Sep 17 00:00:00 2001 From: vish0012 Date: Tue, 21 Jan 2025 12:00:59 +0900 Subject: [PATCH 1/6] feat(autoware_traffic_light_multi_camera_fusion): Created Schema file and updated ReadME file for parameters setting Signed-off-by: vish0012 --- .../README.md | 7 +-- ...ffic_light_multi_camera_fusion.schema.json | 57 +++++++++++++++++++ ...traffic_light_multi_camera_fusion_node.cpp | 2 +- 3 files changed, 59 insertions(+), 7 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 f7ee294cda147..dea583d8db5cb 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/README.md +++ b/perception/autoware_traffic_light_multi_camera_fusion/README.md @@ -27,9 +27,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") }} \ No newline at end of file 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..455c1f64ee683 --- /dev/null +++ b/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json @@ -0,0 +1,57 @@ +{ + "$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 + }, + "perform_group_fusion": { + "type": "boolean", + "description": "Whether to perform Group Fusion.", + "default": false + } + }, + "required": [ + "camera_namespaces", + "message_lifespan", + "approximate_sync", + "perform_group_fusion" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/autoware_traffic_light_multi_camera_fusion" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false + } + \ No newline at end of file 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..1b8971d6f6e7d 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 @@ -150,7 +150,7 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) 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); + 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"; From 06854fa940b56fb161e91299f92928e85ddd1914 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 27 Jan 2025 05:08:29 +0000 Subject: [PATCH 2/6] style(pre-commit): autofix --- .../README.md | 2 +- ...ffic_light_multi_camera_fusion.schema.json | 105 +++++++++--------- 2 files changed, 53 insertions(+), 54 deletions(-) diff --git a/perception/autoware_traffic_light_multi_camera_fusion/README.md b/perception/autoware_traffic_light_multi_camera_fusion/README.md index dea583d8db5cb..446fc73a5dd3e 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/README.md +++ b/perception/autoware_traffic_light_multi_camera_fusion/README.md @@ -27,4 +27,4 @@ You don't need to configure these topics manually. Just provide the `camera_name ## Node parameters -{{ json_to_markdown("perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json") }} \ No newline at end of file +{{ 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/schema/traffic_light_multi_camera_fusion.schema.json b/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json index 455c1f64ee683..66a608b0d6a2d 100644 --- 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 @@ -1,57 +1,56 @@ { - "$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": [] + "$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" }, - "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 - }, - "perform_group_fusion": { - "type": "boolean", - "description": "Whether to perform Group Fusion.", - "default": false - } + "default": [] + }, + "message_lifespan": { + "type": "number", + "description": "The maximum timestamp span to be fused.", + "default": 0.0 }, - "required": [ - "camera_namespaces", - "message_lifespan", - "approximate_sync", - "perform_group_fusion" - ], - "additionalProperties": false - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/autoware_traffic_light_multi_camera_fusion" - } + "approximate_sync": { + "type": "boolean", + "description": "Whether to work in Approximate Synchronization Mode.", + "default": false }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false - } - \ No newline at end of file + "perform_group_fusion": { + "type": "boolean", + "description": "Whether to perform Group Fusion.", + "default": false + } + }, + "required": [ + "camera_namespaces", + "message_lifespan", + "approximate_sync", + "perform_group_fusion" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/autoware_traffic_light_multi_camera_fusion" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} From 9573ae3429f69bc9b83c13c3cb5bcda387db6776 Mon Sep 17 00:00:00 2001 From: vish0012 Date: Tue, 28 Jan 2025 10:01:32 +0900 Subject: [PATCH 3/6] fix: updated param file , schema and node.cpp file for traffic_light_multi_camera_fusion as per review comments Signed-off-by: vish0012 --- .../config/traffic_light_multi_camera_fusion.param.yaml | 2 +- .../schema/traffic_light_multi_camera_fusion.schema.json | 8 +------- .../src/traffic_light_multi_camera_fusion_node.cpp | 4 ++-- 3 files changed, 4 insertions(+), 10 deletions(-) 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..5a791d082a23e 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,4 @@ 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 index 66a608b0d6a2d..77dc393a09def 100644 --- 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 @@ -23,18 +23,12 @@ "type": "boolean", "description": "Whether to work in Approximate Synchronization Mode.", "default": false - }, - "perform_group_fusion": { - "type": "boolean", - "description": "Whether to perform Group Fusion.", - "default": false } }, "required": [ "camera_namespaces", "message_lifespan", - "approximate_sync", - "perform_group_fusion" + "approximate_sync" ], "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 1b8971d6f6e7d..e3e21640dfcf8 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,8 +148,8 @@ 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); + 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"; From e908af6f697a98e66de97f22b1063d88fa87c3bf Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 28 Jan 2025 01:05:30 +0000 Subject: [PATCH 4/6] style(pre-commit): autofix --- .../config/traffic_light_multi_camera_fusion.param.yaml | 2 +- .../schema/traffic_light_multi_camera_fusion.schema.json | 6 +----- .../src/traffic_light_multi_camera_fusion_node.cpp | 2 +- 3 files changed, 3 insertions(+), 7 deletions(-) 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 5a791d082a23e..21fc241837609 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,4 @@ camera_namespaces: ["camera6", "camera7"] message_lifespan: 0.09 approximate_sync: false - + 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 index 77dc393a09def..bdd6dca516fa5 100644 --- 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 @@ -25,11 +25,7 @@ "default": false } }, - "required": [ - "camera_namespaces", - "message_lifespan", - "approximate_sync" - ], + "required": ["camera_namespaces", "message_lifespan", "approximate_sync"], "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 e3e21640dfcf8..b9226be0949cb 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 @@ -149,7 +149,7 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) std::vector camera_namespaces = this->declare_parameter>("camera_namespaces"); - is_approximate_sync_ = this->declare_parameter("approximate_sync",); + 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"; From bbf94fb22159c91406c730ea5d93820904ae84db Mon Sep 17 00:00:00 2001 From: Vishal Chauhan <40782713+vish0012@users.noreply.github.com> Date: Wed, 5 Feb 2025 12:46:45 +0900 Subject: [PATCH 5/6] Update traffic_light_multi_camera_fusion_node.cpp updated code as per suggestion --- .../src/traffic_light_multi_camera_fusion_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 b9226be0949cb..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 @@ -149,7 +149,7 @@ MultiCameraFusion::MultiCameraFusion(const rclcpp::NodeOptions & node_options) std::vector camera_namespaces = this->declare_parameter>("camera_namespaces"); - is_approximate_sync_ = this->declare_parameter("approximate_sync", ); + 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"; From 837d0d5c1dd0839613c2069bf67d931eb87e127b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 5 Feb 2025 03:49:29 +0000 Subject: [PATCH 6/6] style(pre-commit): autofix --- .../config/traffic_light_multi_camera_fusion.param.yaml | 1 - 1 file changed, 1 deletion(-) 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 21fc241837609..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 -