diff --git a/nav2_simple_commander/nav2_simple_commander/utils.py b/nav2_simple_commander/nav2_simple_commander/utils.py
new file mode 100644
index 0000000000..d363901020
--- /dev/null
+++ b/nav2_simple_commander/nav2_simple_commander/utils.py
@@ -0,0 +1,55 @@
+#! /usr/bin/env python3
+# Copyright 2024 Open Navigation LLC
+# Copyright 2024 Stevedan Ogochukwu Omodolor Omodia
+#
+# 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.
+
+"""General utility functions."""
+
+import os
+import signal
+import subprocess
+
+
+def find_os_processes(name):
+ """Find all the processes that are running gz sim."""
+ ps_output = subprocess.check_output(['ps', 'aux'], text=True)
+ ps_lines = ps_output.split('\n')
+ gz_sim_processes = []
+ for line in ps_lines:
+ if name in line:
+ columns = line.split()
+ pid = columns[1]
+ command = ' '.join(columns[10:])
+ if command.startswith(name):
+ gz_sim_processes.append((pid, command))
+ return gz_sim_processes
+
+
+def kill_process(pid):
+ """Kill a process with a given PID."""
+ try:
+ os.kill(int(pid), signal.SIGKILL)
+ print(f'Successfully killed process with PID: {pid}')
+ except Exception as e:
+ print(f'Failed to kill process with PID: {pid}. Error: {e}')
+
+
+def kill_os_processes(name):
+ """Kill all processes that are running with name."""
+ processes = find_os_processes(name)
+ if processes:
+ for pid, _ in processes:
+ kill_process(pid)
+ else:
+ print(f'No processes found starting with {name}')
diff --git a/nav2_system_tests/CMakeLists.txt b/nav2_system_tests/CMakeLists.txt
index d94298da77..baa1256d52 100644
--- a/nav2_system_tests/CMakeLists.txt
+++ b/nav2_system_tests/CMakeLists.txt
@@ -28,6 +28,7 @@ find_package(navigation2)
find_package(angles REQUIRED)
find_package(behaviortree_cpp REQUIRED)
find_package(pluginlib REQUIRED)
+find_package(nav2_minimal_tb3_sim REQUIRED)
nav2_package()
@@ -113,9 +114,9 @@ if(BUILD_TESTING)
add_subdirectory(src/behavior_tree)
add_subdirectory(src/planning)
- # Uncomment after https://github.com/ros-navigation/navigation2/pull/3634
add_subdirectory(src/localization)
- # add_subdirectory(src/system)
+ add_subdirectory(src/system)
+ # Uncomment after https://github.com/ros-navigation/navigation2/pull/3634
# add_subdirectory(src/system_failure)
# add_subdirectory(src/updown)
# add_subdirectory(src/waypoint_follower)
@@ -127,7 +128,7 @@ if(BUILD_TESTING)
# add_subdirectory(src/behaviors/assisted_teleop)
# add_subdirectory(src/costmap_filters)
add_subdirectory(src/error_codes)
- install(DIRECTORY maps DESTINATION share/${PROJECT_NAME})
+ install(DIRECTORY maps models DESTINATION share/${PROJECT_NAME})
endif()
diff --git a/nav2_system_tests/models/cardboard_box.sdf b/nav2_system_tests/models/cardboard_box.sdf
new file mode 100644
index 0000000000..97a40603c2
--- /dev/null
+++ b/nav2_system_tests/models/cardboard_box.sdf
@@ -0,0 +1,9 @@
+
+
+
+
+ https://fuel.gazebosim.org/1.0/OpenRobotics/models/Cardboard box
+
+
+
+
\ No newline at end of file
diff --git a/nav2_system_tests/package.xml b/nav2_system_tests/package.xml
index 5fdbc230b7..2f3f45d191 100644
--- a/nav2_system_tests/package.xml
+++ b/nav2_system_tests/package.xml
@@ -30,6 +30,7 @@
launch_ros
launch_testing
nav2_planner
+ nav2_minimal_tb3_sim
launch_ros
launch_testing
@@ -48,6 +49,7 @@
nav2_amcl
std_msgs
tf2_geometry_msgs
+ nav2_minimal_tb3_sim
navigation2
lcov
diff --git a/nav2_system_tests/src/localization/test_localization_launch.py b/nav2_system_tests/src/localization/test_localization_launch.py
index aedca4fcf7..e56ca77986 100755
--- a/nav2_system_tests/src/localization/test_localization_launch.py
+++ b/nav2_system_tests/src/localization/test_localization_launch.py
@@ -15,6 +15,7 @@
# limitations under the License.
import os
+from pathlib import Path
import sys
from ament_index_python.packages import get_package_share_directory
@@ -26,6 +27,8 @@
import launch_ros.actions
from launch_testing.legacy import LaunchTestService
+from nav2_simple_commander.utils import kill_os_processes
+
def main(argv=sys.argv[1:]):
testExecutable = os.getenv('TEST_EXECUTABLE')
@@ -36,11 +39,19 @@ def main(argv=sys.argv[1:]):
world_sdf_xacro = os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro')
robot_sdf = os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf')
+ urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
+ with open(urdf, 'r') as infp:
+ robot_description = infp.read()
+
map_yaml_file = os.path.join(nav2_bringup_dir, 'maps', 'tb3_sandbox.yaml')
set_env_vars_resources = AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')
)
+ set_env_vars_resources2 = AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH',
+ str(Path(os.path.join(sim_dir)).parent.resolve())
+ )
start_gazebo_server = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
@@ -64,18 +75,14 @@ def main(argv=sys.argv[1:]):
'yaw': '0.0',
}.items(),
)
-
- link_footprint = launch_ros.actions.Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'],
- )
- footprint_scan = launch_ros.actions.Node(
- package='tf2_ros',
- executable='static_transform_publisher',
+ run_robot_state_publisher = launch_ros.actions.Node(
+ package='robot_state_publisher',
+ executable='robot_state_publisher',
+ name='robot_state_publisher',
output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'],
+ parameters=[
+ {'use_sim_time': True, 'robot_description': robot_description}
+ ],
)
run_map_server = launch_ros.actions.Node(
package='nav2_map_server',
@@ -97,10 +104,10 @@ def main(argv=sys.argv[1:]):
ld = LaunchDescription(
[
set_env_vars_resources,
+ set_env_vars_resources2,
start_gazebo_server,
spawn_robot,
- link_footprint,
- footprint_scan,
+ run_robot_state_publisher,
run_map_server,
run_amcl,
run_lifecycle_manager,
@@ -115,7 +122,9 @@ def main(argv=sys.argv[1:]):
lts.add_test_action(ld, test1_action)
ls = LaunchService(argv=argv)
ls.include_launch_description(ld)
- return lts.run(ls)
+ return_code = lts.run(ls)
+ kill_os_processes('gz sim')
+ return return_code
if __name__ == '__main__':
diff --git a/nav2_system_tests/src/system/CMakeLists.txt b/nav2_system_tests/src/system/CMakeLists.txt
index 39afa461c2..34ebf0e30e 100644
--- a/nav2_system_tests/src/system/CMakeLists.txt
+++ b/nav2_system_tests/src/system/CMakeLists.txt
@@ -5,9 +5,6 @@ ament_add_test(test_bt_navigator
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
TESTER=nav_to_pose_tester_node.py
ASTAR=True
@@ -22,9 +19,6 @@ ament_add_test(test_bt_navigator_with_wrong_init_pose
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
TESTER=nav_to_pose_tester_node.py
ASTAR=True
@@ -39,9 +33,6 @@ ament_add_test(test_bt_navigator_with_dijkstra
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
TESTER=nav_to_pose_tester_node.py
ASTAR=False
@@ -56,9 +47,6 @@ ament_add_test(test_bt_navigator_2
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
TESTER=nav_to_pose_tester_node.py
ASTAR=False
@@ -68,14 +56,12 @@ ament_add_test(test_bt_navigator_2
ament_add_test(test_dynamic_obstacle
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
- COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py"
+ COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_with_obstacle_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_obstacle.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
+ ADD_OBSTACLE=True
BT_NAVIGATOR_XML=navigate_to_pose_w_replanning_and_recovery.xml
TESTER=nav_to_pose_tester_node.py
ASTAR=False
@@ -85,14 +71,12 @@ ament_add_test(test_dynamic_obstacle
ament_add_test(test_nav_through_poses
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
- COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py"
+ COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_with_obstacle_launch.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
TIMEOUT 180
ENV
TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR}
- TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml
- TEST_WORLD=${PROJECT_SOURCE_DIR}/worlds/turtlebot3_ros2_demo_obstacle.world
- GAZEBO_MODEL_PATH=${PROJECT_SOURCE_DIR}/models
+ ADD_OBSTACLE=True
BT_NAVIGATOR_XML=navigate_through_poses_w_replanning_and_recovery.xml
TESTER=nav_through_poses_tester_node.py
ASTAR=False
diff --git a/nav2_system_tests/src/system/nav2_system_params.yaml b/nav2_system_tests/src/system/nav2_system_params.yaml
index a98d340f21..5ee29e6536 100644
--- a/nav2_system_tests/src/system/nav2_system_params.yaml
+++ b/nav2_system_tests/src/system/nav2_system_params.yaml
@@ -317,3 +317,49 @@ collision_monitor:
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
+
\ No newline at end of file
diff --git a/nav2_system_tests/src/system/nav_to_pose_tester_node.py b/nav2_system_tests/src/system/nav_to_pose_tester_node.py
index 8fd1bc6034..0eca068039 100755
--- a/nav2_system_tests/src/system/nav_to_pose_tester_node.py
+++ b/nav2_system_tests/src/system/nav_to_pose_tester_node.py
@@ -59,6 +59,7 @@ def __init__(self, initial_pose: Pose, goal_pose: Pose, namespace: str = ''):
self.initial_pose_received = False
self.initial_pose = initial_pose
self.goal_pose = goal_pose
+ self.set_initial_pose_timeout = 15
self.action_client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
def info_msg(self, msg: str):
@@ -212,11 +213,21 @@ def shutdown(self):
def wait_for_initial_pose(self):
self.initial_pose_received = False
+ # If the initial pose is not received within 100 seconds, return False
+ # this is because when setting a wrong initial pose, amcl_pose is not received
+ # and the test will hang indefinitely
+ start_time = time.time()
+ duration = 0
while not self.initial_pose_received:
self.info_msg('Setting initial pose')
self.setInitialPose()
self.info_msg('Waiting for amcl_pose to be received')
+ duration = time.time() - start_time
+ if duration > self.set_initial_pose_timeout:
+ self.error_msg('Timeout waiting for initial pose to be set')
+ return False
rclpy.spin_once(self, timeout_sec=1)
+ return True
def test_RobotMovesToGoal(robot_tester):
@@ -231,7 +242,8 @@ def run_all_tests(robot_tester):
result = True
if result:
robot_tester.wait_for_node_active('amcl')
- robot_tester.wait_for_initial_pose()
+ result = robot_tester.wait_for_initial_pose()
+ if result:
robot_tester.wait_for_node_active('bt_navigator')
result = robot_tester.runNavigateAction()
diff --git a/nav2_system_tests/src/system/test_system_launch.py b/nav2_system_tests/src/system/test_system_launch.py
index 2f0546d156..a644072ebb 100755
--- a/nav2_system_tests/src/system/test_system_launch.py
+++ b/nav2_system_tests/src/system/test_system_launch.py
@@ -16,6 +16,7 @@
# limitations under the License.
import os
+from pathlib import Path
import sys
from ament_index_python.packages import get_package_share_directory
@@ -23,6 +24,7 @@
from launch import LaunchDescription
from launch import LaunchService
from launch.actions import (
+ AppendEnvironmentVariable,
ExecuteProcess,
IncludeLaunchDescription,
SetEnvironmentVariable,
@@ -33,11 +35,22 @@
from launch_testing.legacy import LaunchTestService
from nav2_common.launch import RewrittenYaml
+from nav2_simple_commander.utils import kill_os_processes
def generate_launch_description():
- map_yaml_file = os.getenv('TEST_MAP')
- world = os.getenv('TEST_WORLD')
+ sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
+ nav2_bringup_dir = get_package_share_directory('nav2_bringup')
+ ros_gz_sim_dir = get_package_share_directory('ros_gz_sim')
+
+ world_sdf_xacro = os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro')
+ robot_sdf = os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf')
+
+ urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
+ with open(urdf, 'r') as infp:
+ robot_description = infp.read()
+
+ map_yaml_file = os.path.join(nav2_bringup_dir, 'maps', 'tb3_sandbox.yaml')
bt_navigator_xml = os.path.join(
get_package_share_directory('nav2_bt_navigator'),
@@ -45,8 +58,6 @@ def generate_launch_description():
os.getenv('BT_NAVIGATOR_XML'),
)
- bringup_dir = get_package_share_directory('nav2_bringup')
-
# Use local param file
launch_dir = os.path.dirname(os.path.realpath(__file__))
params_file = os.path.join(launch_dir, 'nav2_system_params.yaml')
@@ -79,34 +90,46 @@ def generate_launch_description():
[
SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'),
- # Launch gazebo server for simulation
- ExecuteProcess(
- cmd=[
- 'gzserver',
- '-s',
- 'libgazebo_ros_init.so',
- '--minimal_comms',
- world,
- ],
- output='screen',
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')
),
- # TODO(orduno) Launch the robot state publisher instead
- # using a local copy of TB3 urdf file
- Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'],
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH',
+ str(Path(os.path.join(sim_dir)).parent.resolve())
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(ros_gz_sim_dir, 'launch', 'gz_sim.launch.py')
+ ),
+ launch_arguments={'gz_args': ['-r -s ', world_sdf_xacro]}.items(),
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(sim_dir, 'launch', 'spawn_tb3.launch.py')
+ ),
+ launch_arguments={
+ 'use_sim_time': 'True',
+ 'robot_sdf': robot_sdf,
+ 'x_pose': '-2.0',
+ 'y_pose': '-0.5',
+ 'z_pose': '0.01',
+ 'roll': '0.0',
+ 'pitch': '0.0',
+ 'yaw': '0.0',
+ }.items(),
),
Node(
- package='tf2_ros',
- executable='static_transform_publisher',
+ package='robot_state_publisher',
+ executable='robot_state_publisher',
+ name='robot_state_publisher',
output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'],
+ parameters=[
+ {'use_sim_time': True, 'robot_description': robot_description}
+ ],
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
- os.path.join(bringup_dir, 'launch', 'bringup_launch.py')
+ os.path.join(nav2_bringup_dir, 'launch', 'bringup_launch.py')
),
launch_arguments={
'namespace': '',
@@ -145,7 +168,9 @@ def main(argv=sys.argv[1:]):
lts.add_test_action(ld, test1_action)
ls = LaunchService(argv=argv)
ls.include_launch_description(ld)
- return lts.run(ls)
+ return_code = lts.run(ls)
+ kill_os_processes('gz sim')
+ return return_code
if __name__ == '__main__':
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
new file mode 100755
index 0000000000..fb4468afef
--- /dev/null
+++ b/nav2_system_tests/src/system/test_system_with_obstacle_launch.py
@@ -0,0 +1,190 @@
+#!/usr/bin/env python3
+
+# Copyright (c) 2018 Intel Corporation
+# Copyright (c) 2020 Florian Gramss
+#
+# 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.
+
+import os
+from pathlib import Path
+import sys
+
+from ament_index_python.packages import get_package_share_directory
+
+from launch import LaunchDescription
+from launch import LaunchService
+from launch.actions import (
+ AppendEnvironmentVariable,
+ ExecuteProcess,
+ IncludeLaunchDescription,
+ SetEnvironmentVariable,
+)
+from launch.launch_context import LaunchContext
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch_ros.actions import Node
+from launch_testing.legacy import LaunchTestService
+
+from nav2_common.launch import RewrittenYaml
+from nav2_simple_commander.utils import kill_os_processes
+
+
+def generate_launch_description():
+ sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
+ nav2_bringup_dir = get_package_share_directory('nav2_bringup')
+ ros_gz_sim_dir = get_package_share_directory('ros_gz_sim')
+ nav2_system_tests_dir = get_package_share_directory('nav2_system_tests')
+
+ world_sdf_xacro = os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro')
+ robot_sdf = os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf')
+
+ urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
+ with open(urdf, 'r') as infp:
+ robot_description = infp.read()
+
+ map_yaml_file = os.path.join(nav2_bringup_dir, 'maps', 'tb3_sandbox.yaml')
+
+ bt_navigator_xml = os.path.join(
+ get_package_share_directory('nav2_bt_navigator'),
+ 'behavior_trees',
+ os.getenv('BT_NAVIGATOR_XML'),
+ )
+
+ # Use local param file
+ launch_dir = os.path.dirname(os.path.realpath(__file__))
+ params_file = os.path.join(launch_dir, 'nav2_system_params.yaml')
+
+ # Replace the default parameter values for testing special features
+ # without having multiple params_files inside the nav2 stack
+ context = LaunchContext()
+ param_substitutions = {}
+
+ if os.getenv('ASTAR') == 'True':
+ param_substitutions.update({'use_astar': 'True'})
+
+ param_substitutions.update(
+ {'planner_server.ros__parameters.GridBased.plugin': os.getenv('PLANNER')}
+ )
+ param_substitutions.update(
+ {'controller_server.ros__parameters.FollowPath.plugin': os.getenv('CONTROLLER')}
+ )
+
+ configured_params = RewrittenYaml(
+ source_file=params_file,
+ root_key='',
+ param_rewrites=param_substitutions,
+ convert_types=True,
+ )
+
+ new_yaml = configured_params.perform(context)
+
+ cardbox_sdf = os.path.join(nav2_system_tests_dir, 'models', 'cardboard_box.sdf')
+
+ return LaunchDescription(
+ [
+ SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
+ SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'),
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')
+ ),
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH',
+ str(Path(os.path.join(sim_dir)).parent.resolve())
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(ros_gz_sim_dir, 'launch', 'gz_sim.launch.py')
+ ),
+ launch_arguments={'gz_args': ['-r -s ', world_sdf_xacro]}.items(),
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(sim_dir, 'launch', 'spawn_tb3.launch.py')
+ ),
+ launch_arguments={
+ 'use_sim_time': 'True',
+ 'robot_sdf': robot_sdf,
+ 'x_pose': '-2.0',
+ 'y_pose': '-0.5',
+ 'z_pose': '0.01',
+ 'roll': '0.0',
+ 'pitch': '0.0',
+ 'yaw': '0.0',
+ }.items(),
+ ),
+ Node(
+ package='ros_gz_sim',
+ executable='create',
+ output='screen',
+ arguments=[
+ '-entity', 'cardboard_box',
+ '-file', cardbox_sdf,
+ '-x', '-1.0', '-y', '0.6', '-z', '0.15',
+ '-R', '0.0', '-P', '0.0', '-Y', '0.0',]
+ ),
+ Node(
+ package='robot_state_publisher',
+ executable='robot_state_publisher',
+ name='robot_state_publisher',
+ output='screen',
+ parameters=[
+ {'use_sim_time': True, 'robot_description': robot_description}
+ ],
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(nav2_bringup_dir, 'launch', 'bringup_launch.py')
+ ),
+ launch_arguments={
+ 'namespace': '',
+ 'use_namespace': 'False',
+ 'map': map_yaml_file,
+ 'use_sim_time': 'True',
+ 'params_file': new_yaml,
+ 'bt_xml_file': bt_navigator_xml,
+ 'use_composition': 'False',
+ 'autostart': 'True',
+ }.items(),
+ ),
+ ]
+ )
+
+
+def main(argv=sys.argv[1:]):
+ ld = generate_launch_description()
+
+ test1_action = ExecuteProcess(
+ cmd=[
+ os.path.join(os.getenv('TEST_DIR'), os.getenv('TESTER')),
+ '-r',
+ '-2.0',
+ '-0.5',
+ '0.0',
+ '2.0',
+ '-e',
+ 'True',
+ ],
+ name='tester_node',
+ output='screen',
+ )
+
+ lts = LaunchTestService()
+ lts.add_test_action(ld, test1_action)
+ ls = LaunchService(argv=argv)
+ ls.include_launch_description(ld)
+ return_code = lts.run(ls)
+ kill_os_processes('gz sim')
+ return return_code
+
+
+if __name__ == '__main__':
+ sys.exit(main())
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 f42d276fcc..b0e2322692 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
@@ -16,13 +16,14 @@
# limitations under the License.
import os
+from pathlib import Path
import sys
from ament_index_python.packages import get_package_share_directory
-
from launch import LaunchDescription
from launch import LaunchService
from launch.actions import (
+ AppendEnvironmentVariable,
ExecuteProcess,
IncludeLaunchDescription,
SetEnvironmentVariable,
@@ -33,11 +34,22 @@
from launch_testing.legacy import LaunchTestService
from nav2_common.launch import RewrittenYaml
+from nav2_simple_commander.utils import kill_os_processes
def generate_launch_description():
- map_yaml_file = os.getenv('TEST_MAP')
- world = os.getenv('TEST_WORLD')
+ sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
+ nav2_bringup_dir = get_package_share_directory('nav2_bringup')
+ ros_gz_sim_dir = get_package_share_directory('ros_gz_sim')
+
+ world_sdf_xacro = os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro')
+ robot_sdf = os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf')
+
+ urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
+ with open(urdf, 'r') as infp:
+ robot_description = infp.read()
+
+ map_yaml_file = os.path.join(nav2_bringup_dir, 'maps', 'tb3_sandbox.yaml')
bt_navigator_xml = os.path.join(
get_package_share_directory('nav2_bt_navigator'),
@@ -45,8 +57,9 @@ def generate_launch_description():
os.getenv('BT_NAVIGATOR_XML'),
)
- bringup_dir = get_package_share_directory('nav2_bringup')
- params_file = os.path.join(bringup_dir, 'params', 'nav2_params.yaml')
+ # Use local param file
+ launch_dir = os.path.dirname(os.path.realpath(__file__))
+ params_file = os.path.join(launch_dir, 'nav2_system_params.yaml')
# Replace the default parameter values for testing special features
# without having multiple params_files inside the nav2 stack
@@ -76,34 +89,46 @@ def generate_launch_description():
[
SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
SetEnvironmentVariable('RCUTILS_LOGGING_USE_STDOUT', '1'),
- # Launch gazebo server for simulation
- ExecuteProcess(
- cmd=[
- 'gzserver',
- '-s',
- 'libgazebo_ros_init.so',
- '--minimal_comms',
- world,
- ],
- output='screen',
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')
),
- # TODO(orduno) Launch the robot state publisher instead
- # using a local copy of TB3 urdf file
- Node(
- package='tf2_ros',
- executable='static_transform_publisher',
- output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link'],
+ AppendEnvironmentVariable(
+ 'GZ_SIM_RESOURCE_PATH',
+ str(Path(os.path.join(sim_dir)).parent.resolve())
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(ros_gz_sim_dir, 'launch', 'gz_sim.launch.py')
+ ),
+ launch_arguments={'gz_args': ['-r -s ', world_sdf_xacro]}.items(),
+ ),
+ IncludeLaunchDescription(
+ PythonLaunchDescriptionSource(
+ os.path.join(sim_dir, 'launch', 'spawn_tb3.launch.py')
+ ),
+ launch_arguments={
+ 'use_sim_time': 'True',
+ 'robot_sdf': robot_sdf,
+ 'x_pose': '-2.0',
+ 'y_pose': '-0.5',
+ 'z_pose': '0.01',
+ 'roll': '0.0',
+ 'pitch': '0.0',
+ 'yaw': '0.0',
+ }.items(),
),
Node(
- package='tf2_ros',
- executable='static_transform_publisher',
+ package='robot_state_publisher',
+ executable='robot_state_publisher',
+ name='robot_state_publisher',
output='screen',
- arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan'],
+ parameters=[
+ {'use_sim_time': True, 'robot_description': robot_description}
+ ],
),
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
- os.path.join(bringup_dir, 'launch', 'bringup_launch.py')
+ os.path.join(nav2_bringup_dir, 'launch', 'bringup_launch.py')
),
launch_arguments={
'namespace': '',
@@ -142,7 +167,9 @@ def main(argv=sys.argv[1:]):
lts.add_test_action(ld, test1_action)
ls = LaunchService(argv=argv)
ls.include_launch_description(ld)
- return lts.run(ls)
+ return_code = lts.run(ls)
+ kill_os_processes('gz sim')
+ return return_code
if __name__ == '__main__':
diff --git a/nav2_system_tests/urdf/common_properties.urdf b/nav2_system_tests/urdf/common_properties.urdf
deleted file mode 100644
index 9d457ea1d6..0000000000
--- a/nav2_system_tests/urdf/common_properties.urdf
+++ /dev/null
@@ -1,45 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/nav2_system_tests/urdf/turtlebot3_burger.urdf b/nav2_system_tests/urdf/turtlebot3_burger.urdf
deleted file mode 100644
index 90f34dbbb8..0000000000
--- a/nav2_system_tests/urdf/turtlebot3_burger.urdf
+++ /dev/null
@@ -1,155 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/nav2_system_tests/urdf/turtlebot3_waffle.urdf b/nav2_system_tests/urdf/turtlebot3_waffle.urdf
deleted file mode 100644
index 9a5bca1141..0000000000
--- a/nav2_system_tests/urdf/turtlebot3_waffle.urdf
+++ /dev/null
@@ -1,279 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo.world
deleted file mode 100644
index 9a9e1bdbe8..0000000000
--- a/nav2_system_tests/worlds/turtlebot3_ros2_demo.world
+++ /dev/null
@@ -1,497 +0,0 @@
-
-
-
-
-
- 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.064 0 0.048 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 1.0
-
-
-
- -0.064 0 0.048 0 0 0
-
-
- 0.265 0.265 0.089
-
-
-
-
-
- -0.064 0 0 0 0 0
-
-
- model://turtlebot3_waffle/meshes/waffle_base.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
- true
- 200
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
-
- false
-
-
- ~/out:=imu
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
-
- -0.064 0 0.121 0 0 0
-
-
- 0.0508
- 0.055
-
-
-
-
-
- -0.032 0 0.171 0 0 0
-
-
- model://turtlebot3_waffle/meshes/lds.dae
- 0.001 0.001 0.001
-
-
-
-
-
- true
- false
- -0.064 0 0.121 0 0 0
- 5
-
-
-
- 360
- 1.000000
- 0.000000
- 6.280000
-
-
-
- 0.120000
- 3.5
- 0.015000
-
-
- gaussian
- 0.0
- 0.01
-
-
-
-
-
- ~/out:=scan
-
- sensor_msgs/LaserScan
-
-
-
-
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/left_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 -0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/right_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
- -0.177 -0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- -0.177 0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- base_footprint
- base_link
- 0.0 0.0 0.010 0 0 0
-
-
-
- base_link
- wheel_left_link
- 0.0 0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_right_link
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- caster_back_right_link
-
-
-
- base_link
- caster_back_left_link
-
-
-
- base_link
- imu_link
- -0.032 0 0.068 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- base_scan
- -0.064 0 0.121 0 0 0
-
- 0 0 1
-
-
-
-
-
-
-
- /tf:=tf
-
-
-
- wheel_left_joint
- wheel_right_joint
-
-
- 0.287
- 0.066
-
-
- 20
- 1.0
-
-
- true
- true
- false
-
- odom
- base_footprint
-
-
-
-
-
-
- ~/out:=joint_states
-
- 250
- wheel_left_joint
- wheel_right_joint
-
-
-
-
-
-
-
diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world
deleted file mode 100644
index 94b72499a2..0000000000
--- a/nav2_system_tests/worlds/turtlebot3_ros2_demo_gps.world
+++ /dev/null
@@ -1,555 +0,0 @@
-
-
-
-
-
-
- EARTH_WGS84
- ENU
- 55.944831
- -3.186998
- 0.0
- 180.0
-
-
-
- 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
-
-
-
-
-
- -2.0 -0.5 0.01 0.0 0.0 0.0
-
-
-
-
-
-
- -0.064 0 0.048 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 1.0
-
-
-
- -0.064 0 0.048 0 0 0
-
-
- 0.265 0.265 0.089
-
-
-
-
-
- -0.064 0 0 0 0 0
-
-
- model://turtlebot3_waffle/meshes/waffle_base.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
- true
- 200
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
-
- false
-
-
- ~/out:=/imu/data
-
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
- true
- 1
- 0 0 0 0 0 0
-
-
-
-
- 0.0
- 0.1
-
-
-
-
- 0.0
- 0.0
-
-
-
-
-
-
- ~/out:=/gps/fix
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
-
- -0.064 0 0.121 0 0 0
-
-
- 0.0508
- 0.055
-
-
-
-
-
- -0.032 0 0.171 0 0 0
-
-
- model://turtlebot3_waffle/meshes/lds.dae
- 0.001 0.001 0.001
-
-
-
-
-
- true
- false
- -0.064 0 0.121 0 0 0
- 5
-
-
-
- 360
- 1.000000
- 0.000000
- 6.280000
-
-
-
- 0.120000
- 3.5
- 0.015000
-
-
- gaussian
- 0.0
- 0.01
-
-
-
-
-
- ~/out:=scan
-
- sensor_msgs/LaserScan
-
-
-
-
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/left_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 -0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/right_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
- -0.177 -0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- -0.177 0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- base_footprint
- base_link
- 0.0 0.0 0.010 0 0 0
-
-
-
- base_link
- wheel_left_link
- 0.0 0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_right_link
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- caster_back_right_link
-
-
-
- base_link
- caster_back_left_link
-
-
-
- base_link
- imu_link
- -0.032 0 0.068 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- gps_link
- -0.05 0 0.05 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- base_scan
- -0.064 0 0.121 0 0 0
-
- 0 0 1
-
-
-
-
-
-
-
- /tf:=tf
-
-
-
- wheel_left_joint
- wheel_right_joint
-
-
- 0.287
- 0.066
-
-
- 20
- 1.0
-
-
- true
- false
- false
-
- odom
- base_link
-
-
-
-
-
-
- ~/out:=joint_states
-
- 250
- wheel_left_joint
- wheel_right_joint
-
-
-
-
-
-
-
diff --git a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world b/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world
deleted file mode 100644
index b8c0d0d128..0000000000
--- a/nav2_system_tests/worlds/turtlebot3_ros2_demo_obstacle.world
+++ /dev/null
@@ -1,558 +0,0 @@
-
-
-
-
-
- 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.064 0 0.048 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 1.0
-
-
-
- -0.064 0 0.048 0 0 0
-
-
- 0.265 0.265 0.089
-
-
-
-
-
- -0.064 0 0 0 0 0
-
-
- model://turtlebot3_waffle/meshes/waffle_base.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
- true
- 200
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
-
- false
-
-
- ~/out:=imu
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
-
- -0.020 0 0.161 0 0 0
-
-
- 0.0508
- 0.055
-
-
-
-
-
- -0.064 0 0.121 0 0 0
-
-
- model://turtlebot3_waffle/meshes/lds.dae
- 0.001 0.001 0.001
-
-
-
-
-
- true
- false
- -0.064 0 0.121 0 0 0
- 5
-
-
-
- 360
- 1.000000
- 0.000000
- 6.280000
-
-
-
- 0.120000
- 3.5
- 0.015000
-
-
- gaussian
- 0.0
- 0.01
-
-
-
-
-
- ~/out:=scan
-
- sensor_msgs/LaserScan
-
-
-
-
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/left_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 -0.144 0.023 0 0 0
-
-
- model://turtlebot3_waffle/meshes/right_tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
- -0.177 -0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- -0.177 0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- base_footprint
- base_link
- 0.0 0.0 0.010 0 0 0
-
-
-
- base_link
- wheel_left_link
- 0.0 0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_right_link
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- caster_back_right_link
-
-
-
- base_link
- caster_back_left_link
-
-
-
- base_link
- imu_link
- -0.032 0 0.068 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- base_scan
- -0.064 0 0.121 0 0 0
-
- 0 0 1
-
-
-
-
-
-
-
- /tf:=tf
-
-
-
- wheel_left_joint
- wheel_right_joint
-
-
- 0.287
- 0.066
-
-
- 20
- 1.0
-
-
- true
- true
- false
-
- odom
- base_footprint
-
-
-
-
-
-
- ~/out:=joint_states
-
- 250
- wheel_left_joint
- wheel_right_joint
-
-
-
-
-
- -1.0 0.6 0.15 0 -0 0
-
-
-
- 20
-
- 0.0416667
- 0
- 0
- 0.0566667
- 0
- 0.0683333
-
- 0 0 0 0 -0 0
-
-
-
-
-
- 0.5 0.4 0.3
-
-
-
-
-
- 1
- 1
-
-
-
-
-
-
-
- 1e+07
- 1
- 0.001
- 0.1
-
-
-
-
- 10
-
-
-
- 0 0 -0.15 0 -0 0
-
-
- model://cardboard_box/meshes/cardboard_box.dae
- 1.25932 1.00745 0.755591
-
-
-
-
- 0
- 0
- 0
-
-
-
-
-
diff --git a/nav2_system_tests/worlds/world_only.model b/nav2_system_tests/worlds/world_only.model
deleted file mode 100644
index 4c45d4e2f9..0000000000
--- a/nav2_system_tests/worlds/world_only.model
+++ /dev/null
@@ -1,54 +0,0 @@
-
-
-
-
-
- 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
-
-
-
-
-