Skip to content

Commit e11433a

Browse files
committed
Re-enable flaky PSM test and increase timeout
1 parent 6487249 commit e11433a

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

moveit_ros/planning/planning_scene_monitor/CMakeLists.txt

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ if(BUILD_TESTING)
4949
test/current_state_monitor_tests.cpp)
5050
target_link_libraries(current_state_monitor_tests
5151
moveit_planning_scene_monitor)
52+
5253
ament_add_gmock(trajectory_monitor_tests test/trajectory_monitor_tests.cpp)
5354
target_link_libraries(trajectory_monitor_tests moveit_planning_scene_monitor)
5455

@@ -58,6 +59,7 @@ if(BUILD_TESTING)
5859
moveit_planning_scene_monitor)
5960
ament_target_dependencies(planning_scene_monitor_test moveit_core rclcpp
6061
moveit_msgs)
61-
add_ros_test(test/launch/planning_scene_monitor.test.py TIMEOUT 30 ARGS
62+
63+
add_ros_test(test/launch/planning_scene_monitor.test.py TIMEOUT 90 ARGS
6264
"test_binary_dir:=${CMAKE_CURRENT_BINARY_DIR}")
6365
endif()

moveit_ros/planning/planning_scene_monitor/test/launch/planning_scene_monitor.test.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -80,15 +80,13 @@ def generate_test_description():
8080

8181

8282
class TestGTestWaitForCompletion(unittest.TestCase):
83-
@unittest.skip("Flaky test on humble, see moveit2#2821")
8483
# Waits for test to complete, then waits a bit to make sure result files are generated
8584
def test_gtest_run_complete(self, psm_gtest):
8685
self.proc_info.assertWaitForShutdown(psm_gtest, timeout=4000.0)
8786

8887

8988
@launch_testing.post_shutdown_test()
9089
class TestGTestProcessPostShutdown(unittest.TestCase):
91-
@unittest.skip("Flaky test on humble, see moveit2#2821")
9290
# Checks if the test has been completed with acceptable exit codes (successful codes)
9391
def test_gtest_pass(self, proc_info, psm_gtest):
9492
launch_testing.asserts.assertExitCodes(proc_info, process=psm_gtest)

0 commit comments

Comments
 (0)