19from ament_index_python.packages
import get_package_share_directory
21from launch
import LaunchDescription
22from launch.actions
import DeclareLaunchArgument, SetEnvironmentVariable
23from launch.substitutions
import LaunchConfiguration
24from launch_ros.actions
import Node
25from nav2_common.launch
import RewrittenYaml
30 sm_husky_barrel_search_1 = get_package_share_directory(
"sm_husky_barrel_search_1")
32 namespace = LaunchConfiguration(
"namespace")
33 use_sim_time = LaunchConfiguration(
"use_sim_time")
34 autostart = LaunchConfiguration(
"autostart")
35 params_file = LaunchConfiguration(
"params_file")
36 default_nav_to_pose_bt_xml = LaunchConfiguration(
"default_nav_to_pose_bt_xml")
37 map_subscribe_transient_local = LaunchConfiguration(
"map_subscribe_transient_local")
39 lifecycle_nodes = [
"controller_server",
"planner_server",
"recoveries_server",
"bt_navigator"]
47 remappings = [(
"/tf",
"tf"), (
"/tf_static",
"tf_static")]
50 param_substitutions = {
51 "use_sim_time": use_sim_time,
53 "default_nav_to_pose_bt_xml": os.path.join(
54 sm_husky_barrel_search_1,
"params",
"nav2z_client",
"navigation_tree.xml"
56 "autostart": autostart,
57 "map_subscribe_transient_local": map_subscribe_transient_local,
60 configured_params = RewrittenYaml(
61 source_file=params_file,
63 param_rewrites=param_substitutions,
67 xtermprefix =
"xterm -xrm 'XTerm*scrollBar: true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e"
69 print(
"+********************************")
70 print(str(param_substitutions))
71 print(str(default_nav_to_pose_bt_xml))
73 return LaunchDescription(
76 SetEnvironmentVariable(
"RCUTILS_LOGGING_BUFFERED_STREAM",
"1"),
77 DeclareLaunchArgument(
78 "namespace", default_value=
"", description=
"Top-level namespace"
80 DeclareLaunchArgument(
82 default_value=
"false",
83 description=
"Use simulation (Gazebo) clock if true",
85 DeclareLaunchArgument(
88 description=
"Automatically startup the nav2 stack",
90 DeclareLaunchArgument(
92 default_value=os.path.join(
93 sm_husky_barrel_search_1,
"params",
"nav2z_client",
"nav2_params.yaml"
95 description=
"Full path to the ROS2 parameters file to use",
97 DeclareLaunchArgument(
98 "default_nav_to_pose_bt_xml",
100 default_value=os.path.join(
101 sm_husky_barrel_search_1,
"params",
"nav2z_client",
"navigation_tree.xml"
103 description=
"Full path to the behavior tree xml file to use",
105 DeclareLaunchArgument(
106 "map_subscribe_transient_local",
107 default_value=
"false",
108 description=
"Whether to set the map subscriber QoS to transient local",
111 package=
"nav2_controller",
112 executable=
"controller_server",
115 parameters=[configured_params],
116 remappings=remappings,
117 arguments=[
"--ros-args",
"--log-level",
"INFO"],
120 package=
"nav2_planner",
121 executable=
"planner_server",
122 name=
"planner_server",
125 parameters=[configured_params],
126 remappings=remappings,
127 arguments=[
"--ros-args",
"--log-level",
"INFO"],
130 package=
"nav2_recoveries",
131 executable=
"recoveries_server",
132 name=
"recoveries_server",
134 parameters=[configured_params],
135 remappings=remappings,
136 arguments=[
"--ros-args",
"--log-level",
"INFO"],
139 package=
"nav2_bt_navigator",
140 executable=
"bt_navigator",
144 parameters=[configured_params],
145 remappings=remappings,
146 arguments=[
"--ros-args",
"--log-level",
"INFO"],
157 package=
"nav2_lifecycle_manager",
158 executable=
"lifecycle_manager",
159 name=
"lifecycle_manager_navigation",
163 {
"use_sim_time": use_sim_time},
164 {
"autostart": autostart},
165 {
"node_names": lifecycle_nodes},
167 arguments=[
"--ros-args",
"--log-level",
"INFO"],
def generate_launch_description()