Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(tier4_perception_launch): add radar far object integration in tracking stage #5269

Merged
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,10 @@
<arg name="use_near_radar_fusion" default="false"/>
<arg name="far_object_merger_sync_queue_size" default="20"/>

<!-- Filter output name. Switch output topic name by 'radar_long_range_integration' parameter defined in perception.launch -->
<let name="output_of_filtered_objects" value="$(var output/objects)" if="$(eval &quot; '$(var radar_long_range_integration)'=='tracking' &quot;)"/>
<let name="output_of_filtered_objects" value="near_objects" unless="$(eval &quot; '$(var radar_long_range_integration)'=='tracking' &quot;)"/>

<!-- Jetson AGX -->
<!-- <include file="$(find-pkg-share tensorrt_yolo)/launch/yolo.launch.xml">
<arg name="image_raw0" value="$(var image_raw0)"/>
Expand Down Expand Up @@ -392,27 +396,30 @@
<group if="$(eval &quot;'$(var objects_filter_method)'=='lanelet_filter'&quot;)">
<include file="$(find-pkg-share detected_object_validation)/launch/object_lanelet_filter.launch.xml" if="$(var use_object_filter)">
<arg name="input/object" value="objects_before_filter"/>
<arg name="output/object" value="near_objects"/>
<arg name="output/object" value="$(var output_of_filtered_objects)"/>
<arg name="filtering_range_param" value="$(var object_recognition_detection_object_lanelet_filter_param_path)"/>
</include>
</group>

<group if="$(eval &quot;'$(var objects_filter_method)'=='position_filter'&quot;)">
<include file="$(find-pkg-share detected_object_validation)/launch/object_position_filter.launch.xml" if="$(var use_object_filter)">
<arg name="input/object" value="objects_before_filter"/>
<arg name="output/object" value="near_objects"/>
<arg name="output/object" value="$(var output_of_filtered_objects)"/>
<arg name="filtering_range_param" value="$(var object_recognition_detection_object_position_filter_param_path)"/>
</include>
</group>

<!-- Merge far_objects and near_objects. This merger will be removed after tracking fusion operates stably. -->
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="near_objects"/>
<arg name="input/object1" value="radar/far_objects"/>
<arg name="output/object" value="$(var output/objects)"/>
<arg name="priority_mode" value="0"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_detection_object_merger_data_association_matrix_param_path)"/>
<arg name="distance_threshold_list_path" value="$(var object_recognition_detection_object_merger_distance_threshold_list_path)"/>
<arg name="sync_queue_size" value="$(var far_object_merger_sync_queue_size)"/>
</include>
<!-- 'radar_long_range_integration' should defined in perception.launch -->
<group if="$(eval &quot;'$(var radar_long_range_integration)'=='detection'&quot;)">
<!-- Merge far_objects and near_objects. This merger will be removed after tracking fusion operates stably. -->
miursh marked this conversation as resolved.
Show resolved Hide resolved
<include file="$(find-pkg-share object_merger)/launch/object_association_merger.launch.xml">
<arg name="input/object0" value="near_objects"/>
<arg name="input/object1" value="radar/far_objects"/>
<arg name="output/object" value="$(var output/objects)"/>
<arg name="priority_mode" value="0"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_detection_object_merger_data_association_matrix_param_path)"/>
<arg name="distance_threshold_list_path" value="$(var object_recognition_detection_object_merger_distance_threshold_list_path)"/>
<arg name="sync_queue_size" value="$(var far_object_merger_sync_queue_size)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@
<launch>
<arg name="use_vector_map" default="false" description="use vector map in prediction"/>
<arg name="param_path" default="$(find-pkg-share map_based_prediction)/config/map_based_prediction.param.yaml"/>
<arg name="input_topic_to_prediction" default="/perception/object_recognition/tracking/objects"/>
scepter914 marked this conversation as resolved.
Show resolved Hide resolved

<group if="$(var use_vector_map)">
<set_remap from="objects" to="/perception/object_recognition/objects"/>
<include file="$(find-pkg-share map_based_prediction)/launch/map_based_prediction.launch.xml">
<arg name="output_topic" value="/perception/object_recognition/objects"/>
<arg name="input_topic" value="$(var input_topic_to_prediction)"/>
<arg name="param_path" value="$(var object_recognition_prediction_map_based_prediction_param_path)"/>
</include>
</group>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,29 +3,54 @@
<arg name="mode" default="lidar" description="options: `camera_lidar_radar_fusion`, `camera_lidar_fusion`, `lidar_radar_fusion`, `lidar` or `radar`"/>
<arg name="publish_rate" default="10.0"/>
<arg name="enable_delay_compensation" default="true"/>

<!-- Radar Tracking and Merger parameters -->
<arg name="radar_long_range_integration" default="detection" description="integration method for radar long range information. Following args are used only if this parameter is set to 'tracking'"/>
<arg name="radar_tracker_input" default="/perception/object_recognition/detection/radar/far_objects"/>
<arg name="radar_tracker_output" default="/perception/object_recognition/tracking/radar/far_objects"/>
<arg name="object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path" description="association param file for radar far object tracking"/>
<arg name="object_recognition_tracking_radar_object_tracker_tracking_setting_param_path" description="tracking setting param file for radar far object tracking"/>
<arg name="object_recognition_tracking_radar_object_tracker_node_param_path" description="node param file for radar far object tracking"/>
<arg name="object_recognition_tracking_object_merger_data_association_matrix_param_path" description="association param file for radar and lidar object merger"/>
<arg name="object_recognition_tracking_object_merger_node_param_path" description="node param file for radar and lidar object merger"/>

<group>
<!-- Run without tracking merger-->
<group unless="$(eval &quot;'$(var radar_long_range_integration)'=='tracking'&quot;)">
<!--multi object tracking-->
<include file="$(find-pkg-share multi_object_tracker)/launch/multi_object_tracker.launch.xml">
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path)"/>
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
</include>
</group>

<!--radar long range dynamic object tracking if mode contains radar input-->
<!--
<group if="$(eval '&quot;$(var mode)&quot;==&quot;radar&quot; or &quot;$(var mode)&quot;==&quot;lidar_radar_fusion&quot; or &quot;$(var mode)&quot;==&quot;camera_lidar_radar_fusion&quot;')">
<include file="$(find-pkg-share radar_object_tracker)/launch/radar_object_tracker.launch.xml">
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="input" value="$(var radar_tracker_input)"/>
<arg name="output" value="$(var radar_tracker_output)"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path)"/>
<arg name="tracker_setting_path" value="$(var object_recognition_tracking_radar_object_tracker_tracking_setting_param_path)"/>
</include>
</group>
-->
<!-- Run with tracking merger to add far radar information -->
<group if="$(eval &quot;'$(var radar_long_range_integration)'=='tracking'&quot;)">
<!--multi object tracking for near objects-->
<include file="$(find-pkg-share multi_object_tracker)/launch/multi_object_tracker.launch.xml">
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path)"/>
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="output" value="/perception/object_recognition/tracking/near_objects"/>
</include>

<!--radar long range dynamic object tracking-->
<include file="$(find-pkg-share radar_object_tracker)/launch/radar_object_tracker.launch.xml">
<arg name="publish_rate" value="$(var publish_rate)"/>
<arg name="enable_delay_compensation" value="$(var enable_delay_compensation)"/>
<arg name="input" value="$(var radar_tracker_input)"/>
<arg name="output" value="$(var radar_tracker_output)"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path)"/>
<arg name="tracker_setting_path" value="$(var object_recognition_tracking_radar_object_tracker_tracking_setting_param_path)"/>
</include>

<!--tracking object merger to merge near objects and far objects -->
<include file="$(find-pkg-share tracking_object_merger)/launch/decorative_tracker_merger.launch.xml">
<arg name="input/main_object" value="/perception/object_recognition/tracking/near_objects"/>
<arg name="input/sub_object" value="$(var radar_tracker_output)"/>
<arg name="output" value="/perception/object_recognition/tracking/objects"/>
<arg name="data_association_matrix_path" value="$(var object_recognition_tracking_object_merger_data_association_matrix_param_path)"/>
<arg name="node_param_file_path" value="$(var object_recognition_tracking_object_merger_node_param_path)"/>
</include>
</group>
</launch>
16 changes: 16 additions & 0 deletions launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,14 @@
<arg name="fusion_distance" default="100.0"/>
<arg name="trust_object_distance" default="100.0"/>

<!-- Radar long range integration methods -->
<arg
name="radar_long_range_integration"
scepter914 marked this conversation as resolved.
Show resolved Hide resolved
default="tracking"
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[IMO]
Now, we reduced weight by reducing various functions.
I guess radar tracking is a little heavy process (about 20ms processing time), so I want lightweight perception as this default parameter for now.
And I want to put it into operation that if there is enough computational power for project, this parameter can change.

So I think default parameter of should be detection.
If changing to use_radar_tracking_fusion, it should be false.

description="integration method for radar long range information.
'detection' means radar information is merged in detection launch. 'tracking' means radar information is merged in tracking launch. 'none' means radar information is not merged."
/>

<!-- Perception module -->
<group>
<push-ros-namespace namespace="perception"/>
Expand Down Expand Up @@ -181,6 +189,14 @@
<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)"/>
<arg
name="object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path"
value="$(var object_recognition_tracking_radar_object_tracker_data_association_matrix_param_path)"
/>
<arg name="object_recognition_tracking_radar_object_tracker_tracking_setting_param_path" value="$(var object_recognition_tracking_radar_object_tracker_tracking_setting_param_path)"/>
<arg name="object_recognition_tracking_radar_object_tracker_node_param_path" value="$(var object_recognition_tracking_radar_object_tracker_node_param_path)"/>
<arg name="object_recognition_tracking_object_merger_data_association_matrix_param_path" value="$(var object_recognition_tracking_object_merger_data_association_matrix_param_path)"/>
<arg name="object_recognition_tracking_object_merger_node_param_path" value="$(var object_recognition_tracking_object_merger_node_param_path)"/>
</include>
</group>

Expand Down
Loading