diff --git a/perception/autoware_lidar_apollo_instance_segmentation/README.md b/perception/autoware_lidar_apollo_instance_segmentation/README.md index edc3d99e0967f..5bf57667f5538 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/README.md +++ b/perception/autoware_lidar_apollo_instance_segmentation/README.md @@ -28,26 +28,11 @@ See the [original design](https://github.com/ApolloAuto/apollo/blob/r6.0.0/docs/ ## Parameters -### Node Parameters - -None - -### Core Parameters - -| Name | Type | Default Value | Description | -| ----------------------- | ------ | -------------------- | ---------------------------------------------------------------------------------- | -| `score_threshold` | double | 0.8 | If the score of a detected object is lower than this value, the object is ignored. | -| `range` | int | 60 | Half of the length of feature map sides. [m] | -| `width` | int | 640 | The grid width of feature map. | -| `height` | int | 640 | The grid height of feature map. | -| `engine_file` | string | "vls-128.engine" | The name of TensorRT engine file for CNN model. | -| `prototxt_file` | string | "vls-128.prototxt" | The name of prototxt file for CNN model. | -| `caffemodel_file` | string | "vls-128.caffemodel" | The name of caffemodel file for CNN model. | -| `use_intensity_feature` | bool | true | The flag to use intensity feature of pointcloud. | -| `use_constant_feature` | bool | false | The flag to use direction and distance feature of pointcloud. | -| `target_frame` | string | "base_link" | Pointcloud data is transformed into this frame. | -| `z_offset` | int | 2 | z offset from target frame. [m] | -| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | +{{ json_to_markdown("perception/autoware_lidar_apollo_instance_segmentation/schema/hdl-64.schema.json") }} + +{{ json_to_markdown("perception/autoware_lidar_apollo_instance_segmentation/schema/vlp-16.schema.json") }} + +{{ json_to_markdown("perception/autoware_lidar_apollo_instance_segmentation/schema/vls-128.schema.json") }} ## Assumptions / Known limits diff --git a/perception/autoware_lidar_apollo_instance_segmentation/schema/hdl-64.schema.json b/perception/autoware_lidar_apollo_instance_segmentation/schema/hdl-64.schema.json new file mode 100644 index 0000000000000..856fd1b922493 --- /dev/null +++ b/perception/autoware_lidar_apollo_instance_segmentation/schema/hdl-64.schema.json @@ -0,0 +1,72 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_lidar_apollo_instance_segmentation parameters", + "type": "object", + "definitions": { + "hdl-64": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "If the score of a detected object is lower than this value, the object is ignored.", + "default": 0.1 + }, + "range": { + "type": "integer", + "description": "Half of the length of feature map sides. [m]", + "default": 70 + }, + "width": { + "type": "integer", + "description": "The grid width of the feature map.", + "default": 672 + }, + "height": { + "type": "integer", + "description": "The grid height of the feature map.", + "default": 672 + }, + "use_intensity_feature": { + "type": "boolean", + "description": "The flag to use intensity feature of pointcloud.", + "default": true + }, + "use_constant_feature": { + "type": "boolean", + "description": "The flag to use direction and distance feature of pointcloud.", + "default": false + } + }, + "required": [ + "score_threshold", + "range", + "width", + "height", + "use_intensity_feature", + "use_constant_feature" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "type": "object", + "properties": { + "lidar_instance_segmentation": { + "$ref": "#/definitions/hdl-64" + } + }, + "required": ["lidar_instance_segmentation"], + "additionalProperties": false + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_lidar_apollo_instance_segmentation/schema/vlp-16.schema.json b/perception/autoware_lidar_apollo_instance_segmentation/schema/vlp-16.schema.json new file mode 100644 index 0000000000000..4abe7193ffbf8 --- /dev/null +++ b/perception/autoware_lidar_apollo_instance_segmentation/schema/vlp-16.schema.json @@ -0,0 +1,72 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_lidar_apollo_instance_segmentation paramters", + "type": "object", + "definitions": { + "vlp-16": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "If the score of a detected object is lower than this value, the object is ignored.", + "default": 0.1 + }, + "range": { + "type": "integer", + "description": "Half of the length of feature map sides. [m]", + "default": 70 + }, + "width": { + "type": "integer", + "description": "The grid width of the feature map.", + "default": 672 + }, + "height": { + "type": "integer", + "description": "The grid height of the feature map.", + "default": 672 + }, + "use_intensity_feature": { + "type": "boolean", + "description": "The flag to use intensity feature of pointcloud.", + "default": true + }, + "use_constant_feature": { + "type": "boolean", + "description": "The flag to use direction and distance feature of pointcloud.", + "default": false + } + }, + "required": [ + "score_threshold", + "range", + "width", + "height", + "use_intensity_feature", + "use_constant_feature" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "type": "object", + "properties": { + "lidar_instance_segmentation": { + "$ref": "#/definitions/vlp-16" + } + }, + "required": ["lidar_instance_segmentation"], + "additionalProperties": false + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/perception/autoware_lidar_apollo_instance_segmentation/schema/vls-128.schema.json b/perception/autoware_lidar_apollo_instance_segmentation/schema/vls-128.schema.json new file mode 100644 index 0000000000000..e69de29bb2d1d diff --git a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp index 60aa09c8e16d7..f1e8f1ba35b44 100644 --- a/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/autoware_lidar_apollo_instance_segmentation/src/detector.cpp @@ -39,15 +39,15 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * int range, width, height; bool use_intensity_feature, use_constant_feature; std::string onnx_file; - score_threshold_ = node_->declare_parameter("score_threshold", 0.8); - range = node_->declare_parameter("range", 60); - width = node_->declare_parameter("width", 640); - height = node_->declare_parameter("height", 640); + score_threshold_ = node_->declare_parameter("score_threshold"); + range = node_->declare_parameter("range"); + width = node_->declare_parameter("width"); + height = node_->declare_parameter("height"); onnx_file = node_->declare_parameter("onnx_file", "vls-128.onnx"); - use_intensity_feature = node_->declare_parameter("use_intensity_feature", true); - use_constant_feature = node_->declare_parameter("use_constant_feature", true); + use_intensity_feature = node_->declare_parameter("use_intensity_feature"); + use_constant_feature = node_->declare_parameter("use_constant_feature"); target_frame_ = node_->declare_parameter("target_frame", "base_link"); - z_offset_ = node_->declare_parameter("z_offset", -2.0); + z_offset_ = node_->declare_parameter("z_offset"); const auto precision = node_->declare_parameter("precision", "fp32"); trt_common_ = std::make_unique(