22
22
from launch_ros .actions import ComposableNodeContainer
23
23
from launch_ros .actions import LoadComposableNodes
24
24
from launch_ros .descriptions import ComposableNode
25
+ from launch_ros .parameter_descriptions import ParameterFile
25
26
import yaml
27
+ from ament_index_python .packages import get_package_share_directory
28
+ from pathlib import Path
26
29
27
30
28
31
def get_vehicle_info (context ):
@@ -106,6 +109,20 @@ def create_parameter_dict(*args):
106
109
)
107
110
)
108
111
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
+
109
126
nodes .append (
110
127
ComposableNode (
111
128
package = "autoware_pointcloud_preprocessor" ,
@@ -115,6 +132,7 @@ def create_parameter_dict(*args):
115
132
("input" , "rectified/pointcloud_ex" ),
116
133
("output" , "pointcloud" ),
117
134
],
135
+ parameters = [ring_outlier_filter_node_param , ring_outlier_output_frame ],
118
136
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
119
137
)
120
138
)
@@ -179,6 +197,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
179
197
DeclareLaunchArgument (name , default_value = default_value , description = description )
180
198
)
181
199
200
+ common_sensor_share_dir = Path (
201
+ get_package_share_directory ("common_awsim_sensor_launch" )
202
+ )
203
+
182
204
add_launch_arg ("base_frame" , "base_link" , "base frame id" )
183
205
add_launch_arg ("container_name" , "velodyne_composable_node_container" , "container name" )
184
206
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):
188
210
)
189
211
add_launch_arg ("use_multithread" , "False" , "use multithread" )
190
212
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
+ )
191
220
192
221
set_container_executable = SetLaunchConfiguration (
193
222
"container_executable" ,
0 commit comments