Skip to content

Commit

Permalink
Merge pull request #1813 from tier4/cherry-pick-10102
Browse files Browse the repository at this point in the history
fix(ground_segmentation): bring junction parameter from param file to launch argument  (autowarefoundation#10102)
  • Loading branch information
SakodaShintaro authored Feb 17, 2025
2 parents 36209bb + 3e89c58 commit c316a1c
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,16 @@ def __init__(self, context):
"/perception/obstacle_segmentation/single_frame/pointcloud"
)
self.output_topic = "/perception/obstacle_segmentation/pointcloud"
self.use_single_frame_filter = self.ground_segmentation_param["use_single_frame_filter"]
self.use_time_series_filter = self.ground_segmentation_param["use_time_series_filter"]
self.use_single_frame_filter = LaunchConfiguration("use_single_frame_filter").perform(
context
)
self.use_time_series_filter = LaunchConfiguration("use_time_series_filter").perform(context)
# check if self.use_single_frame_filter is bool
if isinstance(self.use_single_frame_filter, str):
self.use_single_frame_filter = self.use_single_frame_filter.lower() == "true"
# check if self.use_time_series_filter is bool
if isinstance(self.use_time_series_filter, str):
self.use_time_series_filter = self.use_time_series_filter.lower() == "true"

def get_vehicle_info(self):
# TODO(TIER IV): Use Parameter Substitution after we drop Galactic support
Expand Down
14 changes: 12 additions & 2 deletions launch/tier4_perception_launch/launch/perception.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,9 @@
<arg name="camera_info7" default="/sensing/camera/camera7/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="pointcloud_container_name" default="pointcloud_container"/>

<!-- Pipeline junctions -->
<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="use_low_height_cropbox" default="true" description="use low height crop filter in the euclidean clustering"/>
Expand All @@ -88,10 +91,11 @@
default="false"
description="if use_empty_dynamic_object_publisher:=true, /perception/object_recognition/objects topic has an empty DynamicObjectArray"
/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="use_object_validator" default="true" description="use obstacle_pointcloud based object validator"/>
<arg name="objects_validation_method" default="obstacle_pointcloud" description="options: `obstacle_pointcloud` or `occupancy_grid`"/>
<arg name="use_perception_online_evaluator" default="false" description="use perception online evaluator"/>
<arg name="use_obstacle_segmentation_single_frame_filter" description="use single frame filter at the ground segmentation"/>
<arg name="use_obstacle_segmentation_time_series_filter" description="use time series filter at the ground segmentation"/>

<!-- Traffic light recognition parameters -->
<arg name="use_traffic_light_recognition" default="false"/>
Expand Down Expand Up @@ -171,14 +175,20 @@
<arg name="use_multithread" value="true"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="input/pointcloud" value="$(var perception_pointcloud)"/>
<arg name="obstacle_segmentation_ground_segmentation_param_path" value="$(var obstacle_segmentation_ground_segmentation_param_path)"/>
<arg name="use_single_frame_filter" value="$(var use_obstacle_segmentation_single_frame_filter)"/>
<arg name="use_time_series_filter" value="$(var use_obstacle_segmentation_time_series_filter)"/>
</include>
</group>

<!-- Occupancy grid map module -->
<group>
<push-ros-namespace namespace="occupancy_grid_map"/>
<let name="unfiltered_obstacle_pointcloud" value="/perception/obstacle_segmentation/pointcloud"/>
<let name="unfiltered_obstacle_pointcloud" value="/perception/obstacle_segmentation/single_frame/pointcloud" if="$(var use_obstacle_segmentation_single_frame_filter)"/>
<let name="unfiltered_obstacle_pointcloud" value="/perception/obstacle_segmentation/single_frame/pointcloud" if="$(var use_obstacle_segmentation_time_series_filter)"/>
<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"/>
<arg name="input/obstacle_pointcloud" value="$(var unfiltered_obstacle_pointcloud)"/>
<arg name="input/raw_pointcloud" value="$(var perception_pointcloud)"/>
<arg name="output" value="/perception/occupancy_grid_map/map"/>
<arg name="use_intra_process" value="true"/>
Expand Down

0 comments on commit c316a1c

Please sign in to comment.