12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import os
15
16
17
+ from ament_index_python .packages import get_package_share_directory
16
18
import launch
17
19
from launch .actions import DeclareLaunchArgument
18
20
from launch .actions import OpaqueFunction
22
24
from launch .substitutions import LaunchConfiguration
23
25
from launch_ros .actions import LoadComposableNodes
24
26
from launch_ros .descriptions import ComposableNode
27
+ from launch_ros .parameter_descriptions import ParameterFile
25
28
26
29
27
30
def launch_setup (context , * args , ** kwargs ):
31
+ # concatenate node parameters
32
+ concatenate_and_time_sync_node_param = ParameterFile (
33
+ param_file = LaunchConfiguration ("concatenate_and_time_sync_node_param_path" ).perform (
34
+ context
35
+ ),
36
+ allow_substs = True ,
37
+ )
38
+
28
39
# set concat filter as a component
29
40
concat_component = ComposableNode (
30
41
package = "autoware_pointcloud_preprocessor" ,
@@ -34,18 +45,7 @@ def launch_setup(context, *args, **kwargs):
34
45
("~/input/twist" , "/sensing/vehicle_velocity_converter/twist_with_covariance" ),
35
46
("output" , "concatenated/pointcloud" ),
36
47
],
37
- parameters = [
38
- {
39
- "input_topics" : [
40
- "/sensing/lidar/top/pointcloud_before_sync" ,
41
- "/sensing/lidar/left/pointcloud_before_sync" ,
42
- "/sensing/lidar/right/pointcloud_before_sync" ,
43
- ],
44
- "output_frame" : LaunchConfiguration ("base_frame" ),
45
- "input_twist_topic_type" : "twist" ,
46
- "publish_synchronized_pointcloud" : True ,
47
- }
48
- ],
48
+ parameters = [concatenate_and_time_sync_node_param ],
49
49
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
50
50
)
51
51
@@ -65,10 +65,20 @@ def generate_launch_description():
65
65
def add_launch_arg (name : str , default_value = None ):
66
66
launch_arguments .append (DeclareLaunchArgument (name , default_value = default_value ))
67
67
68
+ sample_sensor_kit_launch_share_dir = get_package_share_directory ("sample_sensor_kit_launch" )
69
+
68
70
add_launch_arg ("base_frame" , "base_link" )
69
71
add_launch_arg ("use_multithread" , "False" )
70
72
add_launch_arg ("use_intra_process" , "False" )
71
73
add_launch_arg ("pointcloud_container_name" , "pointcloud_container" )
74
+ add_launch_arg (
75
+ "concatenate_and_time_sync_node_param_path" ,
76
+ os .path .join (
77
+ sample_sensor_kit_launch_share_dir ,
78
+ "config" ,
79
+ "concatenate_and_time_sync_node.param.yaml" ,
80
+ ),
81
+ )
72
82
73
83
set_container_executable = SetLaunchConfiguration (
74
84
"container_executable" ,
0 commit comments