|
17 | 17 | import launch
|
18 | 18 | from launch.actions import DeclareLaunchArgument
|
19 | 19 | from launch.actions import GroupAction
|
| 20 | +from launch.actions import OpaqueFunction |
20 | 21 | from launch.actions import SetLaunchConfiguration
|
21 | 22 | from launch.conditions import IfCondition
|
22 | 23 | from launch.conditions import UnlessCondition
|
|
28 | 29 | import yaml
|
29 | 30 |
|
30 | 31 |
|
31 |
| -def generate_launch_description(): |
32 |
| - |
| 32 | +def launch_setup(context, *args, **kwargs): |
33 | 33 | lanelet2_map_origin_path = os.path.join(
|
34 | 34 | get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml"
|
35 | 35 | )
|
@@ -114,42 +114,56 @@ def generate_launch_description():
|
114 | 114 | output="screen",
|
115 | 115 | )
|
116 | 116 |
|
| 117 | + group = GroupAction( |
| 118 | + [ |
| 119 | + PushRosNamespace("map"), |
| 120 | + container, |
| 121 | + map_hash_generator, |
| 122 | + ] |
| 123 | + ) |
| 124 | + |
| 125 | + return [group] |
| 126 | + |
| 127 | + |
| 128 | +def generate_launch_description(): |
| 129 | + launch_arguments = [] |
| 130 | + |
117 | 131 | def add_launch_arg(name: str, default_value=None, description=None):
|
118 |
| - return DeclareLaunchArgument(name, default_value=default_value, description=description) |
| 132 | + launch_arguments.append( |
| 133 | + DeclareLaunchArgument(name, default_value=default_value, description=description) |
| 134 | + ) |
| 135 | + |
| 136 | + add_launch_arg("map_path", "", "path to map directory"), |
| 137 | + add_launch_arg( |
| 138 | + "lanelet2_map_path", |
| 139 | + [LaunchConfiguration("map_path"), "/lanelet2_map.osm"], |
| 140 | + "path to lanelet2 map file", |
| 141 | + ), |
| 142 | + add_launch_arg( |
| 143 | + "pointcloud_map_path", |
| 144 | + [LaunchConfiguration("map_path"), "/pointcloud_map.pcd"], |
| 145 | + "path to pointcloud map file", |
| 146 | + ), |
| 147 | + add_launch_arg("use_intra_process", "false", "use ROS2 component container communication"), |
| 148 | + add_launch_arg("use_multithread", "false", "use multithread"), |
| 149 | + |
| 150 | + set_container_executable = SetLaunchConfiguration( |
| 151 | + "container_executable", |
| 152 | + "component_container", |
| 153 | + condition=UnlessCondition(LaunchConfiguration("use_multithread")), |
| 154 | + ) |
| 155 | + |
| 156 | + set_container_mt_executable = SetLaunchConfiguration( |
| 157 | + "container_executable", |
| 158 | + "component_container_mt", |
| 159 | + condition=IfCondition(LaunchConfiguration("use_multithread")), |
| 160 | + ) |
119 | 161 |
|
120 | 162 | return launch.LaunchDescription(
|
121 |
| - [ |
122 |
| - add_launch_arg("map_path", "", "path to map directory"), |
123 |
| - add_launch_arg( |
124 |
| - "lanelet2_map_path", |
125 |
| - [LaunchConfiguration("map_path"), "/lanelet2_map.osm"], |
126 |
| - "path to lanelet2 map file", |
127 |
| - ), |
128 |
| - add_launch_arg( |
129 |
| - "pointcloud_map_path", |
130 |
| - [LaunchConfiguration("map_path"), "/pointcloud_map.pcd"], |
131 |
| - "path to pointcloud map file", |
132 |
| - ), |
133 |
| - add_launch_arg( |
134 |
| - "use_intra_process", "false", "use ROS2 component container communication" |
135 |
| - ), |
136 |
| - add_launch_arg("use_multithread", "false", "use multithread"), |
137 |
| - SetLaunchConfiguration( |
138 |
| - "container_executable", |
139 |
| - "component_container", |
140 |
| - condition=UnlessCondition(LaunchConfiguration("use_multithread")), |
141 |
| - ), |
142 |
| - SetLaunchConfiguration( |
143 |
| - "container_executable", |
144 |
| - "component_container_mt", |
145 |
| - condition=IfCondition(LaunchConfiguration("use_multithread")), |
146 |
| - ), |
147 |
| - GroupAction( |
148 |
| - [ |
149 |
| - PushRosNamespace("map"), |
150 |
| - container, |
151 |
| - map_hash_generator, |
152 |
| - ] |
153 |
| - ), |
| 163 | + launch_arguments |
| 164 | + + [ |
| 165 | + set_container_executable, |
| 166 | + set_container_mt_executable, |
154 | 167 | ]
|
| 168 | + + [OpaqueFunction(function=launch_setup)] |
155 | 169 | )
|
0 commit comments