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: always separate lidar preprocessing from pointcloud_container #796

Merged
Merged
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,19 @@
<arg name="pose_source" default="ndt" description="select pose_estimator: ndt, yabloc, eagleye"/>
<arg name="twist_source" default="gyro_odom" description="select twist_estimator. gyro_odom, eagleye"/>
<arg name="input_pointcloud" default="/sensing/lidar/top/pointcloud" description="The topic will be used in the localization util module"/>
<arg
name="lidar_container_name"
default="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container"
description="The target container to which lidar preprocessing nodes in localization be attached"
/>

<group>
<include file="$(find-pkg-share tier4_localization_launch)/launch/localization.launch.xml">
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="pose_source" value="$(var pose_source)"/>
<arg name="twist_source" value="$(var twist_source)"/>
<arg name="system_run_mode" value="$(var system_run_mode)"/>
<arg name="input_pointcloud" value="$(var input_pointcloud)"/>
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>

<!-- parameter paths for common -->
<arg name="crop_box_filter_measurement_range_param_path" value="$(var loc_config_path)/crop_box_filter_measurement_range.param.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
<include file="$(find-pkg-share tier4_perception_launch)/launch/perception.launch.xml">
<arg name="mode" value="$(var perception_mode)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="enable_fine_detection" value="$(var traffic_light_recognition/enable_fine_detection)"/>
<arg name="occupancy_grid_map_method" value="$(var occupancy_grid_map_method)"/>
Expand Down
Loading