diff --git a/nav2_bringup/launch/bringup_launch.py b/nav2_bringup/launch/bringup_launch.py index eee19f6b362..a5f6b9c3dc4 100644 --- a/nav2_bringup/launch/bringup_launch.py +++ b/nav2_bringup/launch/bringup_launch.py @@ -29,7 +29,7 @@ from launch_ros.actions import Node from launch_ros.actions import PushROSNamespace from launch_ros.descriptions import ParameterFile -from nav2_common.launch import ReplaceString, RewrittenYaml +from nav2_common.launch import RewrittenYaml def generate_launch_description(): @@ -39,7 +39,6 @@ def generate_launch_description(): # Create the launch configuration variables namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') slam = LaunchConfiguration('slam') map_yaml_file = LaunchConfiguration('map') use_sim_time = LaunchConfiguration('use_sim_time') @@ -58,16 +57,6 @@ def generate_launch_description(): # https://github.com/ros2/launch_ros/issues/56 remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')] - # Only it applys when `use_namespace` is True. - # '' keyword shall be replaced by 'namespace' launch argument - # in config file 'nav2_multirobot_params.yaml' as a default & example. - # User defined config file should contain '' keyword for the replacements. - params_file = ReplaceString( - source_file=params_file, - replacements={'': ('/', namespace)}, - condition=IfCondition(use_namespace), - ) - configured_params = ParameterFile( RewrittenYaml( source_file=params_file, @@ -86,12 +75,6 @@ def generate_launch_description(): 'namespace', default_value='', description='Top-level namespace' ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_slam_cmd = DeclareLaunchArgument( 'slam', default_value='False', description='Whether run a SLAM' ) @@ -142,7 +125,7 @@ def generate_launch_description(): # Specify the actions bringup_cmd_group = GroupAction( [ - PushROSNamespace(condition=IfCondition(use_namespace), namespace=namespace), + PushROSNamespace(namespace), Node( condition=IfCondition(use_composition), name='nav2_container', @@ -207,7 +190,6 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_slam_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_use_sim_time_cmd) diff --git a/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py b/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py index bd001412d58..6bd6bdddcab 100644 --- a/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py +++ b/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py @@ -80,7 +80,7 @@ def generate_launch_description(): declare_params_file_cmd = DeclareLaunchArgument( 'params_file', default_value=os.path.join( - bringup_dir, 'params', 'nav2_multirobot_params_all.yaml' + bringup_dir, 'params', 'nav2_params.yaml' ), description='Full path to the ROS2 parameters file to use for all launched nodes', ) @@ -93,7 +93,7 @@ def generate_launch_description(): declare_rviz_config_file_cmd = DeclareLaunchArgument( 'rviz_config', - default_value=os.path.join(bringup_dir, 'rviz', 'nav2_namespaced_view.rviz'), + default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'), description='Full path to the RVIZ config file to use.', ) @@ -144,7 +144,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': TextSubstitution(text=robot_name), - 'use_namespace': 'True', 'rviz_config': rviz_config_file, }.items(), ), @@ -154,7 +153,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': robot_name, - 'use_namespace': 'True', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': params_file, diff --git a/nav2_bringup/launch/rviz_launch.py b/nav2_bringup/launch/rviz_launch.py index 8728581df12..425dac4edee 100644 --- a/nav2_bringup/launch/rviz_launch.py +++ b/nav2_bringup/launch/rviz_launch.py @@ -18,12 +18,10 @@ from launch import LaunchDescription from launch.actions import DeclareLaunchArgument, EmitEvent, RegisterEventHandler -from launch.conditions import IfCondition, UnlessCondition from launch.event_handlers import OnProcessExit from launch.events import Shutdown from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -from nav2_common.launch import ReplaceString def generate_launch_description(): @@ -32,7 +30,6 @@ def generate_launch_description(): # Create the launch configuration variables namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') rviz_config_file = LaunchConfiguration('rviz_config') use_sim_time = LaunchConfiguration('use_sim_time') @@ -46,12 +43,6 @@ def generate_launch_description(): ), ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_rviz_config_file_cmd = DeclareLaunchArgument( 'rviz_config', default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'), @@ -65,68 +56,37 @@ def generate_launch_description(): # Launch rviz start_rviz_cmd = Node( - condition=UnlessCondition(use_namespace), package='rviz2', executable='rviz2', + namespace=namespace, arguments=['-d', rviz_config_file], output='screen', parameters=[{'use_sim_time': use_sim_time}], - ) - - namespaced_rviz_config_file = ReplaceString( - source_file=rviz_config_file, - replacements={'': ('/', namespace)}, - ) - - start_namespaced_rviz_cmd = Node( - condition=IfCondition(use_namespace), - package='rviz2', - executable='rviz2', - namespace=namespace, - arguments=['-d', namespaced_rviz_config_file], - parameters=[{'use_sim_time': use_sim_time}], - output='screen', remappings=[ - ('/map', 'map'), ('/tf', 'tf'), ('/tf_static', 'tf_static'), - ('/goal_pose', 'goal_pose'), - ('/clicked_point', 'clicked_point'), - ('/initialpose', 'initialpose'), ], ) exit_event_handler = RegisterEventHandler( - condition=UnlessCondition(use_namespace), event_handler=OnProcessExit( target_action=start_rviz_cmd, on_exit=EmitEvent(event=Shutdown(reason='rviz exited')), ), ) - exit_event_handler_namespaced = RegisterEventHandler( - condition=IfCondition(use_namespace), - event_handler=OnProcessExit( - target_action=start_namespaced_rviz_cmd, - on_exit=EmitEvent(event=Shutdown(reason='rviz exited')), - ), - ) - # Create the launch description and populate ld = LaunchDescription() # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_rviz_config_file_cmd) ld.add_action(declare_use_sim_time_cmd) # Add any conditioned actions ld.add_action(start_rviz_cmd) - ld.add_action(start_namespaced_rviz_cmd) # Add other nodes and processes we need ld.add_action(exit_event_handler) - ld.add_action(exit_event_handler_namespaced) return ld diff --git a/nav2_bringup/launch/tb3_loopback_simulation.launch.py b/nav2_bringup/launch/tb3_loopback_simulation.launch.py index 9e598e854cf..3553852597c 100644 --- a/nav2_bringup/launch/tb3_loopback_simulation.launch.py +++ b/nav2_bringup/launch/tb3_loopback_simulation.launch.py @@ -42,7 +42,6 @@ def generate_launch_description(): # Create the launch configuration variables namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') map_yaml_file = LaunchConfiguration('map') params_file = LaunchConfiguration('params_file') autostart = LaunchConfiguration('autostart') @@ -61,12 +60,6 @@ def generate_launch_description(): 'namespace', default_value='', description='Top-level namespace' ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_map_yaml_cmd = DeclareLaunchArgument( 'map', default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'), @@ -134,7 +127,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'use_sim_time': 'True', 'rviz_config': rviz_config_file, }.items(), @@ -144,7 +136,6 @@ def generate_launch_description(): PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': params_file, @@ -203,7 +194,6 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_params_file_cmd) ld.add_action(declare_autostart_cmd) diff --git a/nav2_bringup/launch/tb3_simulation_launch.py b/nav2_bringup/launch/tb3_simulation_launch.py index db1964f955e..532d8ea24fa 100644 --- a/nav2_bringup/launch/tb3_simulation_launch.py +++ b/nav2_bringup/launch/tb3_simulation_launch.py @@ -44,7 +44,6 @@ def generate_launch_description(): # Create the launch configuration variables slam = LaunchConfiguration('slam') namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') map_yaml_file = LaunchConfiguration('map') use_sim_time = LaunchConfiguration('use_sim_time') params_file = LaunchConfiguration('params_file') @@ -77,12 +76,6 @@ def generate_launch_description(): 'namespace', default_value='', description='Top-level namespace' ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_slam_cmd = DeclareLaunchArgument( 'slam', default_value='False', description='Whether run a SLAM' ) @@ -186,7 +179,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'use_sim_time': use_sim_time, 'rviz_config': rviz_config_file, }.items(), @@ -196,7 +188,6 @@ def generate_launch_description(): PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'slam': slam, 'map': map_yaml_file, 'use_sim_time': use_sim_time, @@ -255,7 +246,6 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_slam_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_use_sim_time_cmd) diff --git a/nav2_bringup/launch/tb4_loopback_simulation.launch.py b/nav2_bringup/launch/tb4_loopback_simulation.launch.py index 0ad911ddc74..5373efbfab3 100644 --- a/nav2_bringup/launch/tb4_loopback_simulation.launch.py +++ b/nav2_bringup/launch/tb4_loopback_simulation.launch.py @@ -42,7 +42,6 @@ def generate_launch_description(): # Create the launch configuration variables namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') map_yaml_file = LaunchConfiguration('map') params_file = LaunchConfiguration('params_file') autostart = LaunchConfiguration('autostart') @@ -61,12 +60,6 @@ def generate_launch_description(): 'namespace', default_value='', description='Top-level namespace' ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_map_yaml_cmd = DeclareLaunchArgument( 'map', default_value=os.path.join(bringup_dir, 'maps', 'depot.yaml'), # Try warehouse.yaml! @@ -132,7 +125,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'use_sim_time': 'True', 'rviz_config': rviz_config_file, }.items(), @@ -142,7 +134,6 @@ def generate_launch_description(): PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': params_file, @@ -210,7 +201,6 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_params_file_cmd) ld.add_action(declare_autostart_cmd) diff --git a/nav2_bringup/launch/tb4_simulation_launch.py b/nav2_bringup/launch/tb4_simulation_launch.py index 463f0c17f34..0765ceb4341 100644 --- a/nav2_bringup/launch/tb4_simulation_launch.py +++ b/nav2_bringup/launch/tb4_simulation_launch.py @@ -48,7 +48,6 @@ def generate_launch_description(): # Create the launch configuration variables slam = LaunchConfiguration('slam') namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') map_yaml_file = LaunchConfiguration('map') use_sim_time = LaunchConfiguration('use_sim_time') params_file = LaunchConfiguration('params_file') @@ -81,12 +80,6 @@ def generate_launch_description(): 'namespace', default_value='', description='Top-level namespace' ) - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack', - ) - declare_slam_cmd = DeclareLaunchArgument( 'slam', default_value='False', description='Whether run a SLAM' ) @@ -187,7 +180,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'use_sim_time': use_sim_time, 'rviz_config': rviz_config_file, }.items(), @@ -197,7 +189,6 @@ def generate_launch_description(): PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')), launch_arguments={ 'namespace': namespace, - 'use_namespace': use_namespace, 'slam': slam, 'map': map_yaml_file, 'use_sim_time': use_sim_time, @@ -261,7 +252,6 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) ld.add_action(declare_slam_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_use_sim_time_cmd) diff --git a/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py b/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py index ae5551d179a..862a0083799 100644 --- a/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py +++ b/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py @@ -99,7 +99,7 @@ def generate_launch_description(): declare_robot1_params_file_cmd = DeclareLaunchArgument( 'robot1_params_file', default_value=os.path.join( - bringup_dir, 'params', 'nav2_multirobot_params_1.yaml' + bringup_dir, 'params', 'nav2_params.yaml' ), description='Full path to the ROS2 parameters file to use for robot1 launched nodes', ) @@ -107,7 +107,7 @@ def generate_launch_description(): declare_robot2_params_file_cmd = DeclareLaunchArgument( 'robot2_params_file', default_value=os.path.join( - bringup_dir, 'params', 'nav2_multirobot_params_2.yaml' + bringup_dir, 'params', 'nav2_params.yaml' ), description='Full path to the ROS2 parameters file to use for robot2 launched nodes', ) @@ -120,7 +120,7 @@ def generate_launch_description(): declare_rviz_config_file_cmd = DeclareLaunchArgument( 'rviz_config', - default_value=os.path.join(bringup_dir, 'rviz', 'nav2_namespaced_view.rviz'), + default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'), description='Full path to the RVIZ config file to use.', ) @@ -162,7 +162,6 @@ def generate_launch_description(): condition=IfCondition(use_rviz), launch_arguments={ 'namespace': TextSubstitution(text=robot['name']), - 'use_namespace': 'True', 'rviz_config': rviz_config_file, }.items(), ), @@ -172,7 +171,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': robot['name'], - 'use_namespace': 'True', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': params_file, diff --git a/nav2_bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/params/nav2_multirobot_params_1.yaml deleted file mode 100644 index 319ebd41acd..00000000000 --- a/nav2_bringup/params/nav2_multirobot_params_1.yaml +++ /dev/null @@ -1,316 +0,0 @@ -amcl: - ros__parameters: - alpha1: 0.2 - alpha2: 0.2 - alpha3: 0.2 - alpha4: 0.2 - alpha5: 0.2 - base_frame_id: "base_footprint" - beam_skip_distance: 0.5 - beam_skip_error_threshold: 0.9 - beam_skip_threshold: 0.3 - do_beamskip: false - global_frame_id: "map" - lambda_short: 0.1 - laser_likelihood_max_dist: 2.0 - laser_max_range: 100.0 - laser_min_range: -1.0 - laser_model_type: "likelihood_field" - max_beams: 60 - max_particles: 2000 - min_particles: 500 - odom_frame_id: "odom" - pf_err: 0.05 - pf_z: 0.99 - recovery_alpha_fast: 0.0 - recovery_alpha_slow: 0.0 - resample_interval: 1 - robot_model_type: "nav2_amcl::DifferentialMotionModel" - save_pose_rate: 0.5 - sigma_hit: 0.2 - tf_broadcast: true - transform_tolerance: 1.0 - update_min_a: 0.2 - update_min_d: 0.25 - z_hit: 0.5 - z_max: 0.05 - z_rand: 0.5 - z_short: 0.05 - scan_topic: scan - -bt_navigator: - ros__parameters: - global_frame: map - robot_base_frame: base_link - odom_topic: /odom - bt_loop_duration: 10 - default_server_timeout: 20 - wait_for_service_timeout: 1000 - action_server_result_timeout: 900.0 - navigators: ["navigate_to_pose", "navigate_through_poses"] - navigate_to_pose: - plugin: "nav2_bt_navigator::NavigateToPoseNavigator" - navigate_through_poses: - plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" - # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: - # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml - # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml - # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. - - # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings). - # Built-in plugins are added automatically - # plugin_lib_names: [] - - error_code_names: - - compute_path_error_code - - follow_path_error_code - -controller_server: - ros__parameters: - controller_frequency: 20.0 - costmap_update_timeout: 0.30 - min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.5 - min_theta_velocity_threshold: 0.001 - progress_checker_plugins: ["progress_checker"] - goal_checker_plugins: ["goal_checker"] - controller_plugins: ["FollowPath"] - - # Progress checker parameters - progress_checker: - plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 - movement_time_allowance: 10.0 - # Goal checker parameters - goal_checker: - plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.25 - yaw_goal_tolerance: 0.25 - stateful: True - # DWB parameters - FollowPath: - plugin: "dwb_core::DWBLocalPlanner" - debug_trajectory_details: True - min_vel_x: 0.0 - min_vel_y: 0.0 - max_vel_x: 0.26 - max_vel_y: 0.0 - max_vel_theta: 1.0 - min_speed_xy: 0.0 - max_speed_xy: 0.26 - min_speed_theta: 0.0 - acc_lim_x: 2.5 - acc_lim_y: 0.0 - acc_lim_theta: 3.2 - decel_lim_x: -2.5 - decel_lim_y: 0.0 - decel_lim_theta: -3.2 - vx_samples: 20 - vy_samples: 5 - vtheta_samples: 20 - sim_time: 1.7 - linear_granularity: 0.05 - angular_granularity: 0.025 - transform_tolerance: 0.2 - trans_stopped_velocity: 0.25 - short_circuit_trajectory_evaluation: True - stateful: True - critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] - BaseObstacle.scale: 0.02 - PathAlign.scale: 0.0 - GoalAlign.scale: 0.0 - PathDist.scale: 32.0 - GoalDist.scale: 24.0 - RotateToGoal.scale: 32.0 - RotateToGoal.slowing_factor: 5.0 - RotateToGoal.lookahead_time: -1.0 - -local_costmap: - local_costmap: - ros__parameters: - global_frame: odom - rolling_window: true - width: 3 - height: 3 - resolution: 0.05 - robot_radius: 0.22 - plugins: ["voxel_layer", "inflation_layer"] - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - voxel_layer: - plugin: "nav2_costmap_2d::VoxelLayer" - enabled: True - publish_voxel_map: False - origin_z: 0.0 - z_resolution: 0.05 - z_voxels: 16 - max_obstacle_height: 2.0 - mark_threshold: 0 - observation_sources: scan - scan: - topic: /robot1/scan - max_obstacle_height: 2.0 - clearing: True - marking: True - data_type: "LaserScan" - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - map_subscribe_transient_local: True - always_send_full_costmap: True - -global_costmap: - global_costmap: - ros__parameters: - robot_radius: 0.22 - plugins: ["static_layer", "obstacle_layer", "inflation_layer"] - obstacle_layer: - plugin: "nav2_costmap_2d::ObstacleLayer" - enabled: True - observation_sources: scan - scan: - topic: /robot1/scan - max_obstacle_height: 2.0 - clearing: True - marking: True - data_type: "LaserScan" - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - always_send_full_costmap: True - -map_server: - ros__parameters: - yaml_filename: "tb3_sandbox.yaml" - save_map_timeout: 5.0 - -planner_server: - ros__parameters: - planner_plugins: ["GridBased"] - costmap_update_timeout: 1.0 - GridBased: - plugin: "nav2_navfn_planner::NavfnPlanner" - tolerance: 0.5 - use_astar: false - allow_unknown: true - -behavior_server: - ros__parameters: - costmap_topic: local_costmap/costmap_raw - footprint_topic: local_costmap/published_footprint - cycle_frequency: 10.0 - behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] - spin: - plugin: "nav2_behaviors::Spin" - backup: - plugin: "nav2_behaviors::BackUp" - drive_on_heading: - plugin: "nav2_behaviors::DriveOnHeading" - wait: - plugin: "nav2_behaviors::Wait" - global_frame: odom - robot_base_frame: base_link - transform_tolerance: 0.1 - simulate_ahead_time: 2.0 - max_rotational_vel: 1.0 - min_rotational_vel: 0.4 - rotational_acc_lim: 3.2 - -waypoint_follower: - ros__parameters: - loop_rate: 20 - stop_on_failure: false - action_server_result_timeout: 900.0 - waypoint_task_executor_plugin: "wait_at_waypoint" - wait_at_waypoint: - plugin: "nav2_waypoint_follower::WaitAtWaypoint" - enabled: True - waypoint_pause_duration: 200 - -collision_monitor: - ros__parameters: - base_frame_id: "base_footprint" - odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_smoothed" - cmd_vel_out_topic: "cmd_vel" - state_topic: "collision_monitor_state" - transform_tolerance: 0.2 - source_timeout: 1.0 - base_shift_correction: True - stop_pub_timeout: 2.0 - # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types, - # and robot footprint for "approach" action type. - polygons: ["FootprintApproach"] - FootprintApproach: - type: "polygon" - action_type: "approach" - footprint_topic: "local_costmap/published_footprint" - time_before_collision: 2.0 - simulation_time_step: 0.1 - min_points: 6 - visualize: False - enabled: True - observation_sources: ["scan"] - scan: - type: "scan" - topic: "/robot1/scan" - min_height: 0.15 - max_height: 2.0 - enabled: True - -docking_server: - ros__parameters: - controller_frequency: 50.0 - initial_perception_timeout: 5.0 - wait_charge_timeout: 5.0 - dock_approach_timeout: 30.0 - undock_linear_tolerance: 0.05 - undock_angular_tolerance: 0.1 - max_retries: 3 - base_frame: "base_link" - fixed_frame: "odom" - dock_backwards: false - dock_prestaging_tolerance: 0.5 - - # Types of docks - dock_plugins: ['simple_charging_dock'] - simple_charging_dock: - plugin: 'opennav_docking::SimpleChargingDock' - docking_threshold: 0.05 - staging_x_offset: -0.7 - use_external_detection_pose: true - use_battery_status: false # true - use_stall_detection: false # true - - external_detection_timeout: 1.0 - external_detection_translation_x: -0.18 - external_detection_translation_y: 0.0 - external_detection_rotation_roll: -1.57 - external_detection_rotation_pitch: -1.57 - external_detection_rotation_yaw: 0.0 - filter_coef: 0.1 - - # Dock instances - docks: ['home_dock'] # Input your docks here - home_dock: - type: 'simple_charging_dock' - frame: map - pose: [0.0, 0.0, 0.0] - - controller: - k_phi: 3.0 - k_delta: 2.0 - v_linear_min: 0.15 - v_linear_max: 0.15 diff --git a/nav2_bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/params/nav2_multirobot_params_2.yaml deleted file mode 100644 index 86e2b78e5ec..00000000000 --- a/nav2_bringup/params/nav2_multirobot_params_2.yaml +++ /dev/null @@ -1,315 +0,0 @@ -amcl: - ros__parameters: - alpha1: 0.2 - alpha2: 0.2 - alpha3: 0.2 - alpha4: 0.2 - alpha5: 0.2 - base_frame_id: "base_footprint" - beam_skip_distance: 0.5 - beam_skip_error_threshold: 0.9 - beam_skip_threshold: 0.3 - do_beamskip: false - global_frame_id: "map" - lambda_short: 0.1 - laser_likelihood_max_dist: 2.0 - laser_max_range: 100.0 - laser_min_range: -1.0 - laser_model_type: "likelihood_field" - max_beams: 60 - max_particles: 2000 - min_particles: 500 - odom_frame_id: "odom" - pf_err: 0.05 - pf_z: 0.99 - recovery_alpha_fast: 0.0 - recovery_alpha_slow: 0.0 - resample_interval: 1 - robot_model_type: "nav2_amcl::DifferentialMotionModel" - save_pose_rate: 0.5 - sigma_hit: 0.2 - tf_broadcast: true - transform_tolerance: 1.0 - update_min_a: 0.2 - update_min_d: 0.25 - z_hit: 0.5 - z_max: 0.05 - z_rand: 0.5 - z_short: 0.05 - scan_topic: scan - -bt_navigator: - ros__parameters: - global_frame: map - robot_base_frame: base_link - odom_topic: /odom - bt_loop_duration: 10 - default_server_timeout: 20 - wait_for_service_timeout: 1000 - action_server_result_timeout: 900.0 - navigators: ["navigate_to_pose", "navigate_through_poses"] - navigate_to_pose: - plugin: "nav2_bt_navigator::NavigateToPoseNavigator" - navigate_through_poses: - plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" - # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: - # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml - # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml - # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. - - # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings). - # Built-in plugins are added automatically - # plugin_lib_names: [] - - error_code_names: - - compute_path_error_code - - follow_path_error_code - -controller_server: - ros__parameters: - controller_frequency: 20.0 - costmap_update_timeout: 0.30 - min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.5 - min_theta_velocity_threshold: 0.001 - progress_checker_plugins: ["progress_checker"] - goal_checker_plugins: ["goal_checker"] - controller_plugins: ["FollowPath"] - - # Progress checker parameters - progress_checker: - plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 - movement_time_allowance: 10.0 - # Goal checker parameters - goal_checker: - plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.25 - yaw_goal_tolerance: 0.25 - stateful: True - # DWB parameters - FollowPath: - plugin: "dwb_core::DWBLocalPlanner" - debug_trajectory_details: True - min_vel_x: 0.0 - min_vel_y: 0.0 - max_vel_x: 0.26 - max_vel_y: 0.0 - max_vel_theta: 1.0 - min_speed_xy: 0.0 - max_speed_xy: 0.26 - min_speed_theta: 0.0 - acc_lim_x: 2.5 - acc_lim_y: 0.0 - acc_lim_theta: 3.2 - decel_lim_x: -2.5 - decel_lim_y: 0.0 - decel_lim_theta: -3.2 - vx_samples: 20 - vy_samples: 5 - vtheta_samples: 20 - sim_time: 1.7 - linear_granularity: 0.05 - angular_granularity: 0.025 - transform_tolerance: 0.2 - trans_stopped_velocity: 0.25 - short_circuit_trajectory_evaluation: True - stateful: True - critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] - BaseObstacle.scale: 0.02 - PathAlign.scale: 0.0 - GoalAlign.scale: 0.0 - PathDist.scale: 32.0 - GoalDist.scale: 24.0 - RotateToGoal.scale: 32.0 - RotateToGoal.slowing_factor: 5.0 - RotateToGoal.lookahead_time: -1.0 - -local_costmap: - local_costmap: - ros__parameters: - global_frame: odom - rolling_window: true - width: 3 - height: 3 - resolution: 0.05 - robot_radius: 0.22 - plugins: ["voxel_layer", "inflation_layer"] - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - voxel_layer: - plugin: "nav2_costmap_2d::VoxelLayer" - enabled: True - publish_voxel_map: False - origin_z: 0.0 - z_resolution: 0.05 - z_voxels: 16 - max_obstacle_height: 2.0 - mark_threshold: 0 - observation_sources: scan - scan: - topic: /robot2/scan - max_obstacle_height: 2.0 - clearing: True - marking: True - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - map_subscribe_transient_local: True - always_send_full_costmap: True - -global_costmap: - global_costmap: - ros__parameters: - robot_radius: 0.22 - plugins: ["static_layer", "obstacle_layer", "inflation_layer"] - obstacle_layer: - plugin: "nav2_costmap_2d::ObstacleLayer" - enabled: True - observation_sources: scan - scan: - topic: /robot2/scan - max_obstacle_height: 2.0 - clearing: True - marking: True - data_type: "LaserScan" - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - always_send_full_costmap: True - -map_server: - ros__parameters: - yaml_filename: "tb3_sandbox.yaml" - save_map_timeout: 5.0 - -planner_server: - ros__parameters: - planner_plugins: ["GridBased"] - costmap_update_timeout: 1.0 - GridBased: - plugin: "nav2_navfn_planner::NavfnPlanner" - tolerance: 0.5 - use_astar: false - allow_unknown: true - -behavior_server: - ros__parameters: - costmap_topic: local_costmap/costmap_raw - footprint_topic: local_costmap/published_footprint - cycle_frequency: 10.0 - behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] - spin: - plugin: "nav2_behaviors::Spin" - backup: - plugin: "nav2_behaviors::BackUp" - drive_on_heading: - plugin: "nav2_behaviors::DriveOnHeading" - wait: - plugin: "nav2_behaviors::Wait" - global_frame: odom - robot_base_frame: base_link - transform_tolerance: 0.1 - simulate_ahead_time: 2.0 - max_rotational_vel: 1.0 - min_rotational_vel: 0.4 - rotational_acc_lim: 3.2 - -waypoint_follower: - ros__parameters: - loop_rate: 20 - stop_on_failure: false - action_server_result_timeout: 900.0 - waypoint_task_executor_plugin: "wait_at_waypoint" - wait_at_waypoint: - plugin: "nav2_waypoint_follower::WaitAtWaypoint" - enabled: True - waypoint_pause_duration: 200 - -collision_monitor: - ros__parameters: - base_frame_id: "base_footprint" - odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_smoothed" - cmd_vel_out_topic: "cmd_vel" - state_topic: "collision_monitor_state" - transform_tolerance: 0.2 - source_timeout: 1.0 - base_shift_correction: True - stop_pub_timeout: 2.0 - # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types, - # and robot footprint for "approach" action type. - polygons: ["FootprintApproach"] - FootprintApproach: - type: "polygon" - action_type: "approach" - footprint_topic: "local_costmap/published_footprint" - time_before_collision: 2.0 - simulation_time_step: 0.1 - min_points: 6 - visualize: False - enabled: True - observation_sources: ["scan"] - scan: - type: "scan" - topic: "/robot2/scan" - min_height: 0.15 - max_height: 2.0 - enabled: True - -docking_server: - ros__parameters: - controller_frequency: 50.0 - initial_perception_timeout: 5.0 - wait_charge_timeout: 5.0 - dock_approach_timeout: 30.0 - undock_linear_tolerance: 0.05 - undock_angular_tolerance: 0.1 - max_retries: 3 - base_frame: "base_link" - fixed_frame: "odom" - dock_backwards: false - dock_prestaging_tolerance: 0.5 - - # Types of docks - dock_plugins: ['simple_charging_dock'] - simple_charging_dock: - plugin: 'opennav_docking::SimpleChargingDock' - docking_threshold: 0.05 - staging_x_offset: -0.7 - use_external_detection_pose: true - use_battery_status: false # true - use_stall_detection: false # true - - external_detection_timeout: 1.0 - external_detection_translation_x: -0.18 - external_detection_translation_y: 0.0 - external_detection_rotation_roll: -1.57 - external_detection_rotation_pitch: -1.57 - external_detection_rotation_yaw: 0.0 - filter_coef: 0.1 - - # Dock instances - docks: ['home_dock'] # Input your docks here - home_dock: - type: 'simple_charging_dock' - frame: map - pose: [0.0, 0.0, 0.0] - - controller: - k_phi: 3.0 - k_delta: 2.0 - v_linear_min: 0.15 - v_linear_max: 0.15 diff --git a/nav2_bringup/params/nav2_multirobot_params_all.yaml b/nav2_bringup/params/nav2_multirobot_params_all.yaml deleted file mode 100644 index b6b27887a38..00000000000 --- a/nav2_bringup/params/nav2_multirobot_params_all.yaml +++ /dev/null @@ -1,377 +0,0 @@ -amcl: - ros__parameters: - alpha1: 0.2 - alpha2: 0.2 - alpha3: 0.2 - alpha4: 0.2 - alpha5: 0.2 - base_frame_id: "base_footprint" - beam_skip_distance: 0.5 - beam_skip_error_threshold: 0.9 - beam_skip_threshold: 0.3 - do_beamskip: false - global_frame_id: "map" - lambda_short: 0.1 - laser_likelihood_max_dist: 2.0 - laser_max_range: 100.0 - laser_min_range: -1.0 - laser_model_type: "likelihood_field" - max_beams: 60 - max_particles: 2000 - min_particles: 500 - odom_frame_id: "odom" - pf_err: 0.05 - pf_z: 0.99 - recovery_alpha_fast: 0.0 - recovery_alpha_slow: 0.0 - resample_interval: 1 - robot_model_type: "nav2_amcl::DifferentialMotionModel" - save_pose_rate: 0.5 - sigma_hit: 0.2 - tf_broadcast: true - transform_tolerance: 1.0 - update_min_a: 0.2 - update_min_d: 0.25 - z_hit: 0.5 - z_max: 0.05 - z_rand: 0.5 - z_short: 0.05 - scan_topic: scan - -bt_navigator: - ros__parameters: - global_frame: map - robot_base_frame: base_link - odom_topic: /odom - bt_loop_duration: 10 - default_server_timeout: 20 - wait_for_service_timeout: 1000 - action_server_result_timeout: 900.0 - navigators: ["navigate_to_pose", "navigate_through_poses"] - navigate_to_pose: - plugin: "nav2_bt_navigator::NavigateToPoseNavigator" - navigate_through_poses: - plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator" - # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: - # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml - # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml - # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. - - # plugin_lib_names is used to add custom BT plugins to the executor (vector of strings). - # Built-in plugins are added automatically - # plugin_lib_names: [] - - error_code_names: - - compute_path_error_code - - follow_path_error_code - -controller_server: - ros__parameters: - controller_frequency: 20.0 - costmap_update_timeout: 0.30 - min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.5 - min_theta_velocity_threshold: 0.001 - failure_tolerance: 0.3 - progress_checker_plugins: ["progress_checker"] - goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" - controller_plugins: ["FollowPath"] - - # Progress checker parameters - progress_checker: - plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 - movement_time_allowance: 10.0 - # Goal checker parameters - #precise_goal_checker: - # plugin: "nav2_controller::SimpleGoalChecker" - # xy_goal_tolerance: 0.25 - # yaw_goal_tolerance: 0.25 - # stateful: True - general_goal_checker: - stateful: True - plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.25 - yaw_goal_tolerance: 0.25 - # DWB parameters - FollowPath: - plugin: "dwb_core::DWBLocalPlanner" - debug_trajectory_details: True - min_vel_x: 0.0 - min_vel_y: 0.0 - max_vel_x: 0.26 - max_vel_y: 0.0 - max_vel_theta: 1.0 - min_speed_xy: 0.0 - max_speed_xy: 0.26 - min_speed_theta: 0.0 - acc_lim_x: 2.5 - acc_lim_y: 0.0 - acc_lim_theta: 3.2 - decel_lim_x: -2.5 - decel_lim_y: 0.0 - decel_lim_theta: -3.2 - vx_samples: 20 - vy_samples: 5 - vtheta_samples: 20 - sim_time: 1.7 - linear_granularity: 0.05 - angular_granularity: 0.025 - transform_tolerance: 0.2 - xy_goal_tolerance: 0.25 - trans_stopped_velocity: 0.25 - short_circuit_trajectory_evaluation: True - stateful: True - critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] - BaseObstacle.scale: 0.02 - PathAlign.scale: 32.0 - PathAlign.forward_point_distance: 0.1 - GoalAlign.scale: 24.0 - GoalAlign.forward_point_distance: 0.1 - PathDist.scale: 32.0 - GoalDist.scale: 24.0 - RotateToGoal.scale: 32.0 - RotateToGoal.slowing_factor: 5.0 - RotateToGoal.lookahead_time: -1.0 - -local_costmap: - local_costmap: - ros__parameters: - update_frequency: 5.0 - publish_frequency: 2.0 - global_frame: odom - robot_base_frame: base_link - rolling_window: true - width: 3 - height: 3 - resolution: 0.05 - robot_radius: 0.22 - plugins: ["voxel_layer", "inflation_layer"] - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - voxel_layer: - plugin: "nav2_costmap_2d::VoxelLayer" - enabled: True - publish_voxel_map: True - origin_z: 0.0 - z_resolution: 0.05 - z_voxels: 16 - max_obstacle_height: 2.0 - mark_threshold: 0 - observation_sources: scan - scan: - # '' keyword shall be replaced with 'namespace' where user defined. - # It doesn't need to start with '/' - topic: /scan - max_obstacle_height: 2.0 - clearing: True - marking: True - data_type: "LaserScan" - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True - always_send_full_costmap: True - -global_costmap: - global_costmap: - ros__parameters: - update_frequency: 1.0 - publish_frequency: 1.0 - global_frame: map - robot_base_frame: base_link - robot_radius: 0.22 - resolution: 0.05 - track_unknown_space: true - plugins: ["static_layer", "obstacle_layer", "inflation_layer"] - obstacle_layer: - plugin: "nav2_costmap_2d::ObstacleLayer" - enabled: True - observation_sources: scan - scan: - # '' keyword shall be replaced with 'namespace' where user defined. - # It doesn't need to start with '/' - topic: /scan - max_obstacle_height: 2.0 - clearing: True - marking: True - data_type: "LaserScan" - raytrace_max_range: 3.0 - raytrace_min_range: 0.0 - obstacle_max_range: 2.5 - obstacle_min_range: 0.0 - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True - inflation_layer: - plugin: "nav2_costmap_2d::InflationLayer" - cost_scaling_factor: 3.0 - inflation_radius: 0.55 - always_send_full_costmap: True - -# The yaml_filename does not need to be specified since it going to be set by defaults in launch. -# If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py -# file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used. -# map_server: -# ros__parameters: -# yaml_filename: "" - -map_saver: - ros__parameters: - save_map_timeout: 5.0 - free_thresh_default: 0.25 - occupied_thresh_default: 0.65 - map_subscribe_transient_local: True - -planner_server: - ros__parameters: - expected_planner_frequency: 20.0 - costmap_update_timeout: 1.0 - planner_plugins: ["GridBased"] - GridBased: - plugin: "nav2_navfn_planner::NavfnPlanner" - tolerance: 0.5 - use_astar: false - allow_unknown: true - -smoother_server: - ros__parameters: - smoother_plugins: ["simple_smoother"] - simple_smoother: - plugin: "nav2_smoother::SimpleSmoother" - tolerance: 1.0e-10 - max_its: 1000 - do_refinement: True - -behavior_server: - ros__parameters: - local_costmap_topic: local_costmap/costmap_raw - global_costmap_topic: global_costmap/costmap_raw - local_footprint_topic: local_costmap/published_footprint - global_footprint_topic: global_costmap/published_footprint - cycle_frequency: 10.0 - behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] - spin: - plugin: "nav2_behaviors::Spin" - backup: - plugin: "nav2_behaviors::BackUp" - drive_on_heading: - plugin: "nav2_behaviors::DriveOnHeading" - wait: - plugin: "nav2_behaviors::Wait" - assisted_teleop: - plugin: "nav2_behaviors::AssistedTeleop" - local_frame: odom - global_frame: map - robot_base_frame: base_link - transform_tolerance: 0.1 - simulate_ahead_time: 2.0 - max_rotational_vel: 1.0 - min_rotational_vel: 0.4 - rotational_acc_lim: 3.2 - -waypoint_follower: - ros__parameters: - loop_rate: 20 - stop_on_failure: false - action_server_result_timeout: 900.0 - waypoint_task_executor_plugin: "wait_at_waypoint" - wait_at_waypoint: - plugin: "nav2_waypoint_follower::WaitAtWaypoint" - enabled: True - waypoint_pause_duration: 200 - -velocity_smoother: - ros__parameters: - smoothing_frequency: 20.0 - scale_velocities: False - feedback: "OPEN_LOOP" - max_velocity: [0.26, 0.0, 1.0] - min_velocity: [-0.26, 0.0, -1.0] - max_accel: [2.5, 0.0, 3.2] - max_decel: [-2.5, 0.0, -3.2] - odom_topic: "odom" - odom_duration: 0.1 - deadband_velocity: [0.0, 0.0, 0.0] - velocity_timeout: 1.0 - -collision_monitor: - ros__parameters: - base_frame_id: "base_footprint" - odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_smoothed" - cmd_vel_out_topic: "cmd_vel" - state_topic: "collision_monitor_state" - transform_tolerance: 0.2 - source_timeout: 1.0 - base_shift_correction: True - stop_pub_timeout: 2.0 - # Polygons represent zone around the robot for "stop", "slowdown" and "limit" action types, - # and robot footprint for "approach" action type. - polygons: ["FootprintApproach"] - FootprintApproach: - type: "polygon" - action_type: "approach" - footprint_topic: "/local_costmap/published_footprint" - time_before_collision: 2.0 - simulation_time_step: 0.1 - min_points: 6 - visualize: False - enabled: True - observation_sources: ["scan"] - scan: - type: "scan" - topic: "/scan" - min_height: 0.15 - max_height: 2.0 - enabled: True - -docking_server: - ros__parameters: - controller_frequency: 50.0 - initial_perception_timeout: 5.0 - wait_charge_timeout: 5.0 - dock_approach_timeout: 30.0 - undock_linear_tolerance: 0.05 - undock_angular_tolerance: 0.1 - max_retries: 3 - base_frame: "base_link" - fixed_frame: "odom" - dock_backwards: false - dock_prestaging_tolerance: 0.5 - - # Types of docks - dock_plugins: ['simple_charging_dock'] - simple_charging_dock: - plugin: 'opennav_docking::SimpleChargingDock' - docking_threshold: 0.05 - staging_x_offset: -0.7 - use_external_detection_pose: true - use_battery_status: false # true - use_stall_detection: false # true - - external_detection_timeout: 1.0 - external_detection_translation_x: -0.18 - external_detection_translation_y: 0.0 - external_detection_rotation_roll: -1.57 - external_detection_rotation_pitch: -1.57 - external_detection_rotation_yaw: 0.0 - filter_coef: 0.1 - - # Dock instances - docks: ['home_dock'] # Input your docks here - home_dock: - type: 'simple_charging_dock' - frame: map - pose: [0.0, 0.0, 0.0] - - controller: - k_phi: 3.0 - k_delta: 2.0 - v_linear_min: 0.15 - v_linear_max: 0.15 diff --git a/nav2_bringup/params/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml index 69fe42195eb..a5e4a539c02 100644 --- a/nav2_bringup/params/nav2_params.yaml +++ b/nav2_bringup/params/nav2_params.yaml @@ -42,7 +42,7 @@ bt_navigator: ros__parameters: global_frame: map robot_base_frame: base_link - odom_topic: /odom + odom_topic: odom bt_loop_duration: 10 default_server_timeout: 20 wait_for_service_timeout: 1000 @@ -211,7 +211,13 @@ local_costmap: mark_threshold: 0 observation_sources: scan scan: - topic: /scan + # A relative topic will be appended to the parent of the local_costmap namespace. + # For example: + # * User chosen namespace is `tb4`. + # * User chosen topic is `scan`. + # * Topic will be remapped to `/tb4/scan` without `local_costmap`. + # * Use global topic `/scan` if you do not wish the node namespace to apply + topic: scan max_obstacle_height: 2.0 clearing: True marking: True @@ -241,7 +247,13 @@ global_costmap: enabled: True observation_sources: scan scan: - topic: /scan + # A relative topic will be appended to the parent of the global_costmap namespace. + # For example: + # * User chosen namespace is `tb4`. + # * User chosen topic is `scan`. + # * Topic will be remapped to `/tb4/scan` without `global_costmap`. + # * Use global topic `/scan` if you do not wish the node namespace to apply + topic: scan max_obstacle_height: 2.0 clearing: True marking: True @@ -362,7 +374,7 @@ collision_monitor: FootprintApproach: type: "polygon" action_type: "approach" - footprint_topic: "/local_costmap/published_footprint" + footprint_topic: "local_costmap/published_footprint" time_before_collision: 1.2 simulation_time_step: 0.1 min_points: 6 diff --git a/nav2_bringup/rviz/nav2_default_view.rviz b/nav2_bringup/rviz/nav2_default_view.rviz index c8dd3768583..df1bc58d5dc 100644 --- a/nav2_bringup/rviz/nav2_default_view.rviz +++ b/nav2_bringup/rviz/nav2_default_view.rviz @@ -58,7 +58,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /robot_description + Value: robot_description Enabled: false Links: All Links Enabled: true @@ -148,7 +148,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Best Effort - Value: /scan + Value: scan Use Fixed Frame: true Use rainbow: true Value: true @@ -181,7 +181,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /mobile_base/sensors/bumper_pointcloud + Value: mobile_base/sensors/bumper_pointcloud Use Fixed Frame: true Use rainbow: true Value: true @@ -199,13 +199,13 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /map + Value: map Update Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /map_updates + Value: map_updates Use Timestamp: false Value: true - Alpha: 1 @@ -222,7 +222,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Best Effort - Value: /particle_cloud + Value: particle_cloud Value: true - Class: rviz_common/Group Displays: @@ -240,13 +240,13 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/costmap + Value: global_costmap/costmap Update Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/costmap_updates + Value: global_costmap/costmap_updates Use Timestamp: false Value: true - Alpha: 0.30000001192092896 @@ -263,13 +263,13 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /downsampled_costmap + Value: downsampled_costmap Update Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /downsampled_costmap_updates + Value: downsampled_costmap_updates Use Timestamp: false Value: true - Alpha: 1 @@ -298,7 +298,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /plan + Value: plan Value: true - Alpha: 1 Autocompute Intensity Bounds: true @@ -329,7 +329,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/voxel_marked_cloud + Value: global_costmap/voxel_marked_cloud Use Fixed Frame: true Use rainbow: true Value: true @@ -344,7 +344,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/published_footprint + Value: global_costmap/published_footprint Value: false Enabled: true Name: Global Planner @@ -364,13 +364,13 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/costmap + Value: local_costmap/costmap Update Topic: Depth: 5 Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/costmap_updates + Value: local_costmap/costmap_updates Use Timestamp: false Value: true - Alpha: 1 @@ -399,7 +399,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /local_plan + Value: local_plan Value: true - Class: rviz_default_plugins/MarkerArray Enabled: false @@ -411,7 +411,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /marker + Value: marker Value: false - Alpha: 1 Class: rviz_default_plugins/Polygon @@ -424,7 +424,7 @@ Visualization Manager: Filter size: 10 History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/published_footprint + Value: local_costmap/published_footprint Value: true - Alpha: 1 Autocompute Intensity Bounds: true @@ -455,7 +455,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/voxel_marked_cloud + Value: local_costmap/voxel_marked_cloud Use Fixed Frame: true Use rainbow: true Value: true @@ -475,7 +475,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /intel_realsense_r200_depth/image_raw + Value: intel_realsense_r200_depth/image_raw Value: true - Alpha: 1 Autocompute Intensity Bounds: true @@ -506,7 +506,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /intel_realsense_r200_depth/points + Value: intel_realsense_r200_depth/points Use Fixed Frame: true Use rainbow: true Value: true @@ -522,7 +522,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /waypoints + Value: waypoints Value: true Enabled: true Global Options: @@ -545,7 +545,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /initialpose + Value: initialpose - Class: rviz_default_plugins/PublishPoint Single click: true Topic: @@ -553,7 +553,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /clicked_point + Value: clicked_point - Class: nav2_rviz_plugins/GoalTool Transformation: Current: diff --git a/nav2_bringup/rviz/nav2_namespaced_view.rviz b/nav2_bringup/rviz/nav2_namespaced_view.rviz deleted file mode 100644 index 4dcd23e24b4..00000000000 --- a/nav2_bringup/rviz/nav2_namespaced_view.rviz +++ /dev/null @@ -1,379 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 195 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /RobotModel1/Status1 - - /TF1/Frames1 - - /TF1/Tree1 - - /Global Planner1/Global Costmap1 - Splitter Ratio: 0.5833333134651184 - Tree Height: 464 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 - - Class: nav2_rviz_plugins/Navigation 2 - Name: Navigation 2 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 1 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: false - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - Name: RobotModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_default_plugins/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: false - Marker Scale: 1 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: false - Tree: - {} - Update Interval: 0 - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: LaserScan - Position Transformer: XYZ - Selectable: true - Size (Pixels): 3 - Size (m): 0.009999999776482582 - Style: Flat Squares - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /scan - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Autocompute Intensity Bounds: true - Autocompute Value Bounds: - Max Value: 10 - Min Value: -10 - Value: true - Axis: Z - Channel Name: intensity - Class: rviz_default_plugins/PointCloud2 - Color: 255; 255; 255 - Color Transformer: "" - Decay Time: 0 - Enabled: true - Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 4096 - Min Color: 0; 0; 0 - Min Intensity: 0 - Name: Bumper Hit - Position Transformer: "" - Selectable: true - Size (Pixels): 3 - Size (m): 0.07999999821186066 - Style: Spheres - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /mobile_base/sensors/bumper_pointcloud - Use Fixed Frame: true - Use rainbow: true - Value: true - - Alpha: 1 - Class: rviz_default_plugins/Map - Color Scheme: map - Draw Behind: true - Enabled: true - Name: Map - Topic: - Depth: 1 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /map - Use Timestamp: false - Value: true - - Alpha: 1 - Class: nav2_rviz_plugins/ParticleCloud - Color: 0; 180; 0 - Enabled: true - Max Arrow Length: 0.3 - Min Arrow Length: 0.02 - Name: Amcl Particle Swarm - Shape: Arrow (Flat) - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Best Effort - Value: /particle_cloud - Value: true - - Class: rviz_common/Group - Displays: - - Alpha: 0.30000001192092896 - Class: rviz_default_plugins/Map - Color Scheme: costmap - Draw Behind: false - Enabled: true - Name: Global Costmap - Topic: - Depth: 1 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /global_costmap/costmap - Use Timestamp: false - Value: true - - Alpha: 1 - Buffer Length: 1 - Class: rviz_default_plugins/Path - Color: 255; 0; 0 - Enabled: true - Head Diameter: 0.019999999552965164 - Head Length: 0.019999999552965164 - Length: 0.30000001192092896 - Line Style: Lines - Line Width: 0.029999999329447746 - Name: Path - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: Arrows - Radius: 0.029999999329447746 - Shaft Diameter: 0.004999999888241291 - Shaft Length: 0.019999999552965164 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /plan - Value: true - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: false - Name: Polygon - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /global_costmap/published_footprint - Value: false - Enabled: true - Name: Global Planner - - Class: rviz_common/Group - Displays: - - Alpha: 0.699999988079071 - Class: rviz_default_plugins/Map - Color Scheme: costmap - Draw Behind: false - Enabled: true - Name: Local Costmap - Topic: - Depth: 1 - Durability Policy: Transient Local - History Policy: Keep Last - Reliability Policy: Reliable - Value: /local_costmap/costmap - Use Timestamp: false - Value: true - - Alpha: 1 - Buffer Length: 1 - Class: rviz_default_plugins/Path - Color: 0; 12; 255 - Enabled: true - Head Diameter: 0.30000001192092896 - Head Length: 0.20000000298023224 - Length: 0.30000001192092896 - Line Style: Lines - Line Width: 0.029999999329447746 - Name: Local Plan - Offset: - X: 0 - Y: 0 - Z: 0 - Pose Color: 255; 85; 255 - Pose Style: None - Radius: 0.029999999329447746 - Shaft Diameter: 0.10000000149011612 - Shaft Length: 0.10000000149011612 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /local_plan - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: false - Name: Trajectories - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /marker - Value: false - - Alpha: 1 - Class: rviz_default_plugins/Polygon - Color: 25; 255; 0 - Enabled: true - Name: Polygon - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /local_costmap/published_footprint - Value: true - Enabled: true - Name: Controller - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: MarkerArray - Namespaces: - {} - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /waypoints - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: map - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: nav2_rviz_plugins/GoalTool - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Angle: -1.5708 - Class: rviz_default_plugins/TopDownOrtho - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Scale: 160 - Target Frame: - Value: TopDownOrtho (rviz_default_plugins) - X: 0 - Y: 0 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 914 - Hide Left Dock: false - Hide Right Dock: true - Navigation 2: - collapsed: false - QMainWindow State: 000000ff00000000fd00000004000000000000016a00000338fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002c4000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e0020003201000003070000006e0000006200ffffff000000010000010f00000338fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000338000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004990000033800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1545 - X: 186 - Y: 117 - diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index f68afbe7105..dcef3c6fa2b 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -69,7 +69,7 @@ ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) // The costmap node is used in the implementation of the controller costmap_ros_ = std::make_shared( - "local_costmap", std::string{get_namespace()}, "local_costmap", + "local_costmap", std::string{get_namespace()}, get_parameter("use_sim_time").as_bool()); } diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 33feaa700df..3d71c501ece 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -81,26 +81,16 @@ class Costmap2DROS : public nav2_util::LifecycleNode */ explicit Costmap2DROS(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); - /** - * @brief Constructor for the wrapper, the node will - * be placed in a namespace equal to the node's name - * @param name Name of the costmap ROS node - * @param use_sim_time Whether to use simulation or real time - */ - explicit Costmap2DROS(const std::string & name, const bool & use_sim_time = false); - /** * @brief Constructor for the wrapper - * @param name Name of the costmap ROS node + * @param name Name of the costmap ROS node which will also be used as a local namespace * @param parent_namespace Absolute namespace of the node hosting the costmap node - * @param local_namespace Namespace to append to the parent namespace * @param use_sim_time Whether to use simulation or real time */ explicit Costmap2DROS( const std::string & name, - const std::string & parent_namespace, - const std::string & local_namespace, - const bool & use_sim_time); + const std::string & parent_namespace = "/", + const bool & use_sim_time = false); /** * @brief Common initialization for constructors @@ -372,7 +362,6 @@ class Costmap2DROS : public nav2_util::LifecycleNode std::unique_ptr layered_costmap_{nullptr}; std::string name_; - std::string parent_namespace_; /** * @brief Function on timer for costmap update diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp index 43a82e0cde1..34f0314b76d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_layer.hpp @@ -38,6 +38,8 @@ #ifndef NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_ #define NAV2_COSTMAP_2D__COSTMAP_LAYER_HPP_ +#include + #include #include #include @@ -192,6 +194,24 @@ class CostmapLayer : public Layer, public Costmap2D */ CombinationMethod combination_method_from_int(const int value); + /** + * Joins the specified topic with the parent namespace of the costmap node. + * If the topic has an absolute path, it is returned instead. + * + * This is necessary for user defined relative topics to work as expected since costmap layers + * add a an additional `costmap_name` namespace to the topic. + * For example: + * * User chosen namespace is `tb4`. + * * User chosen topic is `scan`. + * * Costmap node namespace will be `/tb4/global_costmap`. + * * Without this function, the topic would be `/tb4/global_costmap/scan`. + * * With this function, topic will be remapped to `/tb4/scan`. + * Use global topic `/scan` if you do not wish the node namespace to apply + * + * @param topic the topic to parse + */ + std::string joinWithParentNamespace(const std::string & topic); + private: double extra_min_x_, extra_max_x_, extra_min_y_, extra_max_y_; }; diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index 3ba1c97f08a..7021bfb4595 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -189,6 +189,7 @@ void ObstacleLayer::onInitialize() node->get_parameter(name_ + "." + source + "." + "raytrace_min_range", raytrace_min_range); node->get_parameter(name_ + "." + source + "." + "raytrace_max_range", raytrace_max_range); + topic = joinWithParentNamespace(topic); RCLCPP_DEBUG( logger_, diff --git a/nav2_costmap_2d/plugins/range_sensor_layer.cpp b/nav2_costmap_2d/plugins/range_sensor_layer.cpp index ffbe8a3ef8b..dc28d4f4342 100644 --- a/nav2_costmap_2d/plugins/range_sensor_layer.cpp +++ b/nav2_costmap_2d/plugins/range_sensor_layer.cpp @@ -130,6 +130,7 @@ void RangeSensorLayer::onInitialize() // Traverse the topic names list subscribing to all of them with the same callback method for (auto & topic_name : topic_names) { + topic_name = joinWithParentNamespace(topic_name); if (input_sensor_type == InputSensorType::VARIABLE) { processRangeMessageFunc_ = std::bind( &RangeSensorLayer::processVariableRangeMsg, this, diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 67b7fbd5ec9..896dfc77a5f 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -136,7 +136,7 @@ StaticLayer::getParameters() declareParameter("subscribe_to_updates", rclcpp::ParameterValue(false)); declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true)); declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); - declareParameter("map_topic", rclcpp::ParameterValue("")); + declareParameter("map_topic", rclcpp::ParameterValue("map")); declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false)); auto node = node_.lock(); @@ -147,14 +147,8 @@ StaticLayer::getParameters() node->get_parameter(name_ + "." + "enabled", enabled_); node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); - std::string private_map_topic, global_map_topic; - node->get_parameter(name_ + "." + "map_topic", private_map_topic); - node->get_parameter("map_topic", global_map_topic); - if (!private_map_topic.empty()) { - map_topic_ = private_map_topic; - } else { - map_topic_ = global_map_topic; - } + node->get_parameter(name_ + "." + "map_topic", map_topic_); + map_topic_ = joinWithParentNamespace(map_topic_); node->get_parameter( name_ + "." + "map_subscribe_transient_local", map_subscribe_transient_local_); diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index fa11b60ebfe..5413fd3d2c1 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -58,9 +58,6 @@ using rcl_interfaces::msg::ParameterType; namespace nav2_costmap_2d { -Costmap2DROS::Costmap2DROS(const std::string & name, const bool & use_sim_time) -: Costmap2DROS(name, "/", name, use_sim_time) {} - Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) : nav2_util::LifecycleNode("costmap", "", options), name_("costmap"), @@ -70,7 +67,6 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"} { - declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map"))); is_lifecycle_follower_ = false; init(); } @@ -78,7 +74,6 @@ Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) Costmap2DROS::Costmap2DROS( const std::string & name, const std::string & parent_namespace, - const std::string & local_namespace, const bool & use_sim_time) : nav2_util::LifecycleNode(name, "", // NodeOption arguments take precedence over the ones provided on the command line @@ -87,21 +82,17 @@ Costmap2DROS::Costmap2DROS( // of the namespaces rclcpp::NodeOptions().arguments({ "--ros-args", "-r", std::string("__ns:=") + - nav2_util::add_namespaces(parent_namespace, local_namespace), + nav2_util::add_namespaces(parent_namespace, name), "--ros-args", "-r", name + ":" + std::string("__node:=") + name, "--ros-args", "-p", "use_sim_time:=" + std::string(use_sim_time ? "true" : "false"), })), name_(name), - parent_namespace_(parent_namespace), default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"}, default_types_{ "nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"} { - declare_parameter( - "map_topic", rclcpp::ParameterValue( - (parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map"))); init(); } diff --git a/nav2_costmap_2d/src/costmap_layer.cpp b/nav2_costmap_2d/src/costmap_layer.cpp index 8dbce5017f0..93f20f664dc 100644 --- a/nav2_costmap_2d/src/costmap_layer.cpp +++ b/nav2_costmap_2d/src/costmap_layer.cpp @@ -264,4 +264,20 @@ CombinationMethod CostmapLayer::combination_method_from_int(const int value) return CombinationMethod::Max; } } + +std::string CostmapLayer::joinWithParentNamespace(const std::string & topic) +{ + auto node = node_.lock(); + if (!node) { + throw std::runtime_error{"Failed to lock node"}; + } + + if (topic[0] != '/') { + std::string node_namespace = node->get_namespace(); + std::string parent_namespace = node_namespace.substr(0, node_namespace.rfind("/")); + return parent_namespace + "/" + topic; + } + + return topic; +} } // namespace nav2_costmap_2d diff --git a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp index 68a9875ef61..9b91adcf786 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp @@ -45,7 +45,6 @@ class CostmapRosLifecycleNode : public nav2_util::LifecycleNode costmap_ros_ = std::make_shared( name_, std::string{get_namespace()}, - name_, get_parameter("use_sim_time").as_bool()); costmap_thread_ = std::make_unique(costmap_ros_); diff --git a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp index b556a06be15..d3e18e2acbe 100644 --- a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp @@ -125,11 +125,13 @@ TEST(ObstacleFootprint, Prepare) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); - auto costmap_ros = std::make_shared("test_global_costmap"); + std::string ns = "/ns"; + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, false); costmap_ros->configure(); std::string name = "name"; - std::string ns = "ns"; critic->initialize(node, name, ns, costmap_ros); geometry_msgs::msg::Pose2D pose; @@ -185,11 +187,13 @@ TEST(ObstacleFootprint, PointCost) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); - auto costmap_ros = std::make_shared("test_global_costmap"); + std::string ns = "/ns"; + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, false); costmap_ros->configure(); std::string name = "name"; - std::string ns = "ns"; critic->initialize(node, name, ns, costmap_ros); costmap_ros->getCostmap()->setCost(0, 0, nav2_costmap_2d::LETHAL_OBSTACLE); @@ -208,11 +212,13 @@ TEST(ObstacleFootprint, LineCost) auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); - auto costmap_ros = std::make_shared("test_global_costmap"); + std::string ns = "/ns"; + std::string costmap_name = "test_global_costmap"; + auto costmap_ros = + std::make_shared(costmap_name, ns, false); costmap_ros->configure(); std::string name = "name"; - std::string ns = "ns"; critic->initialize(node, name, ns, costmap_ros); costmap_ros->getCostmap()->setCost(3, 3, nav2_costmap_2d::LETHAL_OBSTACLE); diff --git a/nav2_mppi_controller/test/critic_manager_test.cpp b/nav2_mppi_controller/test/critic_manager_test.cpp index f24d205bfbe..e2cf5d80034 100644 --- a/nav2_mppi_controller/test/critic_manager_test.cpp +++ b/nav2_mppi_controller/test/critic_manager_test.cpp @@ -102,7 +102,7 @@ TEST(CriticManagerTests, BasicCriticOperations) { auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -140,7 +140,7 @@ TEST(CriticManagerTests, CriticLoadingTest) "critic_manager.critics", rclcpp::ParameterValue(std::vector{"ConstraintCritic", "PreferForwardCritic"})); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State state; costmap_ros->on_configure(state); diff --git a/nav2_mppi_controller/test/critics_tests.cpp b/nav2_mppi_controller/test/critics_tests.cpp index 70417834df4..e4a28f3df1c 100644 --- a/nav2_mppi_controller/test/critics_tests.cpp +++ b/nav2_mppi_controller/test/critics_tests.cpp @@ -61,7 +61,7 @@ TEST(CriticTests, ConstraintsCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -133,7 +133,7 @@ TEST(CriticTests, GoalAngleCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -185,7 +185,7 @@ TEST(CriticTests, GoalCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -234,7 +234,7 @@ TEST(CriticTests, PathAngleCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -349,7 +349,7 @@ TEST(CriticTests, PreferForwardCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -402,7 +402,7 @@ TEST(CriticTests, TwirlingCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -462,7 +462,7 @@ TEST(CriticTests, PathFollowCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -510,7 +510,7 @@ TEST(CriticTests, PathAlignCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -614,7 +614,7 @@ TEST(CriticTests, VelocityDeadbandCritic) // Standard preamble auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); auto getParam = param_handler.getParamGetter("critic"); std::vector deadband_velocities_; diff --git a/nav2_mppi_controller/test/optimizer_unit_tests.cpp b/nav2_mppi_controller/test/optimizer_unit_tests.cpp index c1b5f56799c..db28b904dd0 100644 --- a/nav2_mppi_controller/test/optimizer_unit_tests.cpp +++ b/nav2_mppi_controller/test/optimizer_unit_tests.cpp @@ -233,7 +233,7 @@ TEST(OptimizerTests, BasicInitializedFunctions) node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.ax_min", rclcpp::ParameterValue(3.0)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -269,7 +269,7 @@ TEST(OptimizerTests, TestOptimizerMotionModels) OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -301,7 +301,7 @@ TEST(OptimizerTests, setOffsetTests) node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -324,7 +324,7 @@ TEST(OptimizerTests, resetTests) node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -344,7 +344,7 @@ TEST(OptimizerTests, FallbackTests) node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); node->declare_parameter("mppic.retry_attempt_limit", rclcpp::ParameterValue(2)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -368,7 +368,7 @@ TEST(OptimizerTests, PrepareTests) node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); node->declare_parameter("mppic.retry_attempt_limit", rclcpp::ParameterValue(2)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -395,7 +395,7 @@ TEST(OptimizerTests, shiftControlSequenceTests) node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); node->declare_parameter("mppic.retry_attempt_limit", rclcpp::ParameterValue(2)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -438,7 +438,7 @@ TEST(OptimizerTests, SpeedLimitTests) node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); node->declare_parameter("mppic.retry_attempt_limit", rclcpp::ParameterValue(2)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -478,7 +478,7 @@ TEST(OptimizerTests, applyControlSequenceConstraintsTests) node->declare_parameter("mppic.vy_max", rclcpp::ParameterValue(0.75)); node->declare_parameter("mppic.wz_max", rclcpp::ParameterValue(2.0)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -538,7 +538,7 @@ TEST(OptimizerTests, updateStateVelocitiesTests) node->declare_parameter("mppic.ay_max", rclcpp::ParameterValue(3.0)); node->declare_parameter("mppic.az_max", rclcpp::ParameterValue(3.5)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -563,7 +563,7 @@ TEST(OptimizerTests, getControlFromSequenceAsTwistTests) node->declare_parameter("mppic.vy_max", rclcpp::ParameterValue(0.60)); node->declare_parameter("mppic.wz_max", rclcpp::ParameterValue(2.0)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); @@ -598,7 +598,7 @@ TEST(OptimizerTests, integrateStateVelocitiesTests) node->declare_parameter("mppic.model_dt", rclcpp::ParameterValue(0.1)); node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); diff --git a/nav2_mppi_controller/test/path_handler_test.cpp b/nav2_mppi_controller/test/path_handler_test.cpp index 0bcf5543924..54707c185bf 100644 --- a/nav2_mppi_controller/test/path_handler_test.cpp +++ b/nav2_mppi_controller/test/path_handler_test.cpp @@ -108,7 +108,7 @@ TEST(PathHandlerTests, TestBounds) auto node = std::make_shared("my_node"); node->declare_parameter("dummy.max_robot_pose_search_dist", rclcpp::ParameterValue(99999.9)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); auto results = costmap_ros->set_parameters_atomically( {rclcpp::Parameter("global_frame", "odom"), rclcpp::Parameter("robot_base_frame", "base_link")}); @@ -159,7 +159,7 @@ TEST(PathHandlerTests, TestTransforms) auto node = std::make_shared("my_node"); node->declare_parameter("dummy.max_robot_pose_search_dist", rclcpp::ParameterValue(99999.9)); auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); ParametersHandler param_handler(node); rclcpp_lifecycle::State state; costmap_ros->on_configure(state); diff --git a/nav2_mppi_controller/test/utils_test.cpp b/nav2_mppi_controller/test/utils_test.cpp index 675433c0c59..529ed2e7c0c 100644 --- a/nav2_mppi_controller/test/utils_test.cpp +++ b/nav2_mppi_controller/test/utils_test.cpp @@ -290,7 +290,7 @@ TEST(UtilsTests, findPathCosts) std::nullopt, std::nullopt}; /// Caution, keep references auto costmap_ros = std::make_shared( - "dummy_costmap", "", "dummy_costmap", true); + "dummy_costmap", "", true); rclcpp_lifecycle::State lstate; costmap_ros->on_configure(lstate); auto * costmap = costmap_ros->getCostmap(); diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 7233a7ba53d..ccce9813544 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -64,7 +64,7 @@ PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) // Setup the global costmap costmap_ros_ = std::make_shared( - "global_costmap", std::string{get_namespace()}, "global_costmap", + "global_costmap", std::string{get_namespace()}, get_parameter("use_sim_time").as_bool()); } diff --git a/nav2_simple_commander/launch/assisted_teleop_example_launch.py b/nav2_simple_commander/launch/assisted_teleop_example_launch.py index 90abfcad8a7..ad3119ce441 100644 --- a/nav2_simple_commander/launch/assisted_teleop_example_launch.py +++ b/nav2_simple_commander/launch/assisted_teleop_example_launch.py @@ -114,7 +114,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/follow_path_example_launch.py b/nav2_simple_commander/launch/follow_path_example_launch.py index 84de9257a77..b07fef9ba68 100644 --- a/nav2_simple_commander/launch/follow_path_example_launch.py +++ b/nav2_simple_commander/launch/follow_path_example_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/inspection_demo_launch.py b/nav2_simple_commander/launch/inspection_demo_launch.py index 7394f494338..be98c14150d 100644 --- a/nav2_simple_commander/launch/inspection_demo_launch.py +++ b/nav2_simple_commander/launch/inspection_demo_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/nav_through_poses_example_launch.py b/nav2_simple_commander/launch/nav_through_poses_example_launch.py index 8dc297d010f..593ee1e8816 100644 --- a/nav2_simple_commander/launch/nav_through_poses_example_launch.py +++ b/nav2_simple_commander/launch/nav_through_poses_example_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/nav_to_pose_example_launch.py b/nav2_simple_commander/launch/nav_to_pose_example_launch.py index 52192c0a2d6..c3e22fb08d3 100644 --- a/nav2_simple_commander/launch/nav_to_pose_example_launch.py +++ b/nav2_simple_commander/launch/nav_to_pose_example_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/picking_demo_launch.py b/nav2_simple_commander/launch/picking_demo_launch.py index 65c49af0b52..f4bd8346013 100644 --- a/nav2_simple_commander/launch/picking_demo_launch.py +++ b/nav2_simple_commander/launch/picking_demo_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/recoveries_example_launch.py b/nav2_simple_commander/launch/recoveries_example_launch.py index 429d5d3bd37..c7afd73f31c 100644 --- a/nav2_simple_commander/launch/recoveries_example_launch.py +++ b/nav2_simple_commander/launch/recoveries_example_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/security_demo_launch.py b/nav2_simple_commander/launch/security_demo_launch.py index 4872c031c22..240f430b236 100644 --- a/nav2_simple_commander/launch/security_demo_launch.py +++ b/nav2_simple_commander/launch/security_demo_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_simple_commander/launch/waypoint_follower_example_launch.py b/nav2_simple_commander/launch/waypoint_follower_example_launch.py index d87fd8ea11d..10f36ce7922 100644 --- a/nav2_simple_commander/launch/waypoint_follower_example_launch.py +++ b/nav2_simple_commander/launch/waypoint_follower_example_launch.py @@ -113,7 +113,7 @@ def generate_launch_description(): os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) # start navigation diff --git a/nav2_system_tests/src/costmap_filters/test_keepout_launch.py b/nav2_system_tests/src/costmap_filters/test_keepout_launch.py index f0d7d924de7..bb43001b5b9 100755 --- a/nav2_system_tests/src/costmap_filters/test_keepout_launch.py +++ b/nav2_system_tests/src/costmap_filters/test_keepout_launch.py @@ -152,7 +152,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/nav2_system_tests/src/costmap_filters/test_speed_launch.py b/nav2_system_tests/src/costmap_filters/test_speed_launch.py index 38492a53bc6..281aed36250 100755 --- a/nav2_system_tests/src/costmap_filters/test_speed_launch.py +++ b/nav2_system_tests/src/costmap_filters/test_speed_launch.py @@ -150,7 +150,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/nav2_system_tests/src/gps_navigation/test_case_py.launch.py b/nav2_system_tests/src/gps_navigation/test_case_py.launch.py index 3dd082c1918..cb11b2c36d7 100755 --- a/nav2_system_tests/src/gps_navigation/test_case_py.launch.py +++ b/nav2_system_tests/src/gps_navigation/test_case_py.launch.py @@ -102,7 +102,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'use_sim_time': 'True', 'params_file': configured_params, 'use_composition': 'False', diff --git a/nav2_system_tests/src/system/test_multi_robot_launch.py b/nav2_system_tests/src/system/test_multi_robot_launch.py index 92f9a912dfd..87c7bb671e0 100755 --- a/nav2_system_tests/src/system/test_multi_robot_launch.py +++ b/nav2_system_tests/src/system/test_multi_robot_launch.py @@ -47,10 +47,10 @@ def generate_launch_description(): bringup_dir = get_package_share_directory('nav2_bringup') robot1_params_file = os.path.join( # noqa: F841 - bringup_dir, 'params/nav2_multirobot_params_1.yaml' + bringup_dir, 'params/nav2_params.yaml' ) robot2_params_file = os.path.join( # noqa: F841 - bringup_dir, 'params/nav2_multirobot_params_2.yaml' + bringup_dir, 'params/nav2_params.yaml' ) # Names and poses of the robots diff --git a/nav2_system_tests/src/system/test_system_launch.py b/nav2_system_tests/src/system/test_system_launch.py index 439a82e8962..fb4d3625880 100755 --- a/nav2_system_tests/src/system/test_system_launch.py +++ b/nav2_system_tests/src/system/test_system_launch.py @@ -129,7 +129,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/nav2_system_tests/src/system/test_system_with_obstacle_launch.py b/nav2_system_tests/src/system/test_system_with_obstacle_launch.py index 4f6cc09ffb5..b31f19bdd61 100755 --- a/nav2_system_tests/src/system/test_system_with_obstacle_launch.py +++ b/nav2_system_tests/src/system/test_system_with_obstacle_launch.py @@ -142,7 +142,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/nav2_system_tests/src/system/test_wrong_init_pose_launch.py b/nav2_system_tests/src/system/test_wrong_init_pose_launch.py index c6fbe3f9548..31e1b8af411 100755 --- a/nav2_system_tests/src/system/test_wrong_init_pose_launch.py +++ b/nav2_system_tests/src/system/test_wrong_init_pose_launch.py @@ -128,7 +128,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/nav2_system_tests/src/system_failure/test_system_failure_launch.py b/nav2_system_tests/src/system_failure/test_system_failure_launch.py index 8adb3617977..0cbc76533e2 100755 --- a/nav2_system_tests/src/system_failure/test_system_failure_launch.py +++ b/nav2_system_tests/src/system_failure/test_system_failure_launch.py @@ -117,7 +117,6 @@ def generate_launch_description(): ), launch_arguments={ 'namespace': '', - 'use_namespace': 'False', 'map': map_yaml_file, 'use_sim_time': 'True', 'params_file': new_yaml, diff --git a/tools/planner_benchmarking/planning_benchmark_bringup.py b/tools/planner_benchmarking/planning_benchmark_bringup.py index 8ed9f400168..05c61a6284d 100644 --- a/tools/planner_benchmarking/planning_benchmark_bringup.py +++ b/tools/planner_benchmarking/planning_benchmark_bringup.py @@ -94,7 +94,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ), ] ) diff --git a/tools/smoother_benchmarking/smoother_benchmark_bringup.py b/tools/smoother_benchmarking/smoother_benchmark_bringup.py index dd1380f0b23..c19d1f2f703 100644 --- a/tools/smoother_benchmarking/smoother_benchmark_bringup.py +++ b/tools/smoother_benchmarking/smoother_benchmark_bringup.py @@ -107,7 +107,7 @@ def generate_launch_description(): PythonLaunchDescriptionSource( os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py') ), - launch_arguments={'namespace': '', 'use_namespace': 'False'}.items(), + launch_arguments={'namespace': ''}.items(), ) metrics_cmd = ExecuteProcess(