19 from ament_index_python.packages
import get_package_share_directory
21 from launch
import LaunchDescription
22 from launch.actions
import DeclareLaunchArgument
23 from launch.substitutions
import LaunchConfiguration
24 from launch_ros.actions
import Node
25 from launch_ros.descriptions
import ParameterFile
29 def generate_launch_description():
31 package_dir = get_package_share_directory(
'nav2_collision_monitor')
34 lifecycle_nodes = [
'collision_monitor']
39 namespace = LaunchConfiguration(
'namespace')
40 use_sim_time = LaunchConfiguration(
'use_sim_time')
41 params_file = LaunchConfiguration(
'params_file')
44 declare_namespace_cmd = DeclareLaunchArgument(
47 description=
'Top-level namespace')
49 declare_use_sim_time_cmd = DeclareLaunchArgument(
52 description=
'Use simulation (Gazebo) clock if true')
54 declare_params_file_cmd = DeclareLaunchArgument(
56 default_value=os.path.join(package_dir,
'params',
'collision_monitor_params.yaml'),
57 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
60 param_substitutions = {
61 'use_sim_time': use_sim_time}
63 configured_params = ParameterFile(
65 source_file=params_file,
67 param_rewrites=param_substitutions,
72 start_lifecycle_manager_cmd = Node(
73 package=
'nav2_lifecycle_manager',
74 executable=
'lifecycle_manager',
75 name=
'lifecycle_manager',
78 parameters=[{
'use_sim_time': use_sim_time},
79 {
'autostart': autostart},
80 {
'node_names': lifecycle_nodes}])
82 start_collision_monitor_cmd = Node(
83 package=
'nav2_collision_monitor',
84 executable=
'collision_monitor',
87 parameters=[configured_params])
89 ld = LaunchDescription()
92 ld.add_action(declare_namespace_cmd)
93 ld.add_action(declare_use_sim_time_cmd)
94 ld.add_action(declare_params_file_cmd)
97 ld.add_action(start_lifecycle_manager_cmd)
98 ld.add_action(start_collision_monitor_cmd)