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