Skip to content

Commit

Permalink
Add dummy MoveIt test in order to keep it running long enough
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Jan 26, 2024
1 parent 9f9c39b commit 99bfdc9
Showing 1 changed file with 13 additions and 0 deletions.
13 changes: 13 additions & 0 deletions ur_moveit_config/test/startup_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,10 @@
from launch_ros.substitutions import FindPackagePrefix, FindPackageShare
from launch.event_handlers import OnProcessExit

import rclpy
import rclpy.node
from moveit_msgs.srv import GetPlanningScene

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.


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

def testCallingMoveItService(self):
# Dummy test to make sure MoveIt lives long enough...
rclpy.init()
node = rclpy.node.Node("ur_moveit_test")

cli = node.create_client(GetPlanningScene, "/get_planning_scene")
while not cli.wait_for_service(timeout_sec=120.0):
node.get_logger().info("service not available, waiting again...")


@launch_testing.post_shutdown_test()
class TestProcessExitCode(unittest.TestCase):
Expand Down

0 comments on commit 99bfdc9

Please sign in to comment.