Nav2 Navigation Stack - rolling  main
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 from launch import LaunchDescription
21 from launch.actions import DeclareLaunchArgument, GroupAction
22 from launch.conditions import IfCondition
23 from launch.substitutions import LaunchConfiguration, NotEqualsSubstitution, PythonExpression
24 from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter
25 from launch_ros.descriptions import ComposableNode, ParameterFile
26 from nav2_common.launch import RewrittenYaml
27 
28 
29 def generate_launch_description() -> LaunchDescription:
30  # Environment
31  package_dir = get_package_share_directory('nav2_collision_monitor')
32 
33  # Constant parameters
34  lifecycle_nodes = ['collision_monitor']
35  autostart = True
36  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
37 
38  # Launch arguments
39  # 1. Create the launch configuration variables
40  namespace = LaunchConfiguration('namespace')
41  use_sim_time = LaunchConfiguration('use_sim_time')
42  params_file = LaunchConfiguration('params_file')
43  use_composition = LaunchConfiguration('use_composition')
44  container_name = LaunchConfiguration('container_name')
45  container_name_full = (namespace, '/', container_name)
46 
47  # 2. Declare the launch arguments
48  declare_namespace_cmd = DeclareLaunchArgument(
49  'namespace', default_value='', description='Top-level namespace'
50  )
51 
52  declare_use_sim_time_cmd = DeclareLaunchArgument(
53  'use_sim_time',
54  default_value='True',
55  description='Use simulation (Gazebo) clock if true',
56  )
57 
58  declare_params_file_cmd = DeclareLaunchArgument(
59  'params_file',
60  default_value=os.path.join(
61  package_dir, 'params', 'collision_monitor_params.yaml'
62  ),
63  description='Full path to the ROS2 parameters file to use for all launched nodes',
64  )
65 
66  declare_use_composition_cmd = DeclareLaunchArgument(
67  'use_composition',
68  default_value='True',
69  description='Use composed bringup if True',
70  )
71 
72  declare_container_name_cmd = DeclareLaunchArgument(
73  'container_name',
74  default_value='nav2_container',
75  description='the name of container that nodes will load in if use composition',
76  )
77 
78  configured_params = ParameterFile(
79  RewrittenYaml(
80  source_file=params_file,
81  root_key=namespace,
82  param_rewrites={},
83  convert_types=True,
84  ),
85  allow_substs=True,
86  )
87 
88  # Declare node launching commands
89  load_nodes = GroupAction(
90  condition=IfCondition(PythonExpression(['not ', use_composition])),
91  actions=[
92  SetParameter('use_sim_time', use_sim_time),
93  PushROSNamespace(
94  condition=IfCondition(
95  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
96  ),
97  namespace=namespace,
98  ),
99  Node(
100  package='nav2_lifecycle_manager',
101  executable='lifecycle_manager',
102  name='lifecycle_manager_collision_monitor',
103  output='screen',
104  emulate_tty=True, # https://github.com/ros2/launch/issues/188
105  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
106  remappings=remappings,
107  ),
108  Node(
109  package='nav2_collision_monitor',
110  executable='collision_monitor',
111  output='screen',
112  emulate_tty=True, # https://github.com/ros2/launch/issues/188
113  parameters=[configured_params],
114  remappings=remappings,
115  ),
116  ],
117  )
118 
119  load_composable_nodes = GroupAction(
120  condition=IfCondition(use_composition),
121  actions=[
122  SetParameter('use_sim_time', use_sim_time),
123  PushROSNamespace(
124  condition=IfCondition(
125  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
126  ),
127  namespace=namespace,
128  ),
129  LoadComposableNodes(
130  target_container=container_name_full,
131  composable_node_descriptions=[
132  ComposableNode(
133  package='nav2_lifecycle_manager',
134  plugin='nav2_lifecycle_manager::LifecycleManager',
135  name='lifecycle_manager_collision_monitor',
136  parameters=[
137  {'autostart': autostart},
138  {'node_names': lifecycle_nodes},
139  ],
140  remappings=remappings,
141  ),
142  ComposableNode(
143  package='nav2_collision_monitor',
144  plugin='nav2_collision_monitor::CollisionMonitor',
145  name='collision_monitor',
146  parameters=[configured_params],
147  remappings=remappings,
148  ),
149  ],
150  ),
151  ],
152  )
153 
154  ld = LaunchDescription()
155 
156  # Launch arguments
157  ld.add_action(declare_namespace_cmd)
158  ld.add_action(declare_use_sim_time_cmd)
159  ld.add_action(declare_params_file_cmd)
160  ld.add_action(declare_use_composition_cmd)
161  ld.add_action(declare_container_name_cmd)
162 
163  # Node launching commands
164  ld.add_action(load_nodes)
165  ld.add_action(load_composable_nodes)
166 
167  return ld