From 7448c1f4126b93f8c092471934929efd90533c63 Mon Sep 17 00:00:00 2001 From: kosuke55 Date: Tue, 20 Feb 2024 01:56:13 +0900 Subject: [PATCH] feat(lidar_apollo_instance_segmentation): add build_only option Signed-off-by: kosuke55 --- perception/lidar_apollo_instance_segmentation/README.md | 1 + .../launch/lidar_apollo_instance_segmentation.launch.xml | 4 ++++ .../lidar_apollo_instance_segmentation/src/detector.cpp | 5 +++++ 3 files changed, 10 insertions(+) diff --git a/perception/lidar_apollo_instance_segmentation/README.md b/perception/lidar_apollo_instance_segmentation/README.md index 2d86b695d2474..f9dc6b3f44a23 100644 --- a/perception/lidar_apollo_instance_segmentation/README.md +++ b/perception/lidar_apollo_instance_segmentation/README.md @@ -47,6 +47,7 @@ None | `use_constant_feature` | bool | false | The flag to use direction and distance feature of pointcloud. | | `target_frame` | string | "base_link" | Pointcloud data is transformed into this frame. | | `z_offset` | int | 2 | z offset from target frame. [m] | +| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built | ## Assumptions / Known limits 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 7f5024929b531..207dac45671dd 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 @@ -2,6 +2,7 @@ + @@ -24,5 +25,8 @@ + + + diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 5da7825f96681..236f0998ab21f 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -48,6 +48,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * return; } + if (node_->declare_parameter("build_only", false)) { + RCLCPP_INFO(node_->get_logger(), "TensorRT engine is built and shutdown node."); + rclcpp::shutdown(); + } + // GPU memory allocation const auto input_dims = trt_common_->getBindingDimensions(0); const auto input_size =