Skip to content

Commit 99bfdc9

Browse files
committed
Add dummy MoveIt test in order to keep it running long enough
1 parent 9f9c39b commit 99bfdc9

File tree

1 file changed

+13
-0
lines changed

1 file changed

+13
-0
lines changed

ur_moveit_config/test/startup_test.py

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@
4444
from launch_ros.substitutions import FindPackagePrefix, FindPackageShare
4545
from launch.event_handlers import OnProcessExit
4646

47+
import rclpy
48+
import rclpy.node
49+
from moveit_msgs.srv import GetPlanningScene
50+
4751
TIMEOUT_WAIT_SERVICE_INITIAL = 120 # If we download the docker image simultaneously to the tests, it can take quite some time until the dashboard server is reachable and usable.
4852

4953

@@ -158,6 +162,15 @@ def test_read_stdout(self, proc_output):
158162
"Dashboard server connections are possible.", timeout=120, stream="stdout"
159163
)
160164

165+
def testCallingMoveItService(self):
166+
# Dummy test to make sure MoveIt lives long enough...
167+
rclpy.init()
168+
node = rclpy.node.Node("ur_moveit_test")
169+
170+
cli = node.create_client(GetPlanningScene, "/get_planning_scene")
171+
while not cli.wait_for_service(timeout_sec=120.0):
172+
node.get_logger().info("service not available, waiting again...")
173+
161174

162175
@launch_testing.post_shutdown_test()
163176
class TestProcessExitCode(unittest.TestCase):

0 commit comments

Comments
 (0)