diff --git a/nav2_bringup/launch/bringup_launch.py b/nav2_bringup/launch/bringup_launch.py index 07e2f3d0ea..8acb5fe209 100644 --- a/nav2_bringup/launch/bringup_launch.py +++ b/nav2_bringup/launch/bringup_launch.py @@ -21,7 +21,7 @@ from launch.conditions import IfCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration, PythonExpression -from launch_ros.actions import Node, PushROSNamespace +from launch_ros.actions import Node from launch_ros.descriptions import ParameterFile from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml @@ -150,10 +150,10 @@ def generate_launch_description() -> LaunchDescription: # Specify the actions bringup_cmd_group = GroupAction( [ - PushROSNamespace(namespace), Node( condition=IfCondition(use_composition), name='nav2_container', + namespace=namespace, package='rclcpp_components', executable='component_container_isolated', parameters=[configured_params, {'autostart': autostart}], diff --git a/nav2_bringup/launch/keepout_zone_launch.py b/nav2_bringup/launch/keepout_zone_launch.py index 23e10bfbe1..2883ac59cf 100644 --- a/nav2_bringup/launch/keepout_zone_launch.py +++ b/nav2_bringup/launch/keepout_zone_launch.py @@ -19,7 +19,7 @@ from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression -from launch_ros.actions import LoadComposableNodes, Node, SetParameter +from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter from launch_ros.descriptions import ComposableNode, ParameterFile from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml @@ -116,6 +116,7 @@ def generate_launch_description() -> LaunchDescription: load_nodes = GroupAction( condition=IfCondition(PythonExpression(['not ', use_composition])), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), Node( condition=IfCondition(use_keepout_zones), @@ -159,6 +160,7 @@ def generate_launch_description() -> LaunchDescription: load_composable_nodes = GroupAction( condition=IfCondition(use_composition), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), LoadComposableNodes( target_container=container_name_full, diff --git a/nav2_bringup/launch/localization_launch.py b/nav2_bringup/launch/localization_launch.py index 3e6c1b7de2..ca440d2f82 100644 --- a/nav2_bringup/launch/localization_launch.py +++ b/nav2_bringup/launch/localization_launch.py @@ -20,7 +20,7 @@ from launch.conditions import IfCondition from launch.substitutions import (EqualsSubstitution, LaunchConfiguration, NotEqualsSubstitution, PythonExpression) -from launch_ros.actions import LoadComposableNodes, Node, SetParameter +from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter from launch_ros.descriptions import ComposableNode, ParameterFile from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml @@ -110,6 +110,7 @@ def generate_launch_description() -> LaunchDescription: load_nodes = GroupAction( condition=IfCondition(PythonExpression(['not ', use_composition])), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), Node( condition=IfCondition( @@ -168,6 +169,7 @@ def generate_launch_description() -> LaunchDescription: load_composable_nodes = GroupAction( condition=IfCondition(use_composition), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), LoadComposableNodes( target_container=container_name_full, diff --git a/nav2_bringup/launch/navigation_launch.py b/nav2_bringup/launch/navigation_launch.py index f6c4160a10..2aa605617e 100644 --- a/nav2_bringup/launch/navigation_launch.py +++ b/nav2_bringup/launch/navigation_launch.py @@ -19,7 +19,7 @@ from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression -from launch_ros.actions import LoadComposableNodes, Node, SetParameter +from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter from launch_ros.descriptions import ComposableNode, ParameterFile from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml @@ -65,6 +65,14 @@ def generate_launch_description() -> LaunchDescription: 'SPEED_ZONE_ENABLED': use_speed_zones, } + # RewrittenYaml: Adds namespace to the parameters file as a root key + # Note: Make sure that all frames are correctly namespaced in the parameters file + # Do not add namespace to topics in the parameters file, as they will be remapped + # by the root key only if they are not prefixed with a forward slash. + # e.g. 'map' will be remapped to '//map', but '/map' will not be remapped. + # IMPORTANT: to make your yaml file dynamic you can refer to humble branch under + # nav2_bringup/launch/bringup_launch.py to see how the parameters file is configured + # using ReplaceString configured_params = ParameterFile( RewrittenYaml( source_file=params_file, @@ -143,6 +151,7 @@ def generate_launch_description() -> LaunchDescription: condition=IfCondition(PythonExpression(['not ', use_composition])), actions=[ SetParameter('use_sim_time', use_sim_time), + PushROSNamespace(namespace=namespace), Node( package='nav2_controller', executable='controller_server', @@ -267,6 +276,7 @@ def generate_launch_description() -> LaunchDescription: condition=IfCondition(use_composition), actions=[ SetParameter('use_sim_time', use_sim_time), + PushROSNamespace(namespace=namespace), LoadComposableNodes( target_container=container_name_full, composable_node_descriptions=[ diff --git a/nav2_bringup/launch/slam_launch.py b/nav2_bringup/launch/slam_launch.py index 884e7ea7ff..f60a1322bb 100644 --- a/nav2_bringup/launch/slam_launch.py +++ b/nav2_bringup/launch/slam_launch.py @@ -20,7 +20,7 @@ from launch.conditions import IfCondition, UnlessCondition from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration -from launch_ros.actions import Node, SetParameter, SetRemap +from launch_ros.actions import Node, PushROSNamespace, SetParameter, SetRemap from launch_ros.descriptions import ParameterFile from nav2_common.launch import HasNodeParams, LaunchConfigAsBool, RewrittenYaml @@ -89,6 +89,7 @@ def generate_launch_description() -> LaunchDescription: # Nodes launching commands start_map_server = GroupAction( actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), Node( package='nav2_map_server', @@ -120,6 +121,8 @@ def generate_launch_description() -> LaunchDescription: start_slam_toolbox_cmd = GroupAction( actions=[ + PushROSNamespace(namespace), + # Remapping required to have a slam session subscribe & publish in optional namespaces SetRemap(src='/scan', dst='scan'), SetRemap(src='/tf', dst='tf'), diff --git a/nav2_bringup/launch/speed_zone_launch.py b/nav2_bringup/launch/speed_zone_launch.py index 4698006848..b612ad0dfd 100644 --- a/nav2_bringup/launch/speed_zone_launch.py +++ b/nav2_bringup/launch/speed_zone_launch.py @@ -19,7 +19,7 @@ from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration, PythonExpression -from launch_ros.actions import LoadComposableNodes, Node, SetParameter +from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter from launch_ros.descriptions import ComposableNode, ParameterFile from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml @@ -116,6 +116,7 @@ def generate_launch_description() -> LaunchDescription: load_nodes = GroupAction( condition=IfCondition(PythonExpression(['not ', use_composition])), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), Node( condition=IfCondition(use_speed_zones), @@ -159,6 +160,7 @@ def generate_launch_description() -> LaunchDescription: load_composable_nodes = GroupAction( condition=IfCondition(use_composition), actions=[ + PushROSNamespace(namespace), SetParameter('use_sim_time', use_sim_time), LoadComposableNodes( target_container=container_name_full,