-
Notifications
You must be signed in to change notification settings - Fork 683
/
Copy pathlidar_centerpoint.launch.xml
29 lines (28 loc) · 1.87 KB
/
lidar_centerpoint.launch.xml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
<?xml version="1.0"?>
<launch>
<arg name="input/pointcloud" default="/sensing/lidar/pointcloud"/>
<arg name="output/objects" default="objects"/>
<arg name="model_name" default="centerpoint_tiny" description="options: `centerpoint` or `centerpoint_tiny`"/>
<arg name="model_path" default="$(find-pkg-share lidar_centerpoint)/data"/>
<arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
<arg name="class_remapper_param_path" default="$(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml"/>
<arg name="score_threshold" default="0.35"/>
<arg name="has_twist" default="false"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
<remap from="~/output/objects" to="$(var output/objects)"/>
<param name="score_threshold" value="$(var score_threshold)"/>
<param name="densification_world_frame_id" value="map"/>
<param name="densification_num_past_frames" value="1"/>
<param name="trt_precision" value="fp16"/>
<param name="has_twist" value="$(var has_twist)"/>
<param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/>
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
<param name="build_only" value="$(var build_only)"/>
<param from="$(var model_param_path)"/>
<param from="$(var class_remapper_param_path)"/>
</node>
</launch>