Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
collision_detector_node.launch.py
1 #!/usr/bin/env python3
2 
3 # Copyright (c) 2023 Pixel Robotics GmbH
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
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_detector']
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 = RewrittenYaml(
83  source_file=params_file,
84  root_key=namespace,
85  param_rewrites={},
86  convert_types=True,
87  )
88 
89  # Declare node launching commands
90  load_nodes = GroupAction(
91  condition=IfCondition(PythonExpression(['not ', use_composition])),
92  actions=[
93  SetParameter('use_sim_time', use_sim_time),
94  PushROSNamespace(
95  condition=IfCondition(
96  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
97  ),
98  namespace=namespace,
99  ),
100  Node(
101  package='nav2_lifecycle_manager',
102  executable='lifecycle_manager',
103  name='lifecycle_manager_collision_detector',
104  output='screen',
105  emulate_tty=True, # https://github.com/ros2/launch/issues/188
106  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
107  remappings=remappings,
108  ),
109  Node(
110  package='nav2_collision_monitor',
111  executable='collision_detector',
112  output='screen',
113  emulate_tty=True, # https://github.com/ros2/launch/issues/188
114  parameters=[configured_params],
115  remappings=remappings,
116  ),
117  ],
118  )
119 
120  load_composable_nodes = GroupAction(
121  condition=IfCondition(use_composition),
122  actions=[
123  SetParameter('use_sim_time', use_sim_time),
124  PushROSNamespace(
125  condition=IfCondition(
126  NotEqualsSubstitution(LaunchConfiguration('namespace'), '')
127  ),
128  namespace=namespace,
129  ),
130  LoadComposableNodes(
131  target_container=container_name_full,
132  composable_node_descriptions=[
133  ComposableNode(
134  package='nav2_lifecycle_manager',
135  plugin='nav2_lifecycle_manager::LifecycleManager',
136  name='lifecycle_manager_collision_detector',
137  parameters=[
138  {'autostart': autostart},
139  {'node_names': lifecycle_nodes},
140  ],
141  remappings=remappings,
142  ),
143  ComposableNode(
144  package='nav2_collision_monitor',
145  plugin='nav2_collision_monitor::CollisionDetector',
146  name='collision_detector',
147  parameters=[configured_params],
148  remappings=remappings,
149  ),
150  ],
151  ),
152  ],
153  )
154 
155  ld = LaunchDescription()
156 
157  # Launch arguments
158  ld.add_action(declare_namespace_cmd)
159  ld.add_action(declare_use_sim_time_cmd)
160  ld.add_action(declare_params_file_cmd)
161  ld.add_action(declare_use_composition_cmd)
162  ld.add_action(declare_container_name_cmd)
163 
164  # Node launching commands
165  ld.add_action(load_nodes)
166  ld.add_action(load_composable_nodes)
167 
168  return ld