diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 9edfc783179c7..9e00618cf56a2 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -36,8 +36,8 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * use_intensity_feature = node_->declare_parameter("use_intensity_feature"); use_constant_feature = node_->declare_parameter("use_constant_feature"); target_frame_ = node_->declare_parameter("target_frame"); - z_offset_ = node_->declare_parameter("z_offset", -2.0); - const auto precision = node_->declare_parameter("precision", "fp32"); + z_offset_ = node_->declare_parameter("z_offset"); + const auto precision = node_->declare_parameter("precision"); trt_common_ = std::make_unique( onnx_file, precision, nullptr, tensorrt_common::BatchConfig{1, 1, 1}, 1 << 30);