diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml
index 5b5fabd4dd886..34f0a01d0a688 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml
@@ -3,7 +3,6 @@
-
@@ -17,7 +16,6 @@
-
diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md
index f5a15916f31a9..2a9adedad9074 100644
--- a/perception/lidar_centerpoint/README.md
+++ b/perception/lidar_centerpoint/README.md
@@ -45,6 +45,15 @@ We trained the models using .
| `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 |
+### The `build_only` option
+
+The `lidar_centerpoint` node has `build_only` option to build the TensorRT engine file from the ONNX file.
+Although it is preferred to move all the ROS parameters in `.param.yaml` file in Autoware Universe, the `build_only` option is not moved to the `.param.yaml` file for now, because it may be used as a flag to execute the build as a pre-task. You can execute with the following command:
+
+```bash
+ros2 launch lidar_centerpoint lidar_centerpoint.launch.xml model_name:=centerpoint_tiny model_path:=/home/autoware/autoware_data/lidar_centerpoint model_param_path:=$(ros2 pkg prefix lidar_centerpoint --share)/config/centerpoint_tiny.param.yaml build_only:=true
+```
+
## Assumptions / Known limits
- The `object.existence_probability` is stored the value of classification confidence of a DNN, not probability.
diff --git a/perception/lidar_centerpoint/config/centerpoint.param.yaml b/perception/lidar_centerpoint/config/centerpoint.param.yaml
index 0b29a87965b42..a9c3174846d0d 100644
--- a/perception/lidar_centerpoint/config/centerpoint.param.yaml
+++ b/perception/lidar_centerpoint/config/centerpoint.param.yaml
@@ -13,3 +13,14 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ has_twist: false
+ trt_precision: fp16
+ densification_num_past_frames: 1
+ densification_world_frame_id: map
+
+ # weight files
+ encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
+ encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
+ head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
+ head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
diff --git a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml
index 8252fde8273d8..474d0e2b695ac 100644
--- a/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml
+++ b/perception/lidar_centerpoint/config/centerpoint_tiny.param.yaml
@@ -13,3 +13,14 @@
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+ score_threshold: 0.35
+ has_twist: false
+ trt_precision: fp16
+ densification_num_past_frames: 1
+ densification_world_frame_id: map
+
+ # weight files
+ encoder_onnx_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"
+ encoder_engine_path: "$(var model_path)/pts_voxel_encoder_$(var model_name).engine"
+ head_onnx_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"
+ head_engine_path: "$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"
diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
index 1210875770510..5489af2c8fb60 100644
--- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
+++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml
@@ -7,8 +7,6 @@
-
-
@@ -19,18 +17,11 @@
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
@@ -38,18 +29,11 @@
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+