Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
collision_monitor_node.launch.py
1 #!/usr/bin/env python3
2 
3 # Copyright (c) 2022 Samsung R&D Institute Russia
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 import os
18 
19 from ament_index_python.packages import get_package_share_directory
20 
21 from launch import LaunchDescription
22 from launch.actions import DeclareLaunchArgument, GroupAction
23 from launch.conditions import IfCondition
24 from launch.substitutions import LaunchConfiguration, PythonExpression
25 from launch.substitutions import NotEqualsSubstitution
26 from launch_ros.actions import LoadComposableNodes, SetParameter
27 from launch_ros.actions import Node
28 from launch_ros.actions import PushROSNamespace
29 from launch_ros.descriptions import ComposableNode, ParameterFile
30 from nav2_common.launch import RewrittenYaml
31 
32 
33 def generate_launch_description():
34  # Environment
35  package_dir = get_package_share_directory('nav2_collision_monitor')
36 
37  # Constant parameters
38  lifecycle_nodes = ['collision_monitor']
39  autostart = True
40  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
41 
42  # Launch arguments
43  # 1. Create the launch configuration variables
44  namespace = LaunchConfiguration('namespace')
45  use_sim_time = LaunchConfiguration('use_sim_time')
46  params_file = LaunchConfiguration('params_file')
47  use_composition = LaunchConfiguration('use_composition')
48  container_name = LaunchConfiguration('container_name')
49  container_name_full = (namespace, '/', container_name)
50 
51  # 2. Declare the launch arguments
52  declare_namespace_cmd = DeclareLaunchArgument(
53  'namespace', default_value='', description='Top-level namespace'
54  )
55 
56  declare_use_sim_time_cmd = DeclareLaunchArgument(
57  'use_sim_time',
58  default_value='True',
59  description='Use simulation (Gazebo) clock if true',
60  )
61 
62  declare_params_file_cmd = DeclareLaunchArgument(
63  'params_file',
64  default_value=os.path.join(
65  package_dir, 'params', 'collision_monitor_params.yaml'
66  ),
67  description='Full path to the ROS2 parameters file to use for all launched nodes',
68  )
69 
70  declare_use_composition_cmd = DeclareLaunchArgument(
71  'use_composition',
72  default_value='True',
73  description='Use composed bringup if True',
74  )
75 
76  declare_container_name_cmd = DeclareLaunchArgument(
77  'container_name',
78  default_value='nav2_container',
79  description='the name of conatiner that nodes will load in if use composition',
80  )
81 
82  configured_params = ParameterFile(
83  RewrittenYaml(
84  source_file=params_file,
85  root_key=namespace,
86  param_rewrites={},
87  convert_types=True,
88  ),
89  allow_substs=True,
90  )
91 
92  # Declare node launching commands
93  load_nodes = GroupAction(
94  condition=IfCondition(PythonExpression(['not ', use_composition])),
95  actions=[
96  SetParameter('use_sim_time', use_sim_time),
97  PushROSNamespace(
98  condition=IfCondition(
99  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
100  ),
101  namespace=namespace,
102  ),
103  Node(
104  package='nav2_lifecycle_manager',
105  executable='lifecycle_manager',
106  name='lifecycle_manager_collision_monitor',
107  output='screen',
108  emulate_tty=True, # https://github.com/ros2/launch/issues/188
109  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
110  remappings=remappings,
111  ),
112  Node(
113  package='nav2_collision_monitor',
114  executable='collision_monitor',
115  output='screen',
116  emulate_tty=True, # https://github.com/ros2/launch/issues/188
117  parameters=[configured_params],
118  remappings=remappings,
119  ),
120  ],
121  )
122 
123  load_composable_nodes = GroupAction(
124  condition=IfCondition(use_composition),
125  actions=[
126  SetParameter('use_sim_time', use_sim_time),
127  PushROSNamespace(
128  condition=IfCondition(
129  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
130  ),
131  namespace=namespace,
132  ),
133  LoadComposableNodes(
134  target_container=container_name_full,
135  composable_node_descriptions=[
136  ComposableNode(
137  package='nav2_lifecycle_manager',
138  plugin='nav2_lifecycle_manager::LifecycleManager',
139  name='lifecycle_manager_collision_monitor',
140  parameters=[
141  {'autostart': autostart},
142  {'node_names': lifecycle_nodes},
143  ],
144  remappings=remappings,
145  ),
146  ComposableNode(
147  package='nav2_collision_monitor',
148  plugin='nav2_collision_monitor::CollisionMonitor',
149  name='collision_monitor',
150  parameters=[configured_params],
151  remappings=remappings,
152  ),
153  ],
154  ),
155  ],
156  )
157 
158  ld = LaunchDescription()
159 
160  # Launch arguments
161  ld.add_action(declare_namespace_cmd)
162  ld.add_action(declare_use_sim_time_cmd)
163  ld.add_action(declare_params_file_cmd)
164  ld.add_action(declare_use_composition_cmd)
165  ld.add_action(declare_container_name_cmd)
166 
167  # Node launching commands
168  ld.add_action(load_nodes)
169  ld.add_action(load_composable_nodes)
170 
171  return ld