Package Summary
Tags | No category tags. |
Version | 1.0.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/ieiauto/autodrrt.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2024-09-19 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Yusuke Muramatsu
- Kenzo Lobos-Tsunekawa
Authors
lidar_centerpoint
Purpose
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_auto_perception_msgs::msg::DetectedObjects |
detected objects |
debug/cyclic_time_ms |
tier4_debug_msgs::msg::Float64Stamped |
cyclic time (msg) |
debug/processing_time_ms |
tier4_debug_msgs::msg::Float64Stamped |
processing time (ms) |
Parameters
Core Parameters
Name | Type | Default Value | Description |
---|---|---|---|
score_threshold |
float | 0.4 |
detected objects with score less than threshold are ignored |
densification_world_frame_id |
string | map |
the world frame id to fuse multi-frame pointcloud |
densification_num_past_frames |
int | 1 |
the number of past frames to fuse with the current frame |
trt_precision |
string | fp16 |
TensorRT inference precision: fp32 or fp16
|
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 |
nms_iou_target_class_names |
list[string] | - | target classes for IoU-based Non Maximum Suppression |
nms_iou_search_distance_2d |
double | - | If two objects are farther than the value, NMS isn’t applied. |
nms_iou_threshold |
double | - | IoU threshold for the IoU-based Non Maximum Suppression |
build_only |
bool | false |
shutdown the node after TensorRT engine file is built |
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.
Standalone inference and visualization
In addition to its use as a standard ROS node, lidar_centerpoint
can also be used to perform inferences in an isolated manner.
To do so, execute the following launcher, where pcd_path
is the path of the pointcloud to be used for inference.
ros2 launch lidar_centerpoint single_inference_lidar_centerpoint.launch.xml pcd_path:=test_pointcloud.pcd detections_path:=test_detections.ply
lidar_centerpoint
generates a ply
file in the provided detections_path
, which contains the detections as triangle meshes.
These detections can be visualized by most 3D tools, but we also integrate a visualization UI using Open3D
which is launched alongside lidar_centerpoint
.
Changelog
v1 (2022/07/06)
Name | URLs | Description |
---|---|---|
centerpoint |
pts_voxel_encoder pts_backbone_neck_head |
There is a single change due to the limitation in the implementation of this package. num_filters=[32, 32] of PillarFeatureNet
|
centerpoint_tiny |
pts_voxel_encoder pts_backbone_neck_head |
The same model as default of v0 . |
These changes are compared with this configuration.
v0 (2021/12/03)
Name | URLs | Description |
---|---|---|
default |
pts_voxel_encoder pts_backbone_neck_head |
There are two changes from the original CenterPoint architecture. num_filters=[32] of PillarFeatureNet and ds_layer_strides=[2, 2, 2] of RPN
|
(Optional) Error detection and handling
(Optional) Performance characterization
References/External links
[1] Yin, Tianwei, Xingyi Zhou, and Philipp Krähenbühl. “Center-based 3d object detection and tracking.” arXiv preprint arXiv:2006.11275 (2020).
[2] Lang, Alex H., et al. “PointPillars: Fast encoders for object detection from point clouds.” Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition. 2019.
[3] https://github.com/tianweiy/CenterPoint
[4] https://github.com/open-mmlab/mmdetection3d
[5] https://github.com/open-mmlab/OpenPCDet
[6] https://github.com/yukkysaito/autoware_perception
[7] https://github.com/NVIDIA-AI-IOT/CUDA-PointPillars
[8] https://www.nuscenes.org/nuscenes
[9] https://www.argoverse.org/av2.html
(Optional) Future extensions / Unimplemented parts
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
python3-open3d |
Dependant Packages
Name | Deps |
---|---|
image_projection_based_fusion |
Launch files
- launch/lidar_centerpoint.launch.xml
-
- input/pointcloud [default: /sensing/lidar/pointcloud]
- output/objects [default: objects]
- data_path [default: $(env HOME)/autoware_data]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/lidar_centerpoint]
- model_param_path [default: $(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml]
- class_remapper_param_path [default: $(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml]
- score_threshold [default: 0.35]
- has_twist [default: false]
- build_only [default: false]
- launch/single_inference_lidar_centerpoint.launch.xml
-
- data_path [default: $(env HOME)/autoware_data]
- model_name [default: centerpoint_tiny]
- model_path [default: $(var data_path)/lidar_centerpoint]
- model_param_path [default: $(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml]
- class_remapper_param_path [default: $(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml]
- score_threshold [default: 0.35]
- yaw_norm_threshold [default: 0.0]
- has_twist [default: false]
- pcd_path [default: test.pcd]
- detections_path [default: test.ply]
- launch/centerpoint_vs_centerpoint-tiny/centerpoint_vs_centerpoint-tiny.launch.xml
-
- rviz_path [default: $(find-pkg-share lidar_centerpoint)/launch/centerpoint_vs_centerpoint-tiny/rviz]
- input/pointcloud [default: /sensing/lidar/concatenated/pointcloud]
- score_threshold [default: 0.35]
- rviz_config1 [default: $(var rviz_path)/centerpoint_tiny.rviz]
- rviz_config2 [default: $(var rviz_path)/centerpoint.rviz]
- data_path [default: $(env HOME)/autoware_data]