Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]
Messages
Services
Plugins
Recent questions tagged autoware_lidar_centerpoint at Robotics Stack Exchange
Package Summary
Tags | No category tags. |
Version | 0.47.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Description | |
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-08-16 |
Dev Status | UNKNOWN |
Released | UNRELEASED |
Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Kenzo Lobos-Tsunekawa
- Amadeusz Szymko
- Kotaro Uetake
- Masato Saeki
- Taekjin Lee
- Kok Seang Tan
Authors
autoware_lidar_centerpoint
Purpose
autoware_lidar_centerpoint is a package for detecting dynamic 3D objects.
Inner-workings / Algorithms
In this implementation, CenterPoint [1] uses a PointPillars-based [2] network to inference with TensorRT.
We trained the models using https://github.com/open-mmlab/mmdetection3d.
Inputs / Outputs
Input
Name | Type | Description |
---|---|---|
~/input/pointcloud |
sensor_msgs::msg::PointCloud2 |
input pointcloud |
Output
Name | Type | Description |
---|---|---|
~/output/objects |
autoware_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
autoware_internal_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
ML Model Parameters
Note that these parameters are associated with ONNX file, predefined during the training phase. Be careful to change ONNX file as well when changing this parameter. Also, whenever you update the ONNX file, do NOT forget to check these values.
Name | Type | Default Value | Description |
---|---|---|---|
model_params.class_names |
list[string] | [“CAR”, “TRUCK”, “BUS”, “BICYCLE”, “PEDESTRIAN”] | list of class names for model outputs |
model_params.point_feature_size |
int | 4 |
number of features per point in the point cloud |
model_params.max_voxel_size |
int | 40000 |
maximum number of voxels |
model_params.point_cloud_range |
list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] |
model_params.voxel_size |
list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] |
model_params.downsample_factor |
int | 1 |
downsample factor for coordinates |
model_params.encoder_in_feature_size |
int | 9 |
number of input features to the encoder |
model_params.has_variance |
bool | false |
true if the model outputs pose variance as well as pose for each bbox |
model_params.has_twist |
bool | false |
true if the model outputs velocity as well as pose for each bbox |
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_thresholds |
list[double] | [0.35, 0.35, 0.35, 0.35, 0.35] | detected objects with score less than their label 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_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 |
The build_only
option
The autoware_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:
ros2 launch autoware_lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix autoware_lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
Assumptions / Known limits
- The
object.existence_probability
is stored the value of classification confidence of a DNN, not probability.
Trained Models
You can download the onnx format of trained models by clicking on the links below.
- Centerpoint: pts_voxel_encoder_centerpoint.onnx, pts_backbone_neck_head_centerpoint.onnx
- Centerpoint tiny: pts_voxel_encoder_centerpoint_tiny.onnx, pts_backbone_neck_head_centerpoint_tiny.onnx
Centerpoint
was trained in nuScenes
(~28k lidar frames) [8] and TIER IV’s internal database (~11k lidar frames) for 60 epochs.
Centerpoint tiny
was trained in Argoverse 2
(~110k lidar frames) [9] and TIER IV’s internal database (~11k lidar frames) for 20 epochs.
Training CenterPoint Model and Deploying to the Autoware
Overview
This guide provides instructions on training a CenterPoint model using the mmdetection3d repository and seamlessly deploying it within Autoware.
Installation
Install prerequisites
Step 1. Download and install Miniconda from the official website.
File truncated at 100 lines see the full file
Changelog for package autoware_lidar_centerpoint
0.47.0 (2025-08-11)
-
feat(autoware_lidar_centerpoint): add class-wise confidence thresholds to CenterPoint (#10881)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Change score_threshold to score_thresholds
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
- Add class-wise confidence thresholds to CenterPoint
- style(pre-commit): autofix
- Remov empty line changes
- Update score_threshold to score_thresholds in REAMME
- style(pre-commit): autofix
- Change score_thresholds from pass by value to pass by reference
- style(pre-commit): autofix
- Add information about class names in scehema
- Change vector<double> to vector<float>
- Remove thrust and add stream_ to PostProcessCUDA
- style(pre-commit): autofix
- Fix incorrect initialization of score_thresholds_ vector
- Fix postprocess CudaMemCpy error
- Fix postprocess score_thresholds_d_ptr_ typing error
- Fix score_thresholds typing in node.cpp
- Static casting params.score_thresholds vector
- style(pre-commit): autofix
- Update perception/autoware_lidar_centerpoint/src/node.cpp
- Update perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/centerpoint_config.hpp
- Update centerpoint_config.hpp
- Update node.cpp
- Update score_thresholds_ to double since ros2 supports only double instead of float
- style(pre-commit): autofix
- Fix cuda memory and revert double score_thresholds_ to float score_thresholds_
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Taekjin LEE <<technolojin@gmail.com>>
-
feat(autoware_lidar_centerpoint): add Intensity support to CenterPoint (#10854)
- Add PreprocessCuda to CenterPoint
- style(pre-commit): autofix
- style(pre-commit): autofix
- Add intensity preprocessing
- style(pre-commit): autofix
- Fix config_.point_feature_size_ typo
- style(pre-commit): autofix
- Fix point typo
- style(pre-commit): autofix
- Use <autoware/cuda_utils/cuda_utils.hpp> for clear_async
- Rename pre_ptr_ to pre_proc_ptr_
- Remove unused getCacheSize() and getIdx
- Use template in generateVoxels_random_kernel instead
- style(pre-commit): autofix
- Remove references in generateVoxels_random_kernel
- Remove references in generateVoxels_random_kernel
- style(pre-commit): autofix
- Remove generateIntensityFeatures_kernel and add the case of 11 to ENCODER_IN_FEATURE_SIZE for generateFeatures_kernel
- style(pre-commit): autofix
* Remov empty line changes ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
-
Contributors: Kok Seang Tan
0.46.0 (2025-06-20)
-
Merge remote-tracking branch 'upstream/main' into tmp/TaikiYamada/bump_version_base
-
chore(perception): delete maintainer name (#10816)
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- node_name [default: lidar_centerpoint]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/$(var node_name)]
- model_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/$(var model_name).param.yaml]
- ml_package_param_path [default: $(var model_path)/$(var model_name)_ml_package.param.yaml]
- class_remapper_param_path [default: $(var model_path)/detection_class_remapper.param.yaml]
- common_param_path [default: $(find-pkg-share autoware_lidar_centerpoint)/config/centerpoint_common.param.yaml]
- build_only [default: false]
- use_pointcloud_container [default: false]
- pointcloud_container_name [default: pointcloud_container]