diff --git a/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py b/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py index bd001412d58..5c3780ea0b6 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', ) diff --git a/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py b/nav2_bringup/launch/unique_multi_tb3_simulation_launch.py index ae5551d179a..9428c9e8d02 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', ) diff --git a/nav2_bringup/rviz/nav2_namespaced_view.rviz b/nav2_bringup/rviz/nav2_namespaced_view.rviz index 4dcd23e24b4..0b2dc39ad65 100644 --- a/nav2_bringup/rviz/nav2_namespaced_view.rviz +++ b/nav2_bringup/rviz/nav2_namespaced_view.rviz @@ -56,7 +56,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 @@ -112,7 +112,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /scan + Value: scan Use Fixed Frame: true Use rainbow: true Value: true @@ -145,7 +145,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 @@ -160,7 +160,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /map + Value: map Use Timestamp: false Value: true - Alpha: 1 @@ -176,7 +176,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Best Effort - Value: /particle_cloud + Value: particle_cloud Value: true - Class: rviz_common/Group Displays: @@ -191,7 +191,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/costmap + Value: global_costmap/costmap Use Timestamp: false Value: true - Alpha: 1 @@ -219,7 +219,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /plan + Value: plan Value: true - Alpha: 1 Class: rviz_default_plugins/Polygon @@ -231,7 +231,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /global_costmap/published_footprint + Value: global_costmap/published_footprint Value: false Enabled: true Name: Global Planner @@ -248,7 +248,7 @@ Visualization Manager: Durability Policy: Transient Local History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/costmap + Value: local_costmap/costmap Use Timestamp: false Value: true - Alpha: 1 @@ -276,7 +276,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /local_plan + Value: local_plan Value: true - Class: rviz_default_plugins/MarkerArray Enabled: false @@ -288,7 +288,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 @@ -300,7 +300,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /local_costmap/published_footprint + Value: local_costmap/published_footprint Value: true Enabled: true Name: Controller @@ -314,7 +314,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /waypoints + Value: waypoints Value: true Enabled: true Global Options: @@ -334,7 +334,7 @@ Visualization Manager: Durability Policy: Volatile History Policy: Keep Last Reliability Policy: Reliable - Value: /initialpose + Value: initialpose - Class: nav2_rviz_plugins/GoalTool Transformation: Current: