diff --git a/nav2_bringup/bringup/README.md b/nav2_bringup/bringup/README.md index da9e64eb411..4e0b263bdcc 100644 --- a/nav2_bringup/bringup/README.md +++ b/nav2_bringup/bringup/README.md @@ -134,3 +134,9 @@ In RVIZ: * Make sure all transforms from odom are present. (odom->base_link->base_scan) * Localize the robot using “2D Pose Estimate” button. * Send the robot a goal pose using “2D Nav Goal” button. + +Note: +* nav2_gazebo_spawner pkg inside nav2_bringup directory is deleted. +* use of nav2_gazebo_spawner to spawn the robot in gazebo is not recommended any more. Instead use spawn_entity.py of gazebo_ros to spawn the robot. +* gazebo should be started with both libgazebo_ros_init.so and libgazebo_ros_factory.so to work correctly. +* spawn_entity node could not remap /tf and /tf_static to tf and tf_static in the launch file yet, used only for multi-robot situations. Instead it should be done as remapping argument /tf:=tf /tf_static:=tf_static under ros2 tag in each plugin which publishs transforms in the SDF file. It is essential to differentiate the tf's of the different robot. \ No newline at end of file diff --git a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py index a8b355595aa..81977af745e 100644 --- a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py +++ b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py @@ -13,7 +13,7 @@ # limitations under the License. """ -Example for spawing multiple robots in Gazebo. +Example for spawning multiple robots in Gazebo. This is an example on how to create a launch file for spawning multiple robots into Gazebo and launch multiple instances of the navigation stack, each controlling one robot. @@ -39,8 +39,10 @@ def generate_launch_description(): # Names and poses of the robots robots = [ - {'name': 'robot1', 'x_pose': 0.0, 'y_pose': 0.5, 'z_pose': 0.01}, - {'name': 'robot2', 'x_pose': 0.0, 'y_pose': -0.5, 'z_pose': 0.01}] + {'name': 'robot1', 'x_pose': 0.0, 'y_pose': 0.5, 'z_pose': 0.01, + 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0}, + {'name': 'robot2', 'x_pose': 0.0, 'y_pose': -0.5, 'z_pose': 0.01, + 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0}] # Simulation settings world = LaunchConfiguration('world') @@ -100,27 +102,12 @@ def generate_launch_description(): default_value='True', description='Whether to start RVIZ') - # Start Gazebo with plugin providing the robot spawing service + # Start Gazebo with plugin providing the robot spawning service start_gazebo_cmd = ExecuteProcess( cmd=[simulator, '--verbose', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so', world], output='screen') - # Define commands for spawing the robots into Gazebo - spawn_robots_cmds = [] - for robot in robots: - spawn_robots_cmds.append( - IncludeLaunchDescription( - PythonLaunchDescriptionSource(os.path.join(bringup_dir, 'launch', - 'spawn_tb3_launch.py')), - launch_arguments={ - 'x_pose': TextSubstitution(text=str(robot['x_pose'])), - 'y_pose': TextSubstitution(text=str(robot['y_pose'])), - 'z_pose': TextSubstitution(text=str(robot['z_pose'])), - 'robot_name': robot['name'], - 'turtlebot_type': TextSubstitution(text='waffle') - }.items())) - # Define commands for launching the navigation instances nav_instances_cmds = [] for robot in robots: @@ -149,7 +136,14 @@ def generate_launch_description(): 'use_rviz': 'False', 'use_simulator': 'False', 'headless': 'False', - 'use_robot_state_pub': use_robot_state_pub}.items()), + 'use_robot_state_pub': use_robot_state_pub, + 'x_pose': TextSubstitution(text=str(robot['x_pose'])), + 'y_pose': TextSubstitution(text=str(robot['y_pose'])), + 'z_pose': TextSubstitution(text=str(robot['z_pose'])), + 'roll': TextSubstitution(text=str(robot['roll'])), + 'pitch': TextSubstitution(text=str(robot['pitch'])), + 'yaw': TextSubstitution(text=str(robot['yaw'])), + 'robot_name':TextSubstitution(text=robot['name']), }.items()), LogInfo( condition=IfCondition(log_settings), @@ -190,9 +184,6 @@ def generate_launch_description(): # Add the actions to start gazebo, robots and simulations ld.add_action(start_gazebo_cmd) - for spawn_robot_cmd in spawn_robots_cmds: - ld.add_action(spawn_robot_cmd) - for simulation_instance_cmd in nav_instances_cmds: ld.add_action(simulation_instance_cmd) diff --git a/nav2_bringup/bringup/launch/spawn_tb3_launch.py b/nav2_bringup/bringup/launch/spawn_tb3_launch.py deleted file mode 100644 index af0d100372c..00000000000 --- a/nav2_bringup/bringup/launch/spawn_tb3_launch.py +++ /dev/null @@ -1,36 +0,0 @@ -# Copyright (c) 2018 Intel Corporation -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from launch import LaunchDescription - -import launch.actions -import launch_ros.actions - - -def generate_launch_description(): - - return LaunchDescription([ - # TODO(orduno) might not be necessary to have it's own package - launch_ros.actions.Node( - package='nav2_gazebo_spawner', - executable='nav2_gazebo_spawner', - output='screen', - arguments=[ - '--robot_name', launch.substitutions.LaunchConfiguration('robot_name'), - '--robot_namespace', launch.substitutions.LaunchConfiguration('robot_name'), - '--turtlebot_type', launch.substitutions.LaunchConfiguration('turtlebot_type'), - '-x', launch.substitutions.LaunchConfiguration('x_pose'), - '-y', launch.substitutions.LaunchConfiguration('y_pose'), - '-z', launch.substitutions.LaunchConfiguration('z_pose')]), - ]) diff --git a/nav2_bringup/bringup/launch/tb3_simulation_launch.py b/nav2_bringup/bringup/launch/tb3_simulation_launch.py index 675b6056980..ec982c3da28 100644 --- a/nav2_bringup/bringup/launch/tb3_simulation_launch.py +++ b/nav2_bringup/bringup/launch/tb3_simulation_launch.py @@ -47,6 +47,14 @@ def generate_launch_description(): use_rviz = LaunchConfiguration('use_rviz') headless = LaunchConfiguration('headless') world = LaunchConfiguration('world') + pose = {'x': LaunchConfiguration('x_pose', default='-2.00'), + 'y': LaunchConfiguration('y_pose', default='-0.50'), + 'z': LaunchConfiguration('z_pose', default='0.01'), + 'R': LaunchConfiguration('roll', default='0.00'), + 'P': LaunchConfiguration('pitch', default='0.00'), + 'Y': LaunchConfiguration('yaw', default='0.00')} + robot_name = LaunchConfiguration('robot_name') + robot_sdf = LaunchConfiguration('robot_sdf') # Map fully qualified names to relative ones so the node's namespace can be prepended. # In case of the transforms (tf), currently, there doesn't seem to be a better alternative @@ -125,9 +133,19 @@ def generate_launch_description(): # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/91 # default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'), # worlds/turtlebot3_worlds/waffle.model') - default_value=os.path.join(bringup_dir, 'worlds', 'waffle.model'), + default_value=os.path.join(bringup_dir, 'worlds', 'world_only.model'), description='Full path to world model file to load') + declare_robot_name_cmd = DeclareLaunchArgument( + 'robot_name', + default_value='turtlebot3_waffle', + description='name of the robot') + + declare_robot_sdf_cmd = DeclareLaunchArgument( + 'robot_sdf', + default_value=os.path.join(bringup_dir, 'worlds', 'waffle.model'), + description='Full path to robot sdf file to spawn the robot in gazebo') + # Specify the actions start_gazebo_server_cmd = ExecuteProcess( condition=IfCondition(use_simulator), @@ -141,6 +159,8 @@ def generate_launch_description(): cwd=[launch_dir], output='screen') urdf = os.path.join(bringup_dir, 'urdf', 'turtlebot3_waffle.urdf') + with open(urdf, 'r') as infp: + robot_description = infp.read() start_robot_state_publisher_cmd = Node( condition=IfCondition(use_robot_state_pub), @@ -149,16 +169,27 @@ def generate_launch_description(): name='robot_state_publisher', namespace=namespace, output='screen', - parameters=[{'use_sim_time': use_sim_time}], - remappings=remappings, - arguments=[urdf]) + parameters=[{'use_sim_time': use_sim_time, + 'robot_description': robot_description}], + remappings=remappings) + + start_gazebo_spawner_cmd = Node( + package='gazebo_ros', + executable='spawn_entity.py', + output='screen', + arguments=[ + '-entity', robot_name, + '-file', robot_sdf, + '-robot_namespace', namespace, + '-x', pose['x'], '-y', pose['y'], '-z', pose['z'], + '-R', pose['R'], '-P', pose['P'], '-Y', pose['Y']]) rviz_cmd = IncludeLaunchDescription( PythonLaunchDescriptionSource( os.path.join(launch_dir, 'rviz_launch.py')), condition=IfCondition(use_rviz), - launch_arguments={'namespace': '', - 'use_namespace': 'False', + launch_arguments={'namespace': namespace, + 'use_namespace': use_namespace, 'rviz_config': rviz_config_file}.items()) bringup_cmd = IncludeLaunchDescription( @@ -190,10 +221,13 @@ def generate_launch_description(): ld.add_action(declare_use_rviz_cmd) ld.add_action(declare_simulator_cmd) ld.add_action(declare_world_cmd) + ld.add_action(declare_robot_name_cmd) + ld.add_action(declare_robot_sdf_cmd) # Add any conditioned actions ld.add_action(start_gazebo_server_cmd) ld.add_action(start_gazebo_client_cmd) + ld.add_action(start_gazebo_spawner_cmd) # Add the actions to launch all of the navigation nodes ld.add_action(start_robot_state_publisher_cmd) diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml index f90053c032c..8620f2e6389 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml @@ -275,3 +275,13 @@ recoveries_server: robot_state_publisher: ros__parameters: use_sim_time: True + +waypoint_follower: + ros__parameters: + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: True + waypoint_pause_duration: 200 \ No newline at end of file diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml index dfb6ab4520c..498fb36eda6 100644 --- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml +++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml @@ -275,3 +275,13 @@ recoveries_server: robot_state_publisher: ros__parameters: use_sim_time: True + +waypoint_follower: + ros__parameters: + loop_rate: 20 + stop_on_failure: false + waypoint_task_executor_plugin: "wait_at_waypoint" + wait_at_waypoint: + plugin: "nav2_waypoint_follower::WaitAtWaypoint" + enabled: True + waypoint_pause_duration: 200 \ No newline at end of file diff --git a/nav2_bringup/bringup/rviz/nav2_namespaced_view.rviz b/nav2_bringup/bringup/rviz/nav2_namespaced_view.rviz index 4897dda6e4f..57b2d7bf741 100644 --- a/nav2_bringup/bringup/rviz/nav2_namespaced_view.rviz +++ b/nav2_bringup/bringup/rviz/nav2_namespaced_view.rviz @@ -304,6 +304,18 @@ Visualization Manager: 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 diff --git a/nav2_bringup/bringup/worlds/waffle.model b/nav2_bringup/bringup/worlds/waffle.model index f8a9fa09ad3..3eafe8bfc59 100644 --- a/nav2_bringup/bringup/worlds/waffle.model +++ b/nav2_bringup/bringup/worlds/waffle.model @@ -1,57 +1,7 @@ - - - - model://ground_plane - - - - model://sun - - - - false - - - - - 0.319654 -0.235002 9.29441 0 1.5138 0.009599 - orbit - perspective - - - - - 1000.0 - 0.001 - 1 - - - quick - 150 - 0 - 1.400000 - 1 - - - 0.00001 - 0.2 - 2000.000000 - 0.01000 - - - - - - 1 - - model://turtlebot3_world - - - - -2.0 -0.5 0.01 0.0 0.0 0.0 + 0.0 0.0 0.0 0.0 0.0 0.0 @@ -517,6 +467,9 @@ + + /tf:=tf 30 @@ -557,6 +510,4 @@ - - diff --git a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/__init__.py b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/__init__.py deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py b/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py deleted file mode 100644 index c7ef149c42f..00000000000 --- a/nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py +++ /dev/null @@ -1,116 +0,0 @@ -# Copyright (c) 2019 Intel Corporation -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -"""Script used to spawn a robot in a generic position.""" - -import argparse -import os -import xml.etree.ElementTree as ET - -from ament_index_python.packages import get_package_share_directory -from gazebo_msgs.srv import SpawnEntity -import rclpy - - -def main(): - # Get input arguments from user - parser = argparse.ArgumentParser(description='Spawn Robot into Gazebo with Nav2') - parser.add_argument('-n', '--robot_name', type=str, default='robot', - help='Name of the robot to spawn') - parser.add_argument('-ns', '--robot_namespace', type=str, default='robot', - help='ROS namespace to apply to the tf and plugins') - parser.add_argument('-x', type=float, default=0, - help='the x component of the initial position [meters]') - parser.add_argument('-y', type=float, default=0, - help='the y component of the initial position [meters]') - parser.add_argument('-z', type=float, default=0, - help='the z component of the initial position [meters]') - parser.add_argument('-k', '--timeout', type=float, default=10.0, - help="Seconds to wait. Block until the future is complete if negative. \ - Don't wait if 0.") - - group = parser.add_mutually_exclusive_group(required=True) - group.add_argument('-t', '--turtlebot_type', type=str, - choices=['waffle', 'burger']) - group.add_argument('-s', '--sdf', type=str, - help="the path to the robot's model file (sdf)") - - args, unknown = parser.parse_known_args() - - # Start node - rclpy.init() - node = rclpy.create_node('entity_spawner') - - node.get_logger().info( - 'Creating Service client to connect to `/spawn_entity`') - client = node.create_client(SpawnEntity, '/spawn_entity') - - node.get_logger().info('Connecting to `/spawn_entity` service...') - if not client.service_is_ready(): - client.wait_for_service() - node.get_logger().info('...connected!') - - node.get_logger().info('spawning `{}` on namespace `{}` at {}, {}, {}'.format( - args.robot_name, args.robot_namespace, args.x, args.y, args.z)) - - # Get path to the robot's sdf file - if args.turtlebot_type is not None: - sdf_file_path = os.path.join( - get_package_share_directory('turtlebot3_gazebo'), 'models', - f'turtlebot3_{args.turtlebot_type}', 'model.sdf') - else: - sdf_file_path = args.sdf - - # We need to remap the transform (/tf) topic so each robot has its own. - # We do this by adding `ROS argument entries` to the sdf file for - # each plugin broadcasting a transform. These argument entries provide the - # remapping rule, i.e. /tf -> //tf - tree = ET.parse(sdf_file_path) - root = tree.getroot() - for plugin in root.iter('plugin'): - if 'ros_diff_drive' in plugin.get('filename'): - # The only plugin we care for now is 'diff_drive' which is - # broadcasting a transform between`odom` and `base_footprint` - break - - if args.robot_namespace: - ros_params = plugin.find('ros') - ros_tf_remap = ET.SubElement(ros_params, 'remapping') - ros_tf_remap.text = f'/tf:=/{args.robot_namespace}/tf' - - # Set data for request - request = SpawnEntity.Request() - request.name = args.robot_name - request.xml = ET.tostring(root, encoding='unicode') - request.robot_namespace = args.robot_namespace - request.initial_pose.position.x = float(args.x) - request.initial_pose.position.y = float(args.y) - request.initial_pose.position.z = float(args.z) - - node.get_logger().info('Sending service request to `/spawn_entity`') - future = client.call_async(request) - rclpy.spin_until_future_complete(node, future, timeout_sec=args.timeout) - if future.result() is not None: - print(f'response: {future.result()!r}') - else: - raise RuntimeError( - f'exception while calling service: {future.exception()!r}') - - node.get_logger().info('Done! Shutting down node.') - node.destroy_node() - rclpy.shutdown() - - -if __name__ == '__main__': - main() diff --git a/nav2_bringup/nav2_gazebo_spawner/package.xml b/nav2_bringup/nav2_gazebo_spawner/package.xml deleted file mode 100644 index 6f2d88b0c50..00000000000 --- a/nav2_bringup/nav2_gazebo_spawner/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - nav2_gazebo_spawner - 1.0.0 - Package for spawning a robot model into Gazebo for Nav2 - lkumarbe - lkumarbe - Apache-2.0 - - rclpy - std_msgs - - ament_lint_auto - ament_lint_common - ament_copyright - python3-pytest - - - ament_python - - diff --git a/nav2_bringup/nav2_gazebo_spawner/resource/nav2_gazebo_spawner b/nav2_bringup/nav2_gazebo_spawner/resource/nav2_gazebo_spawner deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/nav2_bringup/nav2_gazebo_spawner/setup.cfg b/nav2_bringup/nav2_gazebo_spawner/setup.cfg deleted file mode 100644 index 3edf46fbb6f..00000000000 --- a/nav2_bringup/nav2_gazebo_spawner/setup.cfg +++ /dev/null @@ -1,6 +0,0 @@ -[develop] -script-dir=$base/lib/nav2_gazebo_spawner -[install] -install-scripts=$base/lib/nav2_gazebo_spawner -[tool:pytest] -junit_family=xunit2 diff --git a/nav2_bringup/nav2_gazebo_spawner/setup.py b/nav2_bringup/nav2_gazebo_spawner/setup.py deleted file mode 100644 index c71c075e742..00000000000 --- a/nav2_bringup/nav2_gazebo_spawner/setup.py +++ /dev/null @@ -1,22 +0,0 @@ -from setuptools import setup - -PACKAGE_NAME = 'nav2_gazebo_spawner' - -setup( - name=PACKAGE_NAME, - version='0.3.0', - packages=[PACKAGE_NAME], - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + PACKAGE_NAME]), - ('share/' + PACKAGE_NAME, ['package.xml']), - ], - install_requires=['setuptools'], - zip_safe=True, - tests_require=['pytest'], - entry_points={ - 'console_scripts': [ - 'nav2_gazebo_spawner = nav2_gazebo_spawner.nav2_gazebo_spawner:main', - ], - }, -) diff --git a/nav2_simple_commander/launch/warehouse.world b/nav2_simple_commander/launch/warehouse.world index 639965a031d..70cf78d99d4 100644 --- a/nav2_simple_commander/launch/warehouse.world +++ b/nav2_simple_commander/launch/warehouse.world @@ -637,6 +637,7 @@ + /tf:=tf 30 diff --git a/nav2_system_tests/models/turtlebot3_waffle/model-1_4.sdf b/nav2_system_tests/models/turtlebot3_waffle/model-1_4.sdf index c409a6e3e3e..63c52ae9198 100644 --- a/nav2_system_tests/models/turtlebot3_waffle/model-1_4.sdf +++ b/nav2_system_tests/models/turtlebot3_waffle/model-1_4.sdf @@ -477,6 +477,7 @@ + /tf:=tf 30 diff --git a/nav2_system_tests/models/turtlebot3_waffle/model.sdf b/nav2_system_tests/models/turtlebot3_waffle/model.sdf index fdf2b1fef07..42701b5ee5f 100644 --- a/nav2_system_tests/models/turtlebot3_waffle/model.sdf +++ b/nav2_system_tests/models/turtlebot3_waffle/model.sdf @@ -477,6 +477,7 @@ + /tf:=tf 30 diff --git a/nav2_system_tests/models/turtlebot3_waffle_depth_camera/model.sdf b/nav2_system_tests/models/turtlebot3_waffle_depth_camera/model.sdf index 0c7dfa22daf..bf47571cfda 100644 --- a/nav2_system_tests/models/turtlebot3_waffle_depth_camera/model.sdf +++ b/nav2_system_tests/models/turtlebot3_waffle_depth_camera/model.sdf @@ -410,6 +410,7 @@ + /tf:=tf 30 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 ff37ab2af22..81b1c2c880c 100755 --- a/nav2_system_tests/src/system/test_multi_robot_launch.py +++ b/nav2_system_tests/src/system/test_multi_robot_launch.py @@ -52,8 +52,8 @@ def generate_launch_description(): # Launch Gazebo server for simulation start_gazebo_cmd = ExecuteProcess( - cmd=['gzserver', '-s', 'libgazebo_ros_factory.so', - '--minimal_comms', world], + cmd=['gzserver', '-s', 'libgazebo_ros_init.so', + '-s', 'libgazebo_ros_factory.so', '--minimal_comms', world], output='screen') # Define commands for spawing the robots into Gazebo @@ -61,13 +61,13 @@ def generate_launch_description(): for robot in robots: spawn_robots_cmds.append( Node( - package='nav2_gazebo_spawner', - executable='nav2_gazebo_spawner', + package='gazebo_ros', + executable='spawn_entity.py', output='screen', arguments=[ - '--robot_name', TextSubstitution(text=robot['name']), - '--robot_namespace', TextSubstitution(text=robot['name']), - '--sdf', TextSubstitution(text=sdf), + '-entity', TextSubstitution(text=robot['name']), + '-robot_namespace', TextSubstitution(text=robot['name']), + '-file', TextSubstitution(text=sdf), '-x', TextSubstitution(text=str(robot['x_pose'])), '-y', TextSubstitution(text=str(robot['y_pose'])), '-z', TextSubstitution(text=str(robot['z_pose']))] diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo.world index 3a70206ab82..9a9e1bdbe84 100644 --- a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world +++ b/nav2_system_tests/worlds/turtlebot3_ros2_demo.world @@ -455,6 +455,7 @@ + /tf:=tf diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world index 5488938e0ee..b8c0d0d128d 100644 --- a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world +++ b/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world @@ -455,6 +455,7 @@ + /tf:=tf