Skip to content

Commit 7448c1f

Browse files
committed
feat(lidar_apollo_instance_segmentation): add build_only option
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 9530c8a commit 7448c1f

File tree

3 files changed

+10
-0
lines changed

3 files changed

+10
-0
lines changed

perception/lidar_apollo_instance_segmentation/README.md

+1
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ None
4747
| `use_constant_feature` | bool | false | The flag to use direction and distance feature of pointcloud. |
4848
| `target_frame` | string | "base_link" | Pointcloud data is transformed into this frame. |
4949
| `z_offset` | int | 2 | z offset from target frame. [m] |
50+
| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built |
5051

5152
## Assumptions / Known limits
5253

perception/lidar_apollo_instance_segmentation/launch/lidar_apollo_instance_segmentation.launch.xml

+4
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud"/>
33
<arg name="model" default="model_128"/>
44
<arg name="output/objects" default="labeled_clusters"/>
5+
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
56

67
<arg if="$(eval &quot;'$(var model)'=='model_16'&quot;)" name="base_name" default="vlp-16"/>
78
<arg if="$(eval &quot;'$(var model)'=='model_64'&quot;)" name="base_name" default="hdl-64"/>
@@ -24,5 +25,8 @@
2425
<param name="precision" value="$(var precision)"/>
2526
<param name="target_frame" value="$(var target_frame)"/>
2627
<param from="$(var param_file)"/>
28+
29+
<!-- This parameter shall NOT be included in param file. -->
30+
<param name="build_only" value="$(var build_only)"/>
2731
</node>
2832
</launch>

perception/lidar_apollo_instance_segmentation/src/detector.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node *
4848
return;
4949
}
5050

51+
if (node_->declare_parameter("build_only", false)) {
52+
RCLCPP_INFO(node_->get_logger(), "TensorRT engine is built and shutdown node.");
53+
rclcpp::shutdown();
54+
}
55+
5156
// GPU memory allocation
5257
const auto input_dims = trt_common_->getBindingDimensions(0);
5358
const auto input_size =

0 commit comments

Comments
 (0)