Skip to content

Commit

Permalink
update camera lidar fusion arch (tier4#122)
Browse files Browse the repository at this point in the history
  • Loading branch information
yukkysaito authored and UMiho committed Dec 10, 2020
1 parent 6dfe4ce commit 71e2488
Showing 1 changed file with 87 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,6 @@
<arg name="image_number" default="1"/>
<arg name="use_vector_map" default="true"/>

<!-- <include file="$(find euclidean_cluster)/launch/euclidean_cluster.launch"/> -->
<!-- or -->
<!-- <include file="$(find euclidean_cluster)/launch/voxel_grid_based_euclidean_cluster.launch" /> -->
<!-- or -->
<include file="$(find lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch">
<arg name="output/objects" default="clusters"/>
</include>

<!-- Jetson AGX -->
<!-- <include file="$(find tensorrt_yolo3)/launch/yolo3.launch">
<arg name="image_raw0" default="$(arg image_raw0)"/>
Expand All @@ -41,22 +33,93 @@
<arg name="image_number" default="$(arg image_number)"/>
</include> -->

<include file="$(find roi_cluster_fusion)/launch/roi_cluster_fusion.launch">
<arg name="input_camera_info0" default="$(arg camera_info0)"/>
<arg name="input_camera_info1" default="$(arg camera_info1)"/>
<arg name="input_camera_info2" default="$(arg camera_info2)"/>
<arg name="input_camera_info3" default="$(arg camera_info3)"/>
<arg name="input_camera_info4" default="$(arg camera_info4)"/>
<arg name="input_camera_info5" default="$(arg camera_info5)"/>
<arg name="input_camera_info6" default="$(arg camera_info6)"/>
<arg name="input_camera_info7" default="$(arg camera_info7)"/>
<arg name="input_rois_number" default="$(arg image_number)"/>
</include>

<!-- <include file="$(find cluster_data_association)/launch/cluster_data_association.launch" /> -->
<group ns="euclidean" >
<include file="$(find euclidean_cluster)/launch/voxel_grid_based_euclidean_cluster.launch" >
<arg name="output/clusters" default="lidar/clusters"/>
</include>
<include file="$(find roi_cluster_fusion)/launch/roi_cluster_fusion.launch">
<arg name="input_camera_info0" default="$(arg camera_info0)"/>
<arg name="input_rois0" default="/perception/object_recognition/detection/rois0"/>
<arg name="input_camera_info1" default="$(arg camera_info1)"/>
<arg name="input_rois1" default="/perception/object_recognition/detection/rois1"/>
<arg name="input_camera_info2" default="$(arg camera_info2)"/>
<arg name="input_rois2" default="/perception/object_recognition/detection/rois2"/>
<arg name="input_camera_info3" default="$(arg camera_info3)"/>
<arg name="input_rois3" default="/perception/object_recognition/detection/rois3"/>
<arg name="input_camera_info4" default="$(arg camera_info4)"/>
<arg name="input_rois4" default="/perception/object_recognition/detection/rois4"/>
<arg name="input_camera_info5" default="$(arg camera_info5)"/>
<arg name="input_rois5" default="/perception/object_recognition/detection/rois5"/>
<arg name="input_camera_info6" default="$(arg camera_info6)"/>
<arg name="input_rois6" default="/perception/object_recognition/detection/rois6"/>
<arg name="input_camera_info7" default="$(arg camera_info7)"/>
<arg name="input_rois7" default="/perception/object_recognition/detection/rois7"/>
<arg name="input_rois_number" default="$(arg image_number)"/>
<arg name="input_clusters" default="lidar/clusters"/>
<arg name="output" default="camera_lidar_fusion/clusters"/>
</include>
<include file="$(find shape_estimation)/launch/shape_estimation.launch">
<arg name="use_map_corrent" default="$(arg use_vector_map)"/>
<arg name="input/objects" default="camera_lidar_fusion/clusters" />
<arg name="output/objects" default="camera_lidar_fusion/objects" />
<arg name="orientation_reliable" default="false"/>
</include>
<include file="$(find object_range_splitter)/launch/object_range_splitter.launch">
<arg name="input/object" default="camera_lidar_fusion/objects"/>
<arg name="output/long_range_object" default="camera_lidar_fusion/long_range_objects"/>
<arg name="output/short_range_object" default="camera_lidar_fusion/short_range_objects"/>
<arg name="split_range" default="10"/>
</include>
</group>

<include file="$(find shape_estimation)/launch/shape_estimation.launch">
<arg name="use_map_corrent" default="$(arg use_vector_map)"/>
<arg name="output/objects" default="objects" />
<group ns="apollo" >
<include file="$(find lidar_apollo_instance_segmentation)/launch/lidar_apollo_instance_segmentation.launch">
<arg name="output/objects" default="lidar/clusters"/>
</include>
<include file="$(find shape_estimation)/launch/shape_estimation.launch">
<arg name="use_map_corrent" default="$(arg use_vector_map)"/>
<arg name="input/objects" default="lidar/clusters" />
<arg name="output/objects" default="lidar/objects" />
<arg name="orientation_reliable" default="true"/>
</include>
<include file="$(find object_range_splitter)/launch/object_range_splitter.launch">
<arg name="input/object" default="lidar/objects"/>
<arg name="output/long_range_object" default="lidar/long_range_objects"/>
<arg name="output/short_range_object" default="lidar/short_range_objects"/>
<arg name="split_range" default="15"/>
</include>
<include file="$(find roi_cluster_fusion)/launch/roi_cluster_fusion.launch">
<arg name="input_camera_info0" default="$(arg camera_info0)"/>
<arg name="input_rois0" default="/perception/object_recognition/detection/rois0"/>
<arg name="input_camera_info1" default="$(arg camera_info1)"/>
<arg name="input_rois1" default="/perception/object_recognition/detection/rois1"/>
<arg name="input_camera_info2" default="$(arg camera_info2)"/>
<arg name="input_rois2" default="/perception/object_recognition/detection/rois2"/>
<arg name="input_camera_info3" default="$(arg camera_info3)"/>
<arg name="input_rois3" default="/perception/object_recognition/detection/rois3"/>
<arg name="input_camera_info4" default="$(arg camera_info4)"/>
<arg name="input_rois4" default="/perception/object_recognition/detection/rois4"/>
<arg name="input_camera_info5" default="$(arg camera_info5)"/>
<arg name="input_rois5" default="/perception/object_recognition/detection/rois5"/>
<arg name="input_camera_info6" default="$(arg camera_info6)"/>
<arg name="input_rois6" default="/perception/object_recognition/detection/rois6"/>
<arg name="input_camera_info7" default="$(arg camera_info7)"/>
<arg name="input_rois7" default="/perception/object_recognition/detection/rois7"/>
<arg name="input_rois_number" default="$(arg image_number)"/>
<arg name="input_clusters" default="lidar/short_range_objects"/>
<arg name="output" default="camera_lidar_fusion/short_range_objects"/>
</include>
<include file="$(find object_merger)/launch/object_association_merger.launch">
<arg name="input/object0" default="camera_lidar_fusion/short_range_objects"/>
<arg name="input/object1" default="lidar/long_range_objects"/>
<arg name="output/object" default="camera_lidar_fusion/objects"/>
</include>
</group>

<include file="$(find object_merger)/launch/object_association_merger.launch">
<arg name="input/object0" default="apollo/camera_lidar_fusion/objects"/>
<arg name="input/object1" default="euclidean/camera_lidar_fusion/short_range_objects"/>
<arg name="output/object" default="objects"/>
</include>

</launch>

0 comments on commit 71e2488

Please sign in to comment.