diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
index a9c3174846..38c57285e5 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint.param.yaml
@@ -14,6 +14,7 @@
     iou_nms_threshold: 0.1
     yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
     score_threshold: 0.35
+    has_variance: false
     has_twist: false
     trt_precision: fp16
     densification_num_past_frames: 1
diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml
new file mode 100644
index 0000000000..c217f63213
--- /dev/null
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_sigma.param.yaml
@@ -0,0 +1,27 @@
+/**:
+  ros__parameters:
+    class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"]
+    point_feature_size: 4
+    max_voxel_size: 40000
+    point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0]
+    voxel_size: [0.32, 0.32, 10.0]
+    downsample_factor: 1
+    encoder_in_feature_size: 9
+    # post-process params
+    circle_nms_dist_threshold: 0.5
+    iou_nms_target_class_names: ["CAR"]
+    iou_nms_search_distance_2d: 10.0
+    iou_nms_threshold: 0.1
+    yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
+    score_threshold: 0.35
+    has_variance: true
+    has_twist: true
+    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/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
index 474d0e2b69..35e11e61e9 100644
--- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
+++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/centerpoint_tiny.param.yaml
@@ -14,6 +14,7 @@
     iou_nms_threshold: 0.1
     yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
     score_threshold: 0.35
+    has_variance: false
     has_twist: false
     trt_precision: fp16
     densification_num_past_frames: 1