Skip some python tests on incompatible pybind11 versions

If MoveIt and MTC use incompatible versions of pybind11, the tests
will fail because MoveIt objects like RobotModel or PlanningScene
cannot be passed to MTC objects and vice versa.
This commit is contained in:
Robert Haschke 2021-06-10 18:16:48 +02:00
parent e3ee75dc16
commit 244c999514

View File

@ -12,6 +12,13 @@ from std_msgs.msg import Header
PLANNING_GROUP = "manipulator"
pybind11_versions = [
k for k in __builtins__.__dict__.keys() if k.startswith("__pybind11_internals_v")
]
incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions: " + "\n- ".join(
pybind11_versions
)
class PyGenerator(core.Generator):
""" Implements a custom 'Generator' stage."""
@ -99,10 +106,12 @@ class TestTrampolines(unittest.TestCase):
if wait:
input("Waiting for any key (allows inspection in rviz)")
@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)
def test_monitoring_generator(self):
task = self.create(
stages.CurrentState("current"),