17from ament_index_python.packages
import get_package_share_directory
19from launch
import LaunchDescription
20from launch.actions
import (
21 DeclareLaunchArgument,
23 IncludeLaunchDescription,
24 SetEnvironmentVariable,
26from launch.conditions
import IfCondition
27from launch.launch_description_sources
import PythonLaunchDescriptionSource
28from launch.substitutions
import LaunchConfiguration, PythonExpression
29from launch_ros.actions
import PushRosNamespace
34 sm_dance_bot_dir = get_package_share_directory(
"sm_dance_bot")
35 launch_dir = os.path.join(sm_dance_bot_dir,
"launch")
38 namespace = LaunchConfiguration(
"namespace")
39 use_namespace = LaunchConfiguration(
"use_namespace")
40 slam = LaunchConfiguration(
"slam")
41 map_yaml_file = LaunchConfiguration(
"map")
42 use_sim_time = LaunchConfiguration(
"use_sim_time")
43 params_file = LaunchConfiguration(
"params_file")
44 default_nav_to_pose_bt_xml = LaunchConfiguration(
"default_nav_to_pose_bt_xml")
45 autostart = LaunchConfiguration(
"autostart")
47 stdout_linebuf_envvar = SetEnvironmentVariable(
"RCUTILS_LOGGING_BUFFERED_STREAM",
"1")
49 declare_namespace_cmd = DeclareLaunchArgument(
50 "namespace", default_value=
"", description=
"Top-level namespace"
53 declare_use_namespace_cmd = DeclareLaunchArgument(
55 default_value=
"false",
56 description=
"Whether to apply a namespace to the navigation stack",
59 declare_slam_cmd = DeclareLaunchArgument(
60 "slam", default_value=
"False", description=
"Whether run a SLAM"
63 declare_map_yaml_cmd = DeclareLaunchArgument(
64 "map", description=
"Full path to map yaml file to load"
67 declare_use_sim_time_cmd = DeclareLaunchArgument(
68 "use_sim_time", default_value=
"false", description=
"Use simulation (Gazebo) clock if true"
71 declare_params_file_cmd = DeclareLaunchArgument(
73 default_value=os.path.join(sm_dance_bot_dir,
"params",
"nav2z_client",
"nav2_params.yaml"),
74 description=
"Full path to the ROS2 parameters file to use for all launched nodes",
77 declare_bt_xml_cmd = DeclareLaunchArgument(
78 "default_nav_to_pose_bt_xml",
79 default_value=os.path.join(
80 sm_dance_bot_dir,
"params",
"nav2z_client",
"navigation_tree.xml"
82 description=
"Full path to the behavior tree xml file to use",
85 declare_autostart_cmd = DeclareLaunchArgument(
86 "autostart", default_value=
"true", description=
"Automatically startup the nav2 stack"
90 bringup_cmd_group = GroupAction(
92 PushRosNamespace(condition=IfCondition(use_namespace), namespace=namespace),
93 IncludeLaunchDescription(
94 PythonLaunchDescriptionSource(os.path.join(launch_dir,
"slam_launch.py")),
95 condition=IfCondition(slam),
97 "namespace": namespace,
98 "use_sim_time": use_sim_time,
99 "autostart": autostart,
100 "params_file": params_file,
103 IncludeLaunchDescription(
104 PythonLaunchDescriptionSource(os.path.join(launch_dir,
"localization_launch.py")),
105 condition=IfCondition(PythonExpression([
"not ", slam])),
107 "namespace": namespace,
108 "map": map_yaml_file,
109 "use_sim_time": use_sim_time,
110 "autostart": autostart,
111 "params_file": params_file,
112 "use_lifecycle_mgr":
"false",
115 IncludeLaunchDescription(
116 PythonLaunchDescriptionSource(os.path.join(launch_dir,
"navigation_launch.py")),
118 "namespace": namespace,
119 "use_sim_time": use_sim_time,
120 "autostart": autostart,
121 "params_file": params_file,
122 "default_nav_to_pose_bt_xml": default_nav_to_pose_bt_xml,
123 "use_lifecycle_mgr":
"false",
124 "map_subscribe_transient_local":
"true",
131 ld = LaunchDescription()
134 ld.add_action(stdout_linebuf_envvar)
137 ld.add_action(declare_namespace_cmd)
138 ld.add_action(declare_use_namespace_cmd)
139 ld.add_action(declare_slam_cmd)
140 ld.add_action(declare_map_yaml_cmd)
141 ld.add_action(declare_use_sim_time_cmd)
142 ld.add_action(declare_params_file_cmd)
143 ld.add_action(declare_autostart_cmd)
144 ld.add_action(declare_bt_xml_cmd)
147 ld.add_action(bringup_cmd_group)
def generate_launch_description()