SMACC2
navigation_launch.py
Go to the documentation of this file.
1# Copyright (c) 2018 Intel Corporation
2#
3# Licensed under the Apache License, Version 2.0 (the "License");
4# you may not use this file except in compliance with the License.
5# You may obtain a copy of the License at
6#
7# http://www.apache.org/licenses/LICENSE-2.0
8#
9# Unless required by applicable law or agreed to in writing, software
10# distributed under the License is distributed on an "AS IS" BASIS,
11# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12# See the License for the specific language governing permissions and
13# limitations under the License.
14
15import os
16
17# from cv2 import remap
18
19from ament_index_python.packages import get_package_share_directory
20
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
26
27
29 # Get the launch directory
30 sm_husky_barrel_search_1 = get_package_share_directory("sm_husky_barrel_search_1")
31
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")
38
39 lifecycle_nodes = ["controller_server", "planner_server", "recoveries_server", "bt_navigator"]
40
41 # Map fully qualified names to relative ones so the node's namespace can be prepended.
42 # In case of the transforms (tf), currently, there doesn't seem to be a better alternative
43 # https://github.com/ros/geometry2/issues/32
44 # https://github.com/ros/robot_state_publisher/pull/30
45 # TODO(orduno) Substitute with `PushNodeRemapping`
46 # https://github.com/ros2/launch_ros/issues/56
47 remappings = [("/tf", "tf"), ("/tf_static", "tf_static")]
48
49 # Create our own temporary YAML files that include substitutions
50 param_substitutions = {
51 "use_sim_time": use_sim_time,
52 # 'default_nav_to_pose_bt_xml': default_nav_to_pose_bt_xml,
53 "default_nav_to_pose_bt_xml": os.path.join(
54 sm_husky_barrel_search_1, "params", "nav2z_client", "navigation_tree.xml"
55 ),
56 "autostart": autostart,
57 "map_subscribe_transient_local": map_subscribe_transient_local,
58 }
59
60 configured_params = RewrittenYaml(
61 source_file=params_file,
62 root_key=namespace,
63 param_rewrites=param_substitutions,
64 convert_types=True,
65 )
66
67 xtermprefix = "xterm -xrm 'XTerm*scrollBar: true' -xrm 'xterm*rightScrollBar: true' -hold -geometry 1000x600 -sl 10000 -e"
68
69 print("+********************************")
70 print(str(param_substitutions))
71 print(str(default_nav_to_pose_bt_xml))
72
73 return LaunchDescription(
74 [
75 # Set env var to print messages to stdout immediately
76 SetEnvironmentVariable("RCUTILS_LOGGING_BUFFERED_STREAM", "1"),
77 DeclareLaunchArgument(
78 "namespace", default_value="", description="Top-level namespace"
79 ),
80 DeclareLaunchArgument(
81 "use_sim_time",
82 default_value="false",
83 description="Use simulation (Gazebo) clock if true",
84 ),
85 DeclareLaunchArgument(
86 "autostart",
87 default_value="true",
88 description="Automatically startup the nav2 stack",
89 ),
90 DeclareLaunchArgument(
91 "params_file",
92 default_value=os.path.join(
93 sm_husky_barrel_search_1, "params", "nav2z_client", "nav2_params.yaml"
94 ),
95 description="Full path to the ROS2 parameters file to use",
96 ),
97 DeclareLaunchArgument(
98 "default_nav_to_pose_bt_xml",
99 # default_value=os.path.join(get_package_share_directory('nav2_bt_navigator'),'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
100 default_value=os.path.join(
101 sm_husky_barrel_search_1, "params", "nav2z_client", "navigation_tree.xml"
102 ),
103 description="Full path to the behavior tree xml file to use",
104 ),
105 DeclareLaunchArgument(
106 "map_subscribe_transient_local",
107 default_value="false",
108 description="Whether to set the map subscriber QoS to transient local",
109 ),
110 Node(
111 package="nav2_controller",
112 executable="controller_server",
113 output="screen",
114 prefix=xtermprefix,
115 parameters=[configured_params],
116 remappings=remappings,
117 arguments=["--ros-args", "--log-level", "INFO"],
118 ),
119 Node(
120 package="nav2_planner",
121 executable="planner_server",
122 name="planner_server",
123 output="screen",
124 prefix=xtermprefix,
125 parameters=[configured_params],
126 remappings=remappings,
127 arguments=["--ros-args", "--log-level", "INFO"],
128 ),
129 Node(
130 package="nav2_recoveries",
131 executable="recoveries_server",
132 name="recoveries_server",
133 output="screen",
134 parameters=[configured_params],
135 remappings=remappings,
136 arguments=["--ros-args", "--log-level", "INFO"],
137 ),
138 Node(
139 package="nav2_bt_navigator",
140 executable="bt_navigator",
141 name="bt_navigator",
142 output="screen",
143 prefix=xtermprefix,
144 parameters=[configured_params],
145 remappings=remappings,
146 arguments=["--ros-args", "--log-level", "INFO"],
147 ),
148 # Node(
149 # package="nav2_waypoint_follower",
150 # executable="waypoint_follower",
151 # name="waypoint_follower",
152 # output="screen",
153 # parameters=[configured_params],
154 # remappings=remappings,
155 # ),
156 Node(
157 package="nav2_lifecycle_manager",
158 executable="lifecycle_manager",
159 name="lifecycle_manager_navigation",
160 output="screen",
161 prefix=xtermprefix,
162 parameters=[
163 {"use_sim_time": use_sim_time},
164 {"autostart": autostart},
165 {"node_names": lifecycle_nodes},
166 ],
167 arguments=["--ros-args", "--log-level", "INFO"],
168 ),
169 ]
170 )