19 from ament_index_python.packages
import get_package_share_directory
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
33 def generate_launch_description():
35 package_dir = get_package_share_directory(
'nav2_collision_monitor')
38 lifecycle_nodes = [
'collision_detector']
40 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
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)
52 declare_namespace_cmd = DeclareLaunchArgument(
53 'namespace', default_value=
'', description=
'Top-level namespace'
56 declare_use_sim_time_cmd = DeclareLaunchArgument(
59 description=
'Use simulation (Gazebo) clock if true',
62 declare_params_file_cmd = DeclareLaunchArgument(
64 default_value=os.path.join(
65 package_dir,
'params',
'collision_monitor_params.yaml'
67 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
70 declare_use_composition_cmd = DeclareLaunchArgument(
73 description=
'Use composed bringup if True',
76 declare_container_name_cmd = DeclareLaunchArgument(
78 default_value=
'nav2_container',
79 description=
'the name of conatiner that nodes will load in if use composition',
82 configured_params = RewrittenYaml(
83 source_file=params_file,
90 load_nodes = GroupAction(
91 condition=IfCondition(PythonExpression([
'not ', use_composition])),
93 SetParameter(
'use_sim_time', use_sim_time),
95 condition=IfCondition(
96 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
101 package=
'nav2_lifecycle_manager',
102 executable=
'lifecycle_manager',
103 name=
'lifecycle_manager_collision_detector',
106 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
107 remappings=remappings,
110 package=
'nav2_collision_monitor',
111 executable=
'collision_detector',
114 parameters=[configured_params],
115 remappings=remappings,
120 load_composable_nodes = GroupAction(
121 condition=IfCondition(use_composition),
123 SetParameter(
'use_sim_time', use_sim_time),
125 condition=IfCondition(
126 NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')
131 target_container=container_name_full,
132 composable_node_descriptions=[
134 package=
'nav2_lifecycle_manager',
135 plugin=
'nav2_lifecycle_manager::LifecycleManager',
136 name=
'lifecycle_manager_collision_detector',
138 {
'autostart': autostart},
139 {
'node_names': lifecycle_nodes},
141 remappings=remappings,
144 package=
'nav2_collision_monitor',
145 plugin=
'nav2_collision_monitor::CollisionDetector',
146 name=
'collision_detector',
147 parameters=[configured_params],
148 remappings=remappings,
155 ld = LaunchDescription()
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)
165 ld.add_action(load_nodes)
166 ld.add_action(load_composable_nodes)