mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
Cleanup unit tests
... and allow them to run via both, cmdline and pytest
This commit is contained in:
parent
6d376fb8b9
commit
8d2baf2739
@ -1,6 +1,5 @@
|
||||
#! /usr/bin/env python3
|
||||
|
||||
from __future__ import print_function
|
||||
import unittest
|
||||
import rostest
|
||||
from py_binding_tools import roscpp_init
|
||||
@ -9,6 +8,10 @@ from moveit.task_constructor import core, stages
|
||||
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"
|
||||
@ -113,5 +116,4 @@ class TestModifyPlanningScene(unittest.TestCase):
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
roscpp_init("test_mtc")
|
||||
rostest.rosrun("mtc", "mps", TestModifyPlanningScene)
|
||||
|
||||
@ -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):
|
||||
@ -55,5 +57,4 @@ class Test(unittest.TestCase):
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
roscpp_init("test_mtc")
|
||||
rostest.rosrun("mtc", "base", Test)
|
||||
|
||||
@ -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
|
||||
@ -12,11 +11,21 @@ from std_msgs.msg import Header
|
||||
|
||||
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()
|
||||
)
|
||||
|
||||
|
||||
@ -106,12 +115,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)
|
||||
@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"),
|
||||
@ -131,5 +140,4 @@ class TestTrampolines(unittest.TestCase):
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
roscpp_init("test_mtc")
|
||||
rostest.rosrun("mtc", "trampoline", TestTrampolines)
|
||||
|
||||
@ -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):
|
||||
@ -85,8 +84,7 @@ class TestPropertyMap(unittest.TestCase):
|
||||
|
||||
|
||||
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):
|
||||
@ -117,8 +115,7 @@ class TestModifyPlanningScene(unittest.TestCase):
|
||||
|
||||
|
||||
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):
|
||||
|
||||
Loading…
Reference in New Issue
Block a user