diff --git a/perception/lidar_apollo_instance_segmentation/launch/lidar_apollo_instance_segmentation.launch.xml b/perception/lidar_apollo_instance_segmentation/launch/lidar_apollo_instance_segmentation.launch.xml
index 9fed29828ed9f..78127590685fb 100644
--- a/perception/lidar_apollo_instance_segmentation/launch/lidar_apollo_instance_segmentation.launch.xml
+++ b/perception/lidar_apollo_instance_segmentation/launch/lidar_apollo_instance_segmentation.launch.xml
@@ -13,7 +13,7 @@
-
+
diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp
index af8b29f55f340..77eee2c551846 100644
--- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp
+++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp
@@ -38,7 +38,7 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
use_intensity_feature = node_->declare_parameter("use_intensity_feature", true);
use_constant_feature = node_->declare_parameter("use_constant_feature", true);
target_frame_ = node_->declare_parameter("target_frame", "base_link");
- z_offset_ = node_->declare_parameter("z_offset", 2);
+ z_offset_ = node_->declare_parameter("z_offset", -2.0);
// load weight file
std::ifstream fs(engine_file);