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
29 def generate_launch_description() -> LaunchDescription:
31 package_dir = get_package_share_directory(
'nav2_collision_monitor')
34 lifecycle_nodes = [
'collision_detector']
36 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
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)
48 declare_namespace_cmd = DeclareLaunchArgument(
49 'namespace', default_value=
'', description=
'Top-level namespace'
52 declare_use_sim_time_cmd = DeclareLaunchArgument(
55 description=
'Use simulation (Gazebo) clock if true',
58 declare_params_file_cmd = DeclareLaunchArgument(
60 default_value=os.path.join(
61 package_dir,
'params',
'collision_monitor_params.yaml'
63 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
66 declare_use_composition_cmd = DeclareLaunchArgument(
69 description=
'Use composed bringup if True',
72 declare_container_name_cmd = DeclareLaunchArgument(
74 default_value=
'nav2_container',
75 description=
'the name of container that nodes will load in if use composition',
78 configured_params = RewrittenYaml(
79 source_file=params_file,
86 load_nodes = GroupAction(
87 condition=IfCondition(PythonExpression([
'not ', use_composition])),
89 SetParameter(
'use_sim_time', use_sim_time),
91 condition=IfCondition(
92 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
97 package=
'nav2_lifecycle_manager',
98 executable=
'lifecycle_manager',
99 name=
'lifecycle_manager_collision_detector',
102 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
103 remappings=remappings,
106 package=
'nav2_collision_monitor',
107 executable=
'collision_detector',
110 parameters=[configured_params],
111 remappings=remappings,
116 load_composable_nodes = GroupAction(
117 condition=IfCondition(use_composition),
119 SetParameter(
'use_sim_time', use_sim_time),
121 condition=IfCondition(
122 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
127 target_container=container_name_full,
128 composable_node_descriptions=[
130 package=
'nav2_lifecycle_manager',
131 plugin=
'nav2_lifecycle_manager::LifecycleManager',
132 name=
'lifecycle_manager_collision_detector',
134 {
'autostart': autostart},
135 {
'node_names': lifecycle_nodes},
137 remappings=remappings,
140 package=
'nav2_collision_monitor',
141 plugin=
'nav2_collision_monitor::CollisionDetector',
142 name=
'collision_detector',
143 parameters=[configured_params],
144 remappings=remappings,
151 ld = LaunchDescription()
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)
161 ld.add_action(load_nodes)
162 ld.add_action(load_composable_nodes)