Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(lidar_centerpoint): rework parameters #7421

Closed
Closed
Show file tree
Hide file tree
Changes from 26 commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
6015bd2
Refractored parameter for lidar_centerpoint node.
tby-udel Jun 10, 2024
0e04bf2
style(pre-commit): autofix
pre-commit-ci[bot] Jun 10, 2024
a62d396
Correcting the errors.
tby-udel Jun 11, 2024
89d39ab
Merge remote-tracking branch 'upstream/main' into lidar-centerpoint-b…
tby-udel Jun 11, 2024
25cc93e
Update centerpoint_tiny.schema.json
tby-udel Jun 11, 2024
6832e40
Merge branch 'main' into lidar-centerpoint-branch
tby-udel Jun 17, 2024
3192d5b
Merge branch 'main' into lidar-centerpoint-branch
tby-udel Jun 17, 2024
b90febd
renamed centerpoint_ files to centerpoint_base files, made modificati…
tby-udel Jun 17, 2024
604714d
Merge remote-tracking branch 'upstream/main' into lidar-centerpoint-b…
tby-udel Jun 17, 2024
dd2be88
renamed centerpoint_ files to centerpoint_base files, made modificati…
tby-udel Jun 17, 2024
5575a1e
Update centerpoint_base.schemal.json
tby-udel Jun 17, 2024
feb3980
Update centerpoint_base_ml_package.schema.json
tby-udel Jun 17, 2024
2e12712
Update centerpoint_base.param.yaml
tby-udel Jun 17, 2024
94a7779
Changed to (var model_name)_base.param.yaml, renamed some files, corr…
tby-udel Jun 21, 2024
fe8f7f9
Fixed centerpoint_ml_package
tby-udel Jun 24, 2024
b295afc
Changed the definition part of centerpoint_ml_package.schema.json.
tby-udel Jul 1, 2024
5f0a9b6
Merge branch 'main' into lidar-centerpoint-branch
tby-udel Jul 1, 2024
c61e833
Reorganized the readme file.
tby-udel Jul 6, 2024
6bbd978
Required changes are made.
tby-udel Jul 8, 2024
faef3d4
Merge branch 'main' into lidar-centerpoint-branch
knzo25 Jul 9, 2024
d364678
Requested changes for tier4_perception_launch and README.md have been…
tby-udel Jul 11, 2024
bb378d6
Merge branch 'lidar-centerpoint-branch' of https://github.com/tby-ude…
tby-udel Jul 11, 2024
cca3de3
style(pre-commit): autofix
pre-commit-ci[bot] Jul 11, 2024
7bf36eb
All requested changes are made.
tby-udel Jul 14, 2024
47ee2c7
All requested changes are made.
tby-udel Jul 14, 2024
5f68013
style(pre-commit): autofix
pre-commit-ci[bot] Jul 14, 2024
e389dc0
Updated the README.md file
tby-udel Jul 17, 2024
e8c1705
Merge branch 'main' into lidar-centerpoint-branch
tby-udel Jul 22, 2024
592baf6
Rename centerpoint_base.schemal.json to centerpoint_base.schema.json
tby-udel Jul 23, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@
<arg name="output/objects" value="$(var output/objects)"/>
<arg name="model_name" value="$(var centerpoint_model_name)"/>
<arg name="model_path" value="$(var centerpoint_model_path)"/>
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name).param.yaml"/>
<arg name="model_param_path" value="$(var lidar_model_param_path)/$(var centerpoint_model_name)_base.param.yaml"/>
<arg name="ml_package_param_path" value="$(var centerpoint_model_path)/$(var centerpoint_model_name)_ml_package.param.yaml"/>
<arg name="class_remapper_param_path" value="$(var centerpoint_model_path)/detection_class_remapper.param.yaml"/>

Expand Down
63 changes: 16 additions & 47 deletions perception/lidar_centerpoint/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,33 +28,21 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.

## Parameters

### Core Parameters

| Name | Type | Default Value | Description |
| ------------------------------------------------ | ------------ | ------------------------- | ------------------------------------------------------------- |
| `encoder_onnx_path` | string | `""` | path to VoxelFeatureEncoder ONNX file |
| `encoder_engine_path` | string | `""` | path to VoxelFeatureEncoder TensorRT Engine file |
| `head_onnx_path` | string | `""` | path to DetectionHead ONNX file |
| `head_engine_path` | string | `""` | path to DetectionHead TensorRT Engine file |
| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built |
| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` |
| `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored |
| `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. |
| `post_process_params.iou_nms_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression |
| `post_process_params.iou_nms_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. |
| `post_process_params.iou_nms_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression |
| `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. |
| `densification_params.world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud |
| `densification_params.num_past_frames` | int | `1` | the number of past frames to fuse with the current frame |
### Core Parameters for base methods

### The `build_only` option
{{ json_to_markdown("perception/lidar_centerpoint/schema/centerpoint_base.schema.json") }}

The `lidar_centerpoint` node has `build_only` option to build the TensorRT engine file from the ONNX file.
Although it is preferred to move all the ROS parameters in `.param.yaml` file in Autoware Universe, the `build_only` option is not moved to the `.param.yaml` file for now, because it may be used as a flag to execute the build as a pre-task. You can execute with the following command:
### Core Parameters for ML methods

```bash
ros2 launch lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
```
{{ json_to_markdown("perception/lidar_centerpoint/schema/centerpoint_ml_package.schema.json") }}

### Remapper

{{ json_to_markdown("perception/lidar_centerpoint/schema/detection_class_remapper.schema.json") }}

### The `build_only` option

The `lidar_centerpoint` node has a `build_only` option to build the required TensorRT engine file from an ONNX file. This parameter is set in the launch file of this package, whereas all other parameters are set via `.param.yaml` files.

## Assumptions / Known limits

Expand Down Expand Up @@ -234,35 +222,16 @@ You can find it in `mmdetection3d/projects/AutowareCenterPoint` file.
python projects/AutowareCenterPoint/centerpoint_onnx_converter.py --cfg projects/AutowareCenterPoint/configs/centerpoint_custom.py --ckpt work_dirs/centerpoint_custom/YOUR_BEST_MODEL.pth --work-dir ./work_dirs/onnx_models
```

#### Create the config file for the custom model

Create a new config file named **centerpoint_custom.param.yaml** under the config file directory of the lidar_centerpoint node. Sets the parameters of the config file like
point_cloud_range, point_feature_size, voxel_size, etc. according to the training config file.

```yaml
/**:
ros__parameters:
class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
point_feature_size: 4
max_voxel_size: 40000
point_cloud_range: [-51.2, -51.2, -3.0, 51.2, 51.2, 5.0]
voxel_size: [0.2, 0.2, 8.0]
downsample_factor: 1
encoder_in_feature_size: 9
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
```
#### Adjust the config file for the custom model

All the ROS parameters have been moved into `.param.yaml` files, please set the parameters of the config file like point*cloud_range, point_feature_size, voxel_size, etc. in the config files. \*\*centerpoint*(your_selection_of_model).param.yaml\*\* files are under the config file directory of the lidar_centerpoint node. The information for these parameters are shown in the [Parameters](#parameters) section.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry, this lacks a little in both writing and content.
The idea of the section is to describe the process of creating the files for a new model. In addition to some grammatical errors, instead of giving examples of parameters of the config file explain what kind of parameters they have. This links to the the ml config file, which is not mentioned here

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sorry, this lacks a little in both writing and content. The idea of the section is to describe the process of creating the files for a new model. In addition to some grammatical errors, instead of giving examples of parameters of the config file explain what kind of parameters they have. This links to the the ml config file, which is not mentioned here

@knzo25 Thank you for your instructions, I have updated the README.md file, please check if this meets your expectation. If you can give proposal for me to accept, it would be of great help for me. I will click the button commit suggestion afterwards. I really learned a lot with your help for this PR, thank you so much.


#### Launch the lidar_centerpoint node

```bash
cd /YOUR/AUTOWARE/PATH/Autoware
source install/setup.bash
ros2 launch lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_custom model_path:=/PATH/TO/ONNX/FILE/
ros2 launch lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_(your_selection_of_model) model_path:=/PATH/TO/ONNX/FILE/
```

### Changelog
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
<arg name="model_path" default="$(var data_path)/lidar_centerpoint"/>
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name)_base.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="$(var model_path)/detection_class_remapper.param.yaml"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,29 @@
"title": "Parameters for Lidar Centerpoint Node",
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would you fix the name of this file? (schemal.json to schema.json)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@kminoda I have fixed the name of the file.

"type": "object",
"definitions": {
"centerpoint": {
"centerpoint_base": {
"type": "object",
"properties": {
"encoder_onnx_path": {
"type": "string",
"description": "Path to VoxelFeatureEncoder ONNX file.",
"default": ""
},
"encoder_engine_path": {
"type": "string",
"description": "Path to VoxelFeatureEncoder TensorRT Engine file.",
"default": ""
},
"head_onnx_path": {
"type": "string",
"description": "Path to DetectionHead ONNX file.",
"default": ""
},
"head_engine_path": {
"type": "string",
"description": "Path to DetectionHead TensorRT Engine file.",
"default": ""
},
"trt_precision": {
"type": "string",
"description": "TensorRT inference precision.",
Expand Down Expand Up @@ -54,11 +74,6 @@
"default": 0.1,
"minimum": 0.0,
"maximum": 1.0
},
"has_twist": {
"type": "boolean",
"description": "Indicates whether the model outputs twist value.",
"default": false
}
}
},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
"description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.",
"default": [0.32, 0.32, 10.0]
},
"down_sample_factor": {
"downsample_factor": {
"type": "integer",
"description": "A scale factor of downsampling points",
"default": 1,
Expand All @@ -46,6 +46,16 @@
"type": "integer",
"description": "A size of encoder input feature channels.",
"default": 9
},
"has_variance": {
"type": "boolean",
"description": "Flag indicating if the model includes variance estimation.",
"default": false
},
"has_twist": {
"type": "boolean",
"description": "Flag indicating if the model includes twist estimation.",
"default": false
}
}
}
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Centerpoint Sigma ML model",
"type": "object",
"definitions": {
"centerpoint_sigma_ml_package": {
"type": "object",
"properties": {
"model_params": {
"type": "object",
"description": "Parameters for model configuration.",
"properties": {
"class_names": {
"type": "array",
"description": "An array of class names will be predicted.",
"default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"],
"items": {
"type": "string"
},
"uniqueItems": true
},
"point_feature_size": {
"type": "integer",
"description": "A number of channels of point feature layer.",
"default": 4
},
"max_voxel_size": {
"type": "integer",
"description": "A maximum size of voxel grid.",
"default": 40000
},
"point_cloud_range": {
"type": "array",
"description": "An array of distance ranges of each class, this must have same length with `class_names`.",
"default": [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0],
"items": {
"type": "number"
}
},
"voxel_size": {
"type": "array",
"description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.",
"default": [0.32, 0.32, 10.0],
"items": {
"type": "number"
}
},
"downsample_factor": {
"type": "integer",
"description": "A scale factor of downsampling points.",
"default": 1,
"minimum": 1
},
"encoder_in_feature_size": {
"type": "integer",
"description": "A size of encoder input feature channels.",
"default": 9
},
"has_variance": {
"type": "boolean",
"description": "Flag indicating if the model includes variance estimation.",
"default": false
},
"has_twist": {
"type": "boolean",
"description": "Flag indicating if the model includes twist estimation.",
"default": false
}
},
"required": [
"class_names",
"point_feature_size",
"max_voxel_size",
"point_cloud_range",
"voxel_size",
"downsample_factor",
"encoder_in_feature_size",
"has_variance",
"has_twist"
]
}
},
"required": ["model_params"]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/centerpoint_sigma_ml_package"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
Loading
Loading