|
7 | 7 | <arg name="model_path" default="$(var data_path)/lidar_centerpoint"/>
|
8 | 8 | <arg name="model_param_path" default="$(find-pkg-share lidar_centerpoint)/config/$(var model_name).param.yaml"/>
|
9 | 9 | <arg name="class_remapper_param_path" default="$(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml"/>
|
10 |
| - <arg name="score_threshold" default="0.35"/> |
11 |
| - <arg name="has_twist" default="false"/> |
12 | 10 | <arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>
|
13 | 11 |
|
14 | 12 | <arg name="use_pointcloud_container" default="false" description="use pointcloud_container"/>
|
|
19 | 17 | <composable_node pkg="lidar_centerpoint" plugin="centerpoint::LidarCenterPointNode" name="lidar_centerpoint">
|
20 | 18 | <remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
|
21 | 19 | <remap from="~/output/objects" to="$(var output/objects)"/>
|
22 |
| - <param name="score_threshold" value="$(var score_threshold)"/> |
23 |
| - <param name="densification_world_frame_id" value="map"/> |
24 |
| - <param name="densification_num_past_frames" value="1"/> |
25 |
| - <param name="trt_precision" value="fp16"/> |
26 |
| - <param name="has_twist" value="$(var has_twist)"/> |
27 |
| - <param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/> |
28 |
| - <param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/> |
29 |
| - <param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/> |
30 |
| - <param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/> |
31 |
| - <param name="build_only" value="$(var build_only)"/> |
32 |
| - <param from="$(var model_param_path)"/> |
| 20 | + <param from="$(var model_param_path)" allow_substs="true"/> |
33 | 21 | <param from="$(var class_remapper_param_path)"/>
|
| 22 | + |
| 23 | + <!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 --> |
| 24 | + <param name="build_only" value="$(var build_only)"/> |
34 | 25 | </composable_node>
|
35 | 26 | </load_composable_node>
|
36 | 27 | </group>
|
37 | 28 | <group unless="$(var use_pointcloud_container)">
|
38 | 29 | <node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
|
39 | 30 | <remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
|
40 | 31 | <remap from="~/output/objects" to="$(var output/objects)"/>
|
41 |
| - <param name="score_threshold" value="$(var score_threshold)"/> |
42 |
| - <param name="densification_world_frame_id" value="map"/> |
43 |
| - <param name="densification_num_past_frames" value="1"/> |
44 |
| - <param name="trt_precision" value="fp16"/> |
45 |
| - <param name="has_twist" value="$(var has_twist)"/> |
46 |
| - <param name="encoder_onnx_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).onnx"/> |
47 |
| - <param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/> |
48 |
| - <param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/> |
49 |
| - <param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/> |
50 |
| - <param name="build_only" value="$(var build_only)"/> |
51 |
| - <param from="$(var model_param_path)"/> |
| 32 | + <param from="$(var model_param_path)" allow_substs="true"/> |
52 | 33 | <param from="$(var class_remapper_param_path)"/>
|
| 34 | + |
| 35 | + <!-- This parameter shall NOT be included in param file. See also: https://github.com/autowarefoundation/autoware.universe/pull/6167 --> |
| 36 | + <param name="build_only" value="$(var build_only)"/> |
53 | 37 | </node>
|
54 | 38 | </group>
|
55 | 39 | </launch>
|
0 commit comments