Skip to content

Commit

Permalink
Cleanup unit tests
Browse files Browse the repository at this point in the history
... and allow them to run via both, cmdline and pytest
  • Loading branch information
rhaschke committed Jul 12, 2024
1 parent 6d376fb commit 8d2baf2
Show file tree
Hide file tree
Showing 4 changed files with 30 additions and 22 deletions.
6 changes: 4 additions & 2 deletions core/python/test/rostest_mps.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#! /usr/bin/env python3

from __future__ import print_function
import unittest
import rostest
from py_binding_tools import roscpp_init
Expand All @@ -9,6 +8,10 @@
from geometry_msgs.msg import PoseStamped


def setUpModule():
roscpp_init("test_mtc")


def make_pose(x, y, z):
pose = PoseStamped()
pose.header.frame_id = "base_link"
Expand Down Expand Up @@ -113,5 +116,4 @@ def test_bw_remove_object(self):


if __name__ == "__main__":
roscpp_init("test_mtc")
rostest.rosrun("mtc", "mps", TestModifyPlanningScene)
9 changes: 5 additions & 4 deletions core/python/test/rostest_mtc.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,16 @@
#! /usr/bin/env python3

from __future__ import print_function
import unittest
import rostest
from py_binding_tools import roscpp_init
from moveit.task_constructor import core, stages
from geometry_msgs.msg import PoseStamped, Pose
from geometry_msgs.msg import PoseStamped
from geometry_msgs.msg import Vector3Stamped, Vector3
from std_msgs.msg import Header
import rospy


def setUpModule():
roscpp_init("test_mtc")


class Test(unittest.TestCase):
Expand Down Expand Up @@ -55,5 +57,4 @@ def createDisplacement(group, displacement):


if __name__ == "__main__":
roscpp_init("test_mtc")
rostest.rosrun("mtc", "base", Test)
24 changes: 16 additions & 8 deletions core/python/test/rostest_trampoline.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#! /usr/bin/env python3
# -*- coding: utf-8 -*-

from __future__ import print_function
import unittest
import rostest
from py_binding_tools import roscpp_init
Expand All @@ -12,11 +11,21 @@

PLANNING_GROUP = "manipulator"

pybind11_versions = [
k for k in __builtins__.__dict__.keys() if k.startswith("__pybind11_internals_v")
]

def setUpModule():
roscpp_init("test_mtc")


def pybind11_versions():
try:
keys = __builtins__.keys() # for use with pytest
except AttributeError:
keys = __builtins__.__dict__.keys() # use from cmdline
return [k for k in keys if k.startswith("__pybind11_internals_v")]


incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions: " + "\n- ".join(
pybind11_versions
pybind11_versions()
)


Expand Down Expand Up @@ -106,12 +115,12 @@ def plan(self, task, expected_solutions=None, wait=False):
if wait:
input("Waiting for any key (allows inspection in rviz)")

@unittest.skipIf(len(pybind11_versions) > 1, incompatible_pybind11_msg)
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
def test_generator(self):
task = self.create(PyGenerator())
self.plan(task, expected_solutions=PyGenerator.max_calls)

@unittest.skipIf(len(pybind11_versions) > 1, incompatible_pybind11_msg)
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
def test_monitoring_generator(self):
task = self.create(
stages.CurrentState("current"),
Expand All @@ -131,5 +140,4 @@ def test_propagator(self):


if __name__ == "__main__":
roscpp_init("test_mtc")
rostest.rosrun("mtc", "trampoline", TestTrampolines)
13 changes: 5 additions & 8 deletions core/python/test/test_mtc.py
Original file line number Diff line number Diff line change
@@ -1,16 +1,15 @@
#! /usr/bin/env python3
# -*- coding: utf-8 -*-

from __future__ import print_function
import unittest, sys
import sys
import unittest
from geometry_msgs.msg import Pose, PoseStamped, PointStamped, TwistStamped, Vector3Stamped
from moveit_msgs.msg import RobotState, Constraints, MotionPlanRequest
from moveit.task_constructor import core, stages


class TestPropertyMap(unittest.TestCase):
def __init__(self, *args, **kwargs):
super(TestPropertyMap, self).__init__(*args, **kwargs)
def setUp(self):
self.props = core.PropertyMap()

def _check(self, name, value):
Expand Down Expand Up @@ -85,8 +84,7 @@ def test_expose(self):


class TestModifyPlanningScene(unittest.TestCase):
def __init__(self, *args, **kwargs):
super(TestModifyPlanningScene, self).__init__(*args, **kwargs)
def setUp(self):
self.mps = stages.ModifyPlanningScene("mps")

def test_attach_objects_invalid_args(self):
Expand Down Expand Up @@ -117,8 +115,7 @@ def test_allow_collisions(self):


class TestStages(unittest.TestCase):
def __init__(self, *args, **kwargs):
super(TestStages, self).__init__(*args, **kwargs)
def setUp(self):
self.planner = core.PipelinePlanner()

def _check(self, stage, name, value):
Expand Down

0 comments on commit 8d2baf2

Please sign in to comment.