Skip to content

Commit c9d287d

Browse files
Fixed ring_outlier_filter_param
Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
1 parent 7e9f383 commit c9d287d

File tree

3 files changed

+44
-0
lines changed

3 files changed

+44
-0
lines changed

common_awsim_sensor_launch/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -10,5 +10,6 @@ if(BUILD_TESTING)
1010
endif()
1111

1212
ament_auto_package(INSTALL_TO_SHARE
13+
config
1314
launch
1415
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

common_awsim_sensor_launch/launch/velodyne_node_container.launch.py

+29
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,10 @@
2222
from launch_ros.actions import ComposableNodeContainer
2323
from launch_ros.actions import LoadComposableNodes
2424
from launch_ros.descriptions import ComposableNode
25+
from launch_ros.parameter_descriptions import ParameterFile
2526
import yaml
27+
from ament_index_python.packages import get_package_share_directory
28+
from pathlib import Path
2629

2730

2831
def get_vehicle_info(context):
@@ -106,6 +109,20 @@ def create_parameter_dict(*args):
106109
)
107110
)
108111

112+
ring_outlier_filter_node_param = ParameterFile(
113+
param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(
114+
context
115+
),
116+
allow_substs=True,
117+
)
118+
119+
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
120+
if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
121+
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
122+
else:
123+
# keep the output frame as the input frame
124+
ring_outlier_output_frame = {"output_frame": ""}
125+
109126
nodes.append(
110127
ComposableNode(
111128
package="autoware_pointcloud_preprocessor",
@@ -115,6 +132,7 @@ def create_parameter_dict(*args):
115132
("input", "rectified/pointcloud_ex"),
116133
("output", "pointcloud"),
117134
],
135+
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
118136
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
119137
)
120138
)
@@ -179,6 +197,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
179197
DeclareLaunchArgument(name, default_value=default_value, description=description)
180198
)
181199

200+
common_sensor_share_dir = Path(
201+
get_package_share_directory("common_awsim_sensor_launch")
202+
)
203+
182204
add_launch_arg("base_frame", "base_link", "base frame id")
183205
add_launch_arg("container_name", "velodyne_composable_node_container", "container name")
184206
add_launch_arg("input_frame", LaunchConfiguration("base_frame"), "use for cropbox")
@@ -188,6 +210,13 @@ def add_launch_arg(name: str, default_value=None, description=None):
188210
)
189211
add_launch_arg("use_multithread", "False", "use multithread")
190212
add_launch_arg("use_intra_process", "False", "use ROS2 component container communication")
213+
add_launch_arg("output_as_sensor_frame", "False", "output final pointcloud in sensor frame")
214+
add_launch_arg("frame_id", "base_link", "frame id")
215+
add_launch_arg(
216+
"ring_outlier_filter_node_param_path",
217+
str(common_sensor_share_dir / "config" / "ring_outlier_filter_node.param.yaml"),
218+
description="path to parameter file of ring outlier filter node",
219+
)
191220

192221
set_container_executable = SetLaunchConfiguration(
193222
"container_executable",

0 commit comments

Comments
 (0)