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
29 def generate_launch_description() -> LaunchDescription:
31 package_dir = get_package_share_directory(
'nav2_collision_monitor')
34 lifecycle_nodes = [
'collision_monitor']
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 = ParameterFile(
80 source_file=params_file,
89 load_nodes = GroupAction(
90 condition=IfCondition(PythonExpression([
'not ', use_composition])),
92 SetParameter(
'use_sim_time', use_sim_time),
94 condition=IfCondition(
95 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
100 package=
'nav2_lifecycle_manager',
101 executable=
'lifecycle_manager',
102 name=
'lifecycle_manager_collision_monitor',
105 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
106 remappings=remappings,
109 package=
'nav2_collision_monitor',
110 executable=
'collision_monitor',
113 parameters=[configured_params],
114 remappings=remappings,
119 load_composable_nodes = GroupAction(
120 condition=IfCondition(use_composition),
122 SetParameter(
'use_sim_time', use_sim_time),
124 condition=IfCondition(
125 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
130 target_container=container_name_full,
131 composable_node_descriptions=[
133 package=
'nav2_lifecycle_manager',
134 plugin=
'nav2_lifecycle_manager::LifecycleManager',
135 name=
'lifecycle_manager_collision_monitor',
137 {
'autostart': autostart},
138 {
'node_names': lifecycle_nodes},
140 remappings=remappings,
143 package=
'nav2_collision_monitor',
144 plugin=
'nav2_collision_monitor::CollisionMonitor',
145 name=
'collision_monitor',
146 parameters=[configured_params],
147 remappings=remappings,
154 ld = LaunchDescription()
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)
164 ld.add_action(load_nodes)
165 ld.add_action(load_composable_nodes)