|
1 | 1 | <launch>
|
| 2 | + <arg name="pointcloud_container_name" default="pointcloud_container"/> |
2 | 3 | <arg name="input/rois_number" default="6"/>
|
3 | 4 | <arg name="input/rois0" default="rois0"/>
|
4 | 5 | <arg name="input/camera_info0" default="/camera_info0"/>
|
|
33 | 34 | <arg name="input/image6" default="/image_raw6"/>
|
34 | 35 | <arg name="input/image7" default="/image_raw7"/>
|
35 | 36 | <group>
|
36 |
| - <node pkg="autoware_image_projection_based_fusion" exec="roi_pointcloud_fusion_node" name="roi_pointcloud_fusion" output="screen"> |
37 |
| - <param name="rois_number" value="$(var input/rois_number)"/> |
38 |
| - <param from="$(var param_path)"/> |
39 |
| - <param from="$(var sync_param_path)"/> |
40 |
| - <remap from="input" to="$(var input/pointcloud)"/> |
41 |
| - <remap from="output" to="$(var output/clusters)"/> |
42 |
| - <remap from="debug/clusters" to="$(var debug/clusters)"/> |
| 37 | + <node_container pkg="rclcpp_components" exec="component_container" name="$(var pointcloud_container_name)" namespace="/"> |
| 38 | + <composable_node pkg="autoware_image_projection_based_fusion" plugin="autoware::image_projection_based_fusion::RoiPointCloudFusionNode" name="roi_pointcloud_fusion"> |
| 39 | + <param name="rois_number" value="$(var input/rois_number)"/> |
| 40 | + <param from="$(var param_path)"/> |
| 41 | + <param from="$(var sync_param_path)" allow_substs="true"/> |
| 42 | + <remap from="input" to="$(var input/pointcloud)"/> |
| 43 | + <remap from="output" to="$(var output/clusters)"/> |
| 44 | + <remap from="debug/clusters" to="$(var debug/clusters)"/> |
43 | 45 |
|
44 |
| - <!-- rois, camera and info --> |
45 |
| - <param name="input/rois0" value="$(var input/rois0)"/> |
46 |
| - <param name="input/camera_info0" value="$(var input/camera_info0)"/> |
47 |
| - <param name="input/image0" value="$(var input/image0)"/> |
48 |
| - <param name="input/rois1" value="$(var input/rois1)"/> |
49 |
| - <param name="input/camera_info1" value="$(var input/camera_info1)"/> |
50 |
| - <param name="input/image1" value="$(var input/image1)"/> |
51 |
| - <param name="input/rois2" value="$(var input/rois2)"/> |
52 |
| - <param name="input/camera_info2" value="$(var input/camera_info2)"/> |
53 |
| - <param name="input/image2" value="$(var input/image2)"/> |
54 |
| - <param name="input/rois3" value="$(var input/rois3)"/> |
55 |
| - <param name="input/camera_info3" value="$(var input/camera_info3)"/> |
56 |
| - <param name="input/image3" value="$(var input/image3)"/> |
57 |
| - <param name="input/rois4" value="$(var input/rois4)"/> |
58 |
| - <param name="input/camera_info4" value="$(var input/camera_info4)"/> |
59 |
| - <param name="input/image4" value="$(var input/image4)"/> |
60 |
| - <param name="input/rois5" value="$(var input/rois5)"/> |
61 |
| - <param name="input/camera_info5" value="$(var input/camera_info5)"/> |
62 |
| - <param name="input/image5" value="$(var input/image5)"/> |
63 |
| - <param name="input/rois6" value="$(var input/rois6)"/> |
64 |
| - <param name="input/camera_info6" value="$(var input/camera_info6)"/> |
65 |
| - <param name="input/image6" value="$(var input/image6)"/> |
66 |
| - <param name="input/rois7" value="$(var input/rois7)"/> |
67 |
| - <param name="input/camera_info7" value="$(var input/camera_info7)"/> |
68 |
| - <param name="input/image7" value="$(var input/image7)"/> |
69 |
| - </node> |
| 46 | + <!-- rois, camera and info --> |
| 47 | + <param name="input/rois0" value="$(var input/rois0)"/> |
| 48 | + <param name="input/camera_info0" value="$(var input/camera_info0)"/> |
| 49 | + <param name="input/image0" value="$(var input/image0)"/> |
| 50 | + <param name="input/rois1" value="$(var input/rois1)"/> |
| 51 | + <param name="input/camera_info1" value="$(var input/camera_info1)"/> |
| 52 | + <param name="input/image1" value="$(var input/image1)"/> |
| 53 | + <param name="input/rois2" value="$(var input/rois2)"/> |
| 54 | + <param name="input/camera_info2" value="$(var input/camera_info2)"/> |
| 55 | + <param name="input/image2" value="$(var input/image2)"/> |
| 56 | + <param name="input/rois3" value="$(var input/rois3)"/> |
| 57 | + <param name="input/camera_info3" value="$(var input/camera_info3)"/> |
| 58 | + <param name="input/image3" value="$(var input/image3)"/> |
| 59 | + <param name="input/rois4" value="$(var input/rois4)"/> |
| 60 | + <param name="input/camera_info4" value="$(var input/camera_info4)"/> |
| 61 | + <param name="input/image4" value="$(var input/image4)"/> |
| 62 | + <param name="input/rois5" value="$(var input/rois5)"/> |
| 63 | + <param name="input/camera_info5" value="$(var input/camera_info5)"/> |
| 64 | + <param name="input/image5" value="$(var input/image5)"/> |
| 65 | + <param name="input/rois6" value="$(var input/rois6)"/> |
| 66 | + <param name="input/camera_info6" value="$(var input/camera_info6)"/> |
| 67 | + <param name="input/image6" value="$(var input/image6)"/> |
| 68 | + <param name="input/rois7" value="$(var input/rois7)"/> |
| 69 | + <param name="input/camera_info7" value="$(var input/camera_info7)"/> |
| 70 | + <param name="input/image7" value="$(var input/image7)"/> |
| 71 | + </composable_node> |
| 72 | + </node_container> |
70 | 73 | </group>
|
71 | 74 | </launch>
|
0 commit comments