Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Port system tests in nav2_system_tests #4440

Merged
Show file tree
Hide file tree
Changes from 18 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 39 additions & 0 deletions nav2_simple_commander/nav2_simple_commander/utils.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
"""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}')
7 changes: 4 additions & 3 deletions nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down Expand Up @@ -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)
Expand All @@ -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()

Expand Down
9 changes: 9 additions & 0 deletions nav2_system_tests/models/cardboard_box.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<sdf version="1.6">
<model name='cardboard_box'>
<include>
<uri>
https://fuel.gazebosim.org/1.0/OpenRobotics/models/Cardboard box
</uri>
</include>
</model>
</sdf>
2 changes: 2 additions & 0 deletions nav2_system_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
<build_depend>launch_ros</build_depend>
<build_depend>launch_testing</build_depend>
<build_depend>nav2_planner</build_depend>
<build_depend>nav2_minimal_tb3_sim</build_depend>

<exec_depend>launch_ros</exec_depend>
<exec_depend>launch_testing</exec_depend>
Expand All @@ -48,6 +49,7 @@
<exec_depend>nav2_amcl</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>tf2_geometry_msgs</exec_depend>
<exec_depend>nav2_minimal_tb3_sim</exec_depend>
<!-- <exec_depend>gazebo_ros_pkgs</exec_depend> Remove/Replace after https://github.com/ros-navigation/navigation2/pull/3634 -->
<exec_depend>navigation2</exec_depend>
<exec_depend>lcov</exec_depend>
Expand Down
37 changes: 23 additions & 14 deletions nav2_system_tests/src/localization/test_localization_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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')
Expand All @@ -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(
Expand All @@ -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',
Expand All @@ -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,
Expand All @@ -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__':
Expand Down
24 changes: 4 additions & 20 deletions nav2_system_tests/src/system/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
46 changes: 46 additions & 0 deletions nav2_system_tests/src/system/nav2_system_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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

14 changes: 13 additions & 1 deletion nav2_system_tests/src/system/nav_to_pose_tester_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down Expand Up @@ -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):
Expand All @@ -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()

Expand Down
Loading
Loading