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/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..66a608b0d6a2d --- /dev/null +++ b/perception/autoware_traffic_light_multi_camera_fusion/schema/traffic_light_multi_camera_fusion.schema.json @@ -0,0 +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": [] + }, + "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 +} 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";