forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathroi_pointcloud_fusion.launch.xml
74 lines (72 loc) · 4.29 KB
/
roi_pointcloud_fusion.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
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
<launch>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="input/rois_number" default="6"/>
<arg name="input/rois0" default="rois0"/>
<arg name="input/camera_info0" default="/camera_info0"/>
<arg name="input/rois1" default="rois1"/>
<arg name="input/camera_info1" default="/camera_info1"/>
<arg name="input/rois2" default="rois2"/>
<arg name="input/camera_info2" default="/camera_info2"/>
<arg name="input/rois3" default="rois3"/>
<arg name="input/camera_info3" default="/camera_info3"/>
<arg name="input/rois4" default="rois4"/>
<arg name="input/camera_info4" default="/camera_info4"/>
<arg name="input/rois5" default="rois5"/>
<arg name="input/camera_info5" default="/camera_info5"/>
<arg name="input/rois6" default="rois6"/>
<arg name="input/camera_info6" default="/camera_info6"/>
<arg name="input/rois7" default="rois7"/>
<arg name="input/camera_info7" default="/camera_info7"/>
<arg name="input/pointcloud" default="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud"/>
<arg name="output/clusters" default="output/clusters"/>
<arg name="debug/clusters" default="roi_pointcloud_fusion/debug/clusters"/>
<arg name="param_path" default="$(find-pkg-share autoware_image_projection_based_fusion)/config/roi_pointcloud_fusion.param.yaml"/>
<arg name="sync_param_path" default="$(find-pkg-share autoware_image_projection_based_fusion)/config/fusion_common.param.yaml"/>
<!-- for eval variable-->
<arg name="input_rois_number" default="$(var input/rois_number)"/>
<arg name="input/image0" default="/image_raw0"/>
<arg name="input/image1" default="/image_raw1"/>
<arg name="input/image2" default="/image_raw2"/>
<arg name="input/image3" default="/image_raw3"/>
<arg name="input/image4" default="/image_raw4"/>
<arg name="input/image5" default="/image_raw5"/>
<arg name="input/image6" default="/image_raw6"/>
<arg name="input/image7" default="/image_raw7"/>
<group>
<node_container pkg="rclcpp_components" exec="component_container" name="$(var pointcloud_container_name)" namespace="/">
<composable_node pkg="autoware_image_projection_based_fusion" plugin="autoware::image_projection_based_fusion::RoiPointCloudFusionNode" name="roi_pointcloud_fusion">
<param name="rois_number" value="$(var input/rois_number)"/>
<param from="$(var param_path)"/>
<param from="$(var sync_param_path)" allow_substs="true"/>
<remap from="input" to="$(var input/pointcloud)"/>
<remap from="output" to="$(var output/clusters)"/>
<remap from="debug/clusters" to="$(var debug/clusters)"/>
<!-- rois, camera and info -->
<param name="input/rois0" value="$(var input/rois0)"/>
<param name="input/camera_info0" value="$(var input/camera_info0)"/>
<param name="input/image0" value="$(var input/image0)"/>
<param name="input/rois1" value="$(var input/rois1)"/>
<param name="input/camera_info1" value="$(var input/camera_info1)"/>
<param name="input/image1" value="$(var input/image1)"/>
<param name="input/rois2" value="$(var input/rois2)"/>
<param name="input/camera_info2" value="$(var input/camera_info2)"/>
<param name="input/image2" value="$(var input/image2)"/>
<param name="input/rois3" value="$(var input/rois3)"/>
<param name="input/camera_info3" value="$(var input/camera_info3)"/>
<param name="input/image3" value="$(var input/image3)"/>
<param name="input/rois4" value="$(var input/rois4)"/>
<param name="input/camera_info4" value="$(var input/camera_info4)"/>
<param name="input/image4" value="$(var input/image4)"/>
<param name="input/rois5" value="$(var input/rois5)"/>
<param name="input/camera_info5" value="$(var input/camera_info5)"/>
<param name="input/image5" value="$(var input/image5)"/>
<param name="input/rois6" value="$(var input/rois6)"/>
<param name="input/camera_info6" value="$(var input/camera_info6)"/>
<param name="input/image6" value="$(var input/image6)"/>
<param name="input/rois7" value="$(var input/rois7)"/>
<param name="input/camera_info7" value="$(var input/camera_info7)"/>
<param name="input/image7" value="$(var input/image7)"/>
</composable_node>
</node_container>
</group>
</launch>