Skip to content

Commit c484d8f

Browse files
h-ohtapre-commit-ci[bot]
andauthoredMay 24, 2022
refactor: tier4_map_launch (#953)
* refactor: tier4_map_launch * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent f2577c6 commit c484d8f

File tree

1 file changed

+50
-36
lines changed

1 file changed

+50
-36
lines changed
 

‎launch/tier4_map_launch/launch/map.launch.py

+50-36
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
import launch
1818
from launch.actions import DeclareLaunchArgument
1919
from launch.actions import GroupAction
20+
from launch.actions import OpaqueFunction
2021
from launch.actions import SetLaunchConfiguration
2122
from launch.conditions import IfCondition
2223
from launch.conditions import UnlessCondition
@@ -28,8 +29,7 @@
2829
import yaml
2930

3031

31-
def generate_launch_description():
32-
32+
def launch_setup(context, *args, **kwargs):
3333
lanelet2_map_origin_path = os.path.join(
3434
get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml"
3535
)
@@ -114,42 +114,56 @@ def generate_launch_description():
114114
output="screen",
115115
)
116116

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+
117131
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+
)
119161

120162
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,
154167
]
168+
+ [OpaqueFunction(function=launch_setup)]
155169
)

0 commit comments

Comments
 (0)
Please sign in to comment.