Skip to content

Commit

Permalink
Configure camera-lidar fusion
Browse files Browse the repository at this point in the history
- Multi YOLOx launch is enabled with unique node names
- Define 3 cameras and fix correct camera topics
  • Loading branch information
hect95 committed Jun 6, 2024
1 parent 2022fc9 commit 9089da5
Show file tree
Hide file tree
Showing 6 changed files with 51 additions and 40 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
<arg name="image_number" default="1" description="choose image raw number(1-8)"/>

<!-- Jetson AGX -->
<!-- <include file="$(find-pkg-share tensorrt_yolox)/launch/multiple_yolox.launch.xml">
<include file="$(find-pkg-share tensorrt_yolox)/launch/multiple_yolox.launch.xml">
<arg name="image_raw0" value="$(var image_raw0)"/>
<arg name="image_raw1" value="$(var image_raw1)"/>
<arg name="image_raw2" value="$(var image_raw2)"/>
Expand All @@ -48,7 +48,7 @@
<arg name="image_raw6" value="$(var image_raw6)"/>
<arg name="image_raw7" value="$(var image_raw7)"/>
<arg name="image_number" value="$(var image_number)"/>
</include> -->
</include>

<!-- PointPainting -->
<group if="$(eval &quot;'$(var lidar_detection_model)'=='pointpainting'&quot;)">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
<?xml version="1.0"?>
<launch>
<!-- Lidar parameters -->
<arg name="input/pointcloud"/>
<arg name="input/pointcloud" default="/sensor/lidar/top/points"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `clustering`"/>

<!-- Lidar detector centerpoint parameters -->
<arg name="centerpoint_model_name" default="centerpoint_tiny" description="options: `centerpoint`, `centerpoint_tiny` or `centerpoint_sigma`"/>
<arg name="centerpoint_model_path" default="$(var data_path)/lidar_centerpoint"/>
<arg name="centerpoint_model_path" default="/autoware/autoware_data/lidar_centerpoint"/>
<arg name="lidar_model_param_path" default="$(find-pkg-share lidar_centerpoint)/config"/>

<!-- CenterPoint -->
Expand All @@ -22,7 +23,7 @@
<arg name="ml_package_param_path" value="$(var centerpoint_model_path)/$(var centerpoint_model_name)_ml_package.param.yaml"/>
<arg name="class_remapper_param_path" value="$(var centerpoint_model_path)/detection_class_remapper.param.yaml"/>

<arg name="use_pointcloud_container" value="true"/>
<arg name="use_pointcloud_container" value="false"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,8 @@
<let name="filter/input/objects" value="$(var lidar_detection_model)_roi_cluster_fusion/objects" unless="$(var use_detection_by_tracker)"/>
<include file="$(find-pkg-share detected_object_validation)/launch/object_position_filter.launch.xml" if="$(var use_object_filter)">
<arg name="input/object" value="$(var filter/input/objects)"/>
<arg name="output/object" value="$(var output/objects)"/>
<!-- <arg name="output/object" value="$(var output/objects)"/> -->
<arg name="output/object" value="objects"/>
<arg name="filtering_range_param" value="$(var object_recognition_detection_object_position_filter_param_path)"/>
</include>
</group>
Expand Down
56 changes: 29 additions & 27 deletions launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
<arg name="object_recognition_detection_object_range_splitter_radar_param_path"/>
<arg name="object_recognition_detection_object_range_splitter_radar_fusion_param_path"/>
<arg name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"/>
<arg name="object_recognition_tracking_multi_object_tracker_input_channels_param_path"/>
<arg name="object_recognition_tracking_multi_object_tracker_node_param_path"/>
<arg name="object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path"/>
<arg name="object_recognition_tracking_radar_object_tracker_tracking_setting_param_path"/>
Expand All @@ -37,44 +36,47 @@
<arg name="traffic_light_arbiter_param_path"/>

<!-- CenterPoint model parameters -->
<arg name="centerpoint_model_name" default="centerpoint_tiny" description="options: `centerpoint`, `centerpoint_tiny` or `centerpoint_sigma`"/>
<arg name="centerpoint_model_name" default="centerpoint" description="options: `centerpoint`, `centerpoint_tiny` or `centerpoint_sigma`"/>
<arg name="centerpoint_model_path" default="$(var data_path)/lidar_centerpoint"/>

<!-- PointPainting model parameters -->
<arg name="pointpainting_model_path" default="$(var data_path)/image_projection_based_fusion"/>

<!-- Common parameters -->
<arg name="input/pointcloud" default="/sensing/lidar/concatenated/pointcloud" description="The topic will be used in the detection module"/>
<!--USED: /sensing/lidar/concatenated/pointcloud -->
<arg name="input/pointcloud" default="/sensor/lidar/top/points" description="The topic will be used in the detection module"/>
<arg name="mode" default="camera_lidar_fusion" description="options: `camera_lidar_radar_fusion`, `camera_lidar_fusion`, `lidar_radar_fusion`, `lidar` or `radar`"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `pointpainting`, `clustering`"/>
<arg name="image_raw0" default="/sensing/camera/camera0/image_rect_color" description="image raw topic name"/>
<arg name="camera_info0" default="/sensing/camera/camera0/camera_info" description="camera info topic name"/>
<!-- Ideally this images topic should be the rectifed version -->
<arg name="image_raw0" default="/sensor/camera/lspf_r/image_raw" description="image raw topic name"/>
<arg name="camera_info0" default="/sensor/camera/lspf_r/camera_info" description="camera info topic name"/>
<arg name="detection_rois0" default="/perception/object_recognition/detection/rois0" description="detection rois output topic name"/>
<arg name="image_raw1" default="/sensing/camera/camera1/image_rect_color"/>
<arg name="camera_info1" default="/sensing/camera/camera1/camera_info"/>
<arg name="image_raw1" default="/sensor/camera/fsp_l/image_raw"/>
<arg name="camera_info1" default="/sensor/camera/fsp_l/camera_info"/>
<arg name="detection_rois1" default="/perception/object_recognition/detection/rois1"/>
<arg name="image_raw2" default="/sensing/camera/camera2/image_rect_color"/>
<arg name="camera_info2" default="/sensing/camera/camera2/camera_info"/>
<arg name="image_raw2" default="/sensor/camera/rspf_l/image_raw"/>
<arg name="camera_info2" default="/sensor/camera/rspf_l/camera_info"/>
<arg name="detection_rois2" default="/perception/object_recognition/detection/rois2"/>
<arg name="image_raw3" default="/sensing/camera/camera3/image_rect_color"/>
<arg name="camera_info3" default="/sensing/camera/camera3/camera_info"/>
<arg name="image_raw3" default="/sensor/camera/DEFINE/image_raw"/>
<arg name="camera_info3" default="/sensor/camera/DEFINE/camera_info"/>
<arg name="detection_rois3" default="/perception/object_recognition/detection/rois3"/>
<arg name="image_raw4" default="/sensing/camera/camera4/image_rect_color"/>
<arg name="camera_info4" default="/sensing/camera/camera4/camera_info"/>
<arg name="image_raw4" default="/sensor/camera/DEFINE/image_raw"/>
<arg name="camera_info4" default="/sensor/camera/DEFINE/camera_info"/>
<arg name="detection_rois4" default="/perception/object_recognition/detection/rois4"/>
<arg name="image_raw5" default="/sensing/camera/camera5/image_rect_color"/>
<arg name="camera_info5" default="/sensing/camera/camera5/camera_info"/>
<arg name="image_raw5" default="/sensor/camera/DEFINE/image_raw"/>
<arg name="camera_info5" default="/sensor/camera/DEFINE/camera_info"/>
<arg name="detection_rois5" default="/perception/object_recognition/detection/rois5"/>
<arg name="image_raw6" default="/sensing/camera/camera6/image_rect_color"/>
<arg name="camera_info6" default="/sensing/camera/camera6/camera_info"/>
<arg name="image_raw6" default="/sensor/camera/DEFINE/image_raw"/>
<arg name="camera_info6" default="/sensor/camera/DEFINE/camera_info"/>
<arg name="detection_rois6" default="/perception/object_recognition/detection/rois6"/>
<arg name="image_raw7" default="/sensing/camera/camera7/image_rect_color"/>
<arg name="camera_info7" default="/sensing/camera/camera7/camera_info"/>
<arg name="image_raw7" default="/sensor/camera/DEFINE/image_raw"/>
<arg name="camera_info7" default="/sensor/camera/DEFINE/camera_info"/>
<arg name="detection_rois7" default="/perception/object_recognition/detection/rois7"/>
<arg name="image_number" default="6" description="choose image raw number(1-8)"/>
<arg name="use_vector_map" default="true" description="use vector map in prediction"/>
<arg name="use_pointcloud_map" default="true" description="use pointcloud map in detection"/>
<arg name="image_number" default="3" description="choose image raw number(1-8)"/>

<arg name="use_vector_map" default="false" description="use vector map in prediction"/>
<arg name="use_pointcloud_map" default="false" description="use pointcloud map in detection"/>
<arg name="use_low_height_cropbox" default="true" description="use low height crop filter in clustering"/>
<arg name="use_object_filter" default="true" description="use object filter"/>
<arg name="use_roi_based_cluster" default="true" description="use roi_based_cluster in clustering"/>
Expand All @@ -90,7 +92,7 @@
<arg name="use_perception_online_evaluator" default="false" description="use perception online evaluator"/>

<!-- Traffic light recognition parameters -->
<arg name="use_traffic_light_recognition" default="true"/>
<arg name="use_traffic_light_recognition" default="false"/>
<arg name="traffic_light_recognition/enable_fine_detection" default="true"/>
<arg name="traffic_light_recognition/fusion_only" default="false"/>
<arg name="traffic_light_image_number" default="1" description="choose traffic light image raw number(1-2)"/>
Expand All @@ -113,7 +115,7 @@
/>

<!-- Whether to use detection by tracker -->
<arg name="use_detection_by_tracker" default="true"/>
<arg name="use_detection_by_tracker" default="false"/>

<!-- Radar long range integration methods -->
<arg
Expand Down Expand Up @@ -162,7 +164,7 @@
</group>

<!-- Occupancy grid map module -->
<group>
<group if="true">
<push-ros-namespace namespace="occupancy_grid_map"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml">
<arg name="input/obstacle_pointcloud" value="/perception/obstacle_segmentation/single_frame/pointcloud"/>
Expand Down Expand Up @@ -226,7 +228,7 @@
</group>

<!-- Tracking module -->
<group>
<group if="false">
<push-ros-namespace namespace="tracking"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/tracking/tracking.launch.xml">
<arg name="mode" value="$(var mode)"/>
Expand All @@ -242,7 +244,7 @@
</group>

<!-- Prediction module -->
<group>
<group if="false">
<push-ros-namespace namespace="prediction"/>
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/prediction/prediction.launch.xml">
<arg name="use_vector_map" value="$(var use_vector_map)"/>
Expand Down
13 changes: 9 additions & 4 deletions perception/tensorrt_yolox/launch/multiple_yolox.launch.xml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
<launch>
<arg name="image_raw0" default="/image_raw0"/>
<arg name="image_raw0" default="/sensor/camera/lspf_r/image_raw"/>
<arg name="gpu_id_image_raw0" default="0"/>

<arg name="image_raw1" default=""/>
<arg name="image_raw1" default="/sensor/camera/fsp_l/image_raw"/>
<arg name="gpu_id_image_raw1" default="0"/>

<arg name="image_raw2" default=""/>
<arg name="image_raw2" default="/sensor/camera/rspf_l/image_raw"/>
<arg name="gpu_id_image_raw2" default="0"/>

<arg name="image_raw3" default=""/>
Expand All @@ -23,33 +23,38 @@
<arg name="image_raw7" default=""/>
<arg name="gpu_id_image_raw7" default="0"/>

<arg name="image_number" default="1"/>
<arg name="image_number" default="3"/>
<arg name="output_topic" default="rois"/>

<include if="$(eval &quot;'$(var image_number)'>='1'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw0)"/>
<arg name="output/objects" value="rois0"/>
<arg name="gpu_id" value="$(var gpu_id_image_raw0)"/>
<arg name="img_id" value="0"/>
</include>
<include if="$(eval &quot;'$(var image_number)'>='2'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw1)"/>
<arg name="output/objects" value="rois1"/>
<arg name="gpu_id" value="$(var gpu_id_image_raw1)"/>
<arg name="img_id" value="1"/>
</include>
<include if="$(eval &quot;'$(var image_number)'>='3'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw2)"/>
<arg name="output/objects" value="rois2"/>
<arg name="gpu_id" value="$(var gpu_id_image_raw2)"/>
<arg name="img_id" value="2"/>
</include>
<include if="$(eval &quot;'$(var image_number)'>='4'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw3)"/>
<arg name="output/objects" value="rois3"/>
<arg name="gpu_id" value="$(var gpu_id_image_raw3)"/>
<arg name="img_id" value="3"/>
</include>
<include if="$(eval &quot;'$(var image_number)'>='5'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw4)"/>
<arg name="output/objects" value="rois4"/>
<arg name="gpu_id" value="$(var gpu_id_image_raw4)"/>
<arg name="img_id" value="4"/>
</include>
<include if="$(eval &quot;'$(var image_number)'>='6'&quot;)" file="$(find-pkg-share tensorrt_yolox)/launch/yolox.launch.xml">
<arg name="input/image" value="$(var image_raw5)"/>
Expand Down
8 changes: 5 additions & 3 deletions perception/tensorrt_yolox/launch/yolox_s_plus_opt.launch.xml
Original file line number Diff line number Diff line change
@@ -1,23 +1,25 @@
<?xml version="1.0"?>
<launch>
<!-- cspell:ignore finetune -->
<arg name="input/image" default="/sensing/camera/camera0/image_rect_color"/>
<arg name="input/image" default="/sensor/camera/fsp_l/image_raw"/>
<arg name="output/objects" default="/perception/object_recognition/detection/rois0"/>
<arg name="model_name" default="yolox-sPlus-T4-960x960-pseudo-finetune"/>
<arg name="data_path" default="$(env HOME)/autoware_data" description="packages data and artifacts directory path"/>
<arg name="yolox_param_path" default="$(find-pkg-share tensorrt_yolox)/config/yolox_s_plus_opt.param.yaml"/>
<arg name="use_decompress" default="true" description="use image decompress"/>
<arg name="use_decompress" default="false" description="use image decompress"/>
<arg name="build_only" default="false" description="exit after trt engine is built"/>
<arg name="img_id" default="0" description="camera_id"/>

<node pkg="image_transport_decompressor" exec="image_transport_decompressor_node" name="image_transport_decompressor_node" if="$(var use_decompress)">
<remap from="~/input/compressed_image" to="$(var input/image)/compressed"/>
<remap from="~/output/raw_image" to="$(var input/image)"/>
</node>

<node pkg="tensorrt_yolox" exec="tensorrt_yolox_node_exe" name="tensorrt_yolox" output="screen">
<node pkg="tensorrt_yolox" exec="tensorrt_yolox_node_exe" name="tensorrt_yolox_$(var img_id)" output="screen">
<remap from="~/in/image" to="$(var input/image)"/>
<remap from="~/out/objects" to="$(var output/objects)"/>
<param from="$(var yolox_param_path)" allow_substs="true"/>
<param name="build_only" value="$(var build_only)"/>
<!-- <param name="use_sim_time" value="true"/> -->
</node>
</launch>

0 comments on commit 9089da5

Please sign in to comment.