diff --git a/nav2_system_tests/src/localization/CMakeLists.txt b/nav2_system_tests/src/localization/CMakeLists.txt index a4a76a327b..740d38f53e 100644 --- a/nav2_system_tests/src/localization/CMakeLists.txt +++ b/nav2_system_tests/src/localization/CMakeLists.txt @@ -9,7 +9,7 @@ ament_target_dependencies(test_localization_node ament_add_test(test_localization GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_localization_launch.py" - TIMEOUT 60 + TIMEOUT 180 ENV TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml TEST_EXECUTABLE=$ diff --git a/nav2_system_tests/src/recoveries/spin/CMakeLists.txt b/nav2_system_tests/src/recoveries/spin/CMakeLists.txt index ef01473fcb..34abacca01 100644 --- a/nav2_system_tests/src/recoveries/spin/CMakeLists.txt +++ b/nav2_system_tests/src/recoveries/spin/CMakeLists.txt @@ -13,7 +13,7 @@ ament_add_test(test_spin_recovery GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_spin_recovery_launch.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml TEST_EXECUTABLE=$ diff --git a/nav2_system_tests/src/recoveries/wait/CMakeLists.txt b/nav2_system_tests/src/recoveries/wait/CMakeLists.txt index b91374df43..06755020d5 100644 --- a/nav2_system_tests/src/recoveries/wait/CMakeLists.txt +++ b/nav2_system_tests/src/recoveries/wait/CMakeLists.txt @@ -13,7 +13,7 @@ ament_add_test(test_wait_recovery GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_wait_recovery_launch.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml TEST_EXECUTABLE=$ diff --git a/nav2_system_tests/src/system/CMakeLists.txt b/nav2_system_tests/src/system/CMakeLists.txt index 9784be1ac0..09017bfc6c 100644 --- a/nav2_system_tests/src/system/CMakeLists.txt +++ b/nav2_system_tests/src/system/CMakeLists.txt @@ -2,7 +2,7 @@ ament_add_test(test_bt_navigator GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml @@ -16,7 +16,7 @@ ament_add_test(test_bt_navigator_with_dijkstra GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml @@ -30,7 +30,7 @@ ament_add_test(test_dynamic_obstacle GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml @@ -44,7 +44,7 @@ ament_add_test(test_dynamic_obstacle # GENERATE_RESULT_FOR_RETURN_CODE_ZERO # COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_multi_robot_launch.py" # WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" -# TIMEOUT 120 +# TIMEOUT 180 # ENV # TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} # TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml diff --git a/nav2_system_tests/src/system/tester_node.py b/nav2_system_tests/src/system/tester_node.py index ca51089052..a66e2f7b89 100755 --- a/nav2_system_tests/src/system/tester_node.py +++ b/nav2_system_tests/src/system/tester_node.py @@ -203,22 +203,13 @@ def shutdown(self): except Exception as e: self.error_msg('Service call failed %r' % (e,)) - -def test_InitialPose(robot_tester, timeout, retries): - robot_tester.initial_pose_received = False - retry_count = 1 - while not robot_tester.initial_pose_received and retry_count <= retries: - retry_count += 1 - robot_tester.info_msg('Setting initial pose') - robot_tester.setInitialPose() - robot_tester.info_msg('Waiting for amcl_pose to be received') - rclpy.spin_once(robot_tester, timeout_sec=timeout) # wait for poseCallback - - if (robot_tester.initial_pose_received): - robot_tester.info_msg('test_InitialPose PASSED') - else: - robot_tester.info_msg('test_InitialPose FAILED') - return robot_tester.initial_pose_received + def wait_for_initial_pose(self): + self.initial_pose_received = False + while not self.initial_pose_received: + self.info_msg('Setting initial pose') + self.setInitialPose() + self.info_msg('Waiting for amcl_pose to be received') + rclpy.spin_once(self, timeout_sec=1) def test_RobotMovesToGoal(robot_tester): @@ -233,10 +224,8 @@ def run_all_tests(robot_tester): result = True if (result): robot_tester.wait_for_node_active('amcl') - result = test_InitialPose(robot_tester, timeout=1, retries=10) - if (result): + robot_tester.wait_for_initial_pose() robot_tester.wait_for_node_active('bt_navigator') - if (result): result = robot_tester.runNavigateAction() # TODO(orduno) Test sending the navigation request through the topic interface. diff --git a/nav2_system_tests/src/waypoint_follower/CMakeLists.txt b/nav2_system_tests/src/waypoint_follower/CMakeLists.txt index a8d005b175..2cd3c53a92 100644 --- a/nav2_system_tests/src/waypoint_follower/CMakeLists.txt +++ b/nav2_system_tests/src/waypoint_follower/CMakeLists.txt @@ -2,7 +2,7 @@ ament_add_test(test_waypoint_follower GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_case_py.launch" WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}" - TIMEOUT 100 + TIMEOUT 180 ENV TEST_DIR=${CMAKE_CURRENT_SOURCE_DIR} TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map_circular.yaml