Skip to content

Commit

Permalink
refactor: tier4_map_launch (#953)
Browse files Browse the repository at this point in the history
* refactor: tier4_map_launch

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
h-ohta and pre-commit-ci[bot] authored May 24, 2022
1 parent f2577c6 commit c484d8f
Showing 1 changed file with 50 additions and 36 deletions.
86 changes: 50 additions & 36 deletions launch/tier4_map_launch/launch/map.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
from launch.actions import OpaqueFunction
from launch.actions import SetLaunchConfiguration
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
Expand All @@ -28,8 +29,7 @@
import yaml


def generate_launch_description():

def launch_setup(context, *args, **kwargs):
lanelet2_map_origin_path = os.path.join(
get_package_share_directory("map_loader"), "config/lanelet2_map_loader.param.yaml"
)
Expand Down Expand Up @@ -114,42 +114,56 @@ def generate_launch_description():
output="screen",
)

group = GroupAction(
[
PushRosNamespace("map"),
container,
map_hash_generator,
]
)

return [group]


def generate_launch_description():
launch_arguments = []

def add_launch_arg(name: str, default_value=None, description=None):
return DeclareLaunchArgument(name, default_value=default_value, description=description)
launch_arguments.append(
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

add_launch_arg("map_path", "", "path to map directory"),
add_launch_arg(
"lanelet2_map_path",
[LaunchConfiguration("map_path"), "/lanelet2_map.osm"],
"path to lanelet2 map file",
),
add_launch_arg(
"pointcloud_map_path",
[LaunchConfiguration("map_path"), "/pointcloud_map.pcd"],
"path to pointcloud map file",
),
add_launch_arg("use_intra_process", "false", "use ROS2 component container communication"),
add_launch_arg("use_multithread", "false", "use multithread"),

set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
condition=UnlessCondition(LaunchConfiguration("use_multithread")),
)

set_container_mt_executable = SetLaunchConfiguration(
"container_executable",
"component_container_mt",
condition=IfCondition(LaunchConfiguration("use_multithread")),
)

return launch.LaunchDescription(
[
add_launch_arg("map_path", "", "path to map directory"),
add_launch_arg(
"lanelet2_map_path",
[LaunchConfiguration("map_path"), "/lanelet2_map.osm"],
"path to lanelet2 map file",
),
add_launch_arg(
"pointcloud_map_path",
[LaunchConfiguration("map_path"), "/pointcloud_map.pcd"],
"path to pointcloud map file",
),
add_launch_arg(
"use_intra_process", "false", "use ROS2 component container communication"
),
add_launch_arg("use_multithread", "false", "use multithread"),
SetLaunchConfiguration(
"container_executable",
"component_container",
condition=UnlessCondition(LaunchConfiguration("use_multithread")),
),
SetLaunchConfiguration(
"container_executable",
"component_container_mt",
condition=IfCondition(LaunchConfiguration("use_multithread")),
),
GroupAction(
[
PushRosNamespace("map"),
container,
map_hash_generator,
]
),
launch_arguments
+ [
set_container_executable,
set_container_mt_executable,
]
+ [OpaqueFunction(function=launch_setup)]
)

0 comments on commit c484d8f

Please sign in to comment.