Skip to content

Commit

Permalink
refactor(autoware_lidar_transfusion): split config (autowarefoundatio…
Browse files Browse the repository at this point in the history
…n#8205)

* refactor(autoware_lidar_transfusion): split config

Signed-off-by: Amadeusz Szymko <amadeusz.szymko.2@tier4.jp>

* style(pre-commit): autofix

* chore(autoware_lidar_transfusion): bypass schema CI workflow

Signed-off-by: amadeuszsz <amadeusz.szymko.2@tier4.jp>

---------

Signed-off-by: Amadeusz Szymko <amadeusz.szymko.2@tier4.jp>
Signed-off-by: amadeuszsz <amadeusz.szymko.2@tier4.jp>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
  • Loading branch information
3 people authored Sep 3, 2024
1 parent 1c2b07b commit 631d967
Show file tree
Hide file tree
Showing 7 changed files with 93 additions and 62 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@
<arg name="model_name" value="$(var transfusion_model_name)"/>
<arg name="model_path" value="$(var transfusion_model_path)"/>
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var transfusion_model_name).param.yaml"/>
<arg name="class_remapper_param_path" value="$(var lidar_model_param_path)/detection_class_remapper.param.yaml"/>
<arg name="ml_package_param_path" value="$(var transfusion_model_path)/$(var transfusion_model_name)_ml_package.param.yaml"/>
<arg name="class_remapper_param_path" value="$(var transfusion_model_path)/detection_class_remapper.param.yaml"/>

<arg name="use_pointcloud_container" value="true"/>
<arg name="pointcloud_container_name" value="$(var node/pointcloud_container)"/>
Expand Down
8 changes: 6 additions & 2 deletions perception/autoware_lidar_transfusion/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,13 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.

## Parameters

### TransFusion
### TransFusion node

{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion.schema.json") }}
{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion.schema.dummy.json") }}

### TransFusion model

{{ json_to_markdown("perception/autoware_lidar_transfusion/schema/transfusion_ml_package.schema.json") }}

### Detection class remapper

Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,8 @@
/**:
ros__parameters:
# network
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
trt_precision: fp16
cloud_capacity: 2000000
voxels_num: [5000, 30000, 60000] # [min, opt, max]
point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.24, 0.24, 10.0] # [x, y, z]
num_proposals: 500
onnx_path: "$(var model_path)/transfusion.onnx"
engine_path: "$(var model_path)/transfusion.engine"
# pre-process params
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
voxels_num: [5000, 30000, 60000] # [min, opt, max]
point_cloud_range: [-92.16, -92.16, -3.0, 92.16, 92.16, 7.0] # [x_min, y_min, z_min, x_max, y_max, z_max]
voxel_size: [0.24, 0.24, 10.0] # [x, y, z]
num_proposals: 500
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,10 @@
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud"/>
<arg name="output/objects" default="objects"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="model_name" default="transfusion" description="options: `transfusion`"/>
<arg name="model_path" default="$(var data_path)/lidar_transfusion"/>
<arg name="model_param_path" default="$(find-pkg-share autoware_lidar_transfusion)/config/transfusion.param.yaml"/>
<arg name="model_param_path" default="$(find-pkg-share autoware_lidar_transfusion)/config/$(var model_name).param.yaml"/>
<arg name="ml_package_param_path" default="$(var model_path)/$(var model_name)_ml_package.param.yaml"/>
<arg name="class_remapper_param_path" default="$(find-pkg-share autoware_lidar_transfusion)/config/detection_class_remapper.param.yaml"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
<arg name="log_level" default="info"/>
Expand All @@ -18,6 +20,7 @@
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
<param from="$(var ml_package_param_path)" allow_substs="true"/>
<param from="$(var class_remapper_param_path)"/>

<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
Expand All @@ -30,6 +33,7 @@
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param from="$(var model_param_path)" allow_substs="true"/>
<param from="$(var ml_package_param_path)" allow_substs="true"/>
<param from="$(var class_remapper_param_path)"/>

<!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 -->
Expand Down
Original file line number Diff line number Diff line change
@@ -1,20 +1,12 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for LiDAR TransFusion Node",
"$comment": "This schema is not considered in CI workflow. See https://github.com/autowarefoundation/autoware.universe/pull/8205#issuecomment-2255074224.",
"type": "object",
"definitions": {
"transfusion": {
"type": "object",
"properties": {
"class_names": {
"type": "array",
"items": {
"type": "string"
},
"description": "An array of class names will be predicted.",
"default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"],
"uniqueItems": true
},
"trt_precision": {
"type": "string",
"description": "A precision of TensorRT engine.",
Expand All @@ -27,34 +19,6 @@
"default": 2000000,
"minimum": 1
},
"voxels_num": {
"type": "array",
"items": {
"type": "integer"
},
"description": "A maximum number of voxels [min, opt, max].",
"default": [5000, 30000, 60000]
},
"point_cloud_range": {
"type": "array",
"items": {
"type": "number"
},
"description": "An array of distance ranges of each class.",
"default": [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0],
"minItems": 6,
"maxItems": 6
},
"voxel_size": {
"type": "array",
"items": {
"type": "number"
},
"description": "Voxels size [x, y, z].",
"default": [0.3, 0.3, 8.0],
"minItems": 3,
"maxItems": 3
},
"onnx_path": {
"type": "string",
"description": "A path to ONNX model file.",
Expand All @@ -67,18 +31,6 @@
"default": "$(var model_path)/transfusion.engine",
"pattern": "\\.engine$"
},
"num_proposals": {
"type": "integer",
"description": "Number of proposals at TransHead.",
"default": 500,
"minimum": 1
},
"down_sample_factor": {
"type": "integer",
"description": "A scale factor of downsampling points",
"default": 1,
"minimum": 1
},
"densification_num_past_frames": {
"type": "integer",
"description": "A number of past frames to be considered as same input frame.",
Expand Down Expand Up @@ -136,11 +88,8 @@
}
},
"required": [
"class_names",
"trt_precision",
"voxels_num",
"point_cloud_range",
"voxel_size",
"cloud_capacity",
"onnx_path",
"engine_path",
"densification_num_past_frames",
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for LiDAR TransFusion Node",
"type": "object",
"definitions": {
"transfusion": {
"type": "object",
"properties": {
"class_names": {
"type": "array",
"items": {
"type": "string"
},
"description": "An array of class names will be predicted.",
"default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"],
"uniqueItems": true
},
"voxels_num": {
"type": "array",
"items": {
"type": "integer"
},
"description": "A maximum number of voxels [min, opt, max].",
"default": [5000, 30000, 60000]
},
"point_cloud_range": {
"type": "array",
"items": {
"type": "number"
},
"description": "An array of distance ranges of each class.",
"default": [-76.8, -76.8, -3.0, 76.8, 76.8, 5.0],
"minItems": 6,
"maxItems": 6
},
"voxel_size": {
"type": "array",
"items": {
"type": "number"
},
"description": "Voxels size [x, y, z].",
"default": [0.3, 0.3, 8.0],
"minItems": 3,
"maxItems": 3
},
"num_proposals": {
"type": "integer",
"description": "Number of proposals at TransHead.",
"default": 500,
"minimum": 1
}
},
"required": ["class_names", "voxels_num", "point_cloud_range", "voxel_size", "num_proposals"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/transfusion"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}

0 comments on commit 631d967

Please sign in to comment.