Skip to content

Commit 8d2baf2

Browse files
committed
Cleanup unit tests
... and allow them to run via both, cmdline and pytest
1 parent 6d376fb commit 8d2baf2

File tree

4 files changed

+30
-22
lines changed

4 files changed

+30
-22
lines changed

core/python/test/rostest_mps.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,5 @@
11
#! /usr/bin/env python3
22

3-
from __future__ import print_function
43
import unittest
54
import rostest
65
from py_binding_tools import roscpp_init
@@ -9,6 +8,10 @@
98
from geometry_msgs.msg import PoseStamped
109

1110

11+
def setUpModule():
12+
roscpp_init("test_mtc")
13+
14+
1215
def make_pose(x, y, z):
1316
pose = PoseStamped()
1417
pose.header.frame_id = "base_link"
@@ -113,5 +116,4 @@ def test_bw_remove_object(self):
113116

114117

115118
if __name__ == "__main__":
116-
roscpp_init("test_mtc")
117119
rostest.rosrun("mtc", "mps", TestModifyPlanningScene)

core/python/test/rostest_mtc.py

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,16 @@
11
#! /usr/bin/env python3
22

3-
from __future__ import print_function
43
import unittest
54
import rostest
65
from py_binding_tools import roscpp_init
76
from moveit.task_constructor import core, stages
8-
from geometry_msgs.msg import PoseStamped, Pose
7+
from geometry_msgs.msg import PoseStamped
98
from geometry_msgs.msg import Vector3Stamped, Vector3
109
from std_msgs.msg import Header
11-
import rospy
10+
11+
12+
def setUpModule():
13+
roscpp_init("test_mtc")
1214

1315

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

5658

5759
if __name__ == "__main__":
58-
roscpp_init("test_mtc")
5960
rostest.rosrun("mtc", "base", Test)

core/python/test/rostest_trampoline.py

Lines changed: 16 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,6 @@
11
#! /usr/bin/env python3
22
# -*- coding: utf-8 -*-
33

4-
from __future__ import print_function
54
import unittest
65
import rostest
76
from py_binding_tools import roscpp_init
@@ -12,11 +11,21 @@
1211

1312
PLANNING_GROUP = "manipulator"
1413

15-
pybind11_versions = [
16-
k for k in __builtins__.__dict__.keys() if k.startswith("__pybind11_internals_v")
17-
]
14+
15+
def setUpModule():
16+
roscpp_init("test_mtc")
17+
18+
19+
def pybind11_versions():
20+
try:
21+
keys = __builtins__.keys() # for use with pytest
22+
except AttributeError:
23+
keys = __builtins__.__dict__.keys() # use from cmdline
24+
return [k for k in keys if k.startswith("__pybind11_internals_v")]
25+
26+
1827
incompatible_pybind11_msg = "MoveIt and MTC use incompatible pybind11 versions: " + "\n- ".join(
19-
pybind11_versions
28+
pybind11_versions()
2029
)
2130

2231

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

109-
@unittest.skipIf(len(pybind11_versions) > 1, incompatible_pybind11_msg)
118+
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
110119
def test_generator(self):
111120
task = self.create(PyGenerator())
112121
self.plan(task, expected_solutions=PyGenerator.max_calls)
113122

114-
@unittest.skipIf(len(pybind11_versions) > 1, incompatible_pybind11_msg)
123+
@unittest.skipIf(len(pybind11_versions()) > 1, incompatible_pybind11_msg)
115124
def test_monitoring_generator(self):
116125
task = self.create(
117126
stages.CurrentState("current"),
@@ -131,5 +140,4 @@ def test_propagator(self):
131140

132141

133142
if __name__ == "__main__":
134-
roscpp_init("test_mtc")
135143
rostest.rosrun("mtc", "trampoline", TestTrampolines)

core/python/test/test_mtc.py

Lines changed: 5 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,15 @@
11
#! /usr/bin/env python3
22
# -*- coding: utf-8 -*-
33

4-
from __future__ import print_function
5-
import unittest, sys
4+
import sys
5+
import unittest
66
from geometry_msgs.msg import Pose, PoseStamped, PointStamped, TwistStamped, Vector3Stamped
77
from moveit_msgs.msg import RobotState, Constraints, MotionPlanRequest
88
from moveit.task_constructor import core, stages
99

1010

1111
class TestPropertyMap(unittest.TestCase):
12-
def __init__(self, *args, **kwargs):
13-
super(TestPropertyMap, self).__init__(*args, **kwargs)
12+
def setUp(self):
1413
self.props = core.PropertyMap()
1514

1615
def _check(self, name, value):
@@ -85,8 +84,7 @@ def test_expose(self):
8584

8685

8786
class TestModifyPlanningScene(unittest.TestCase):
88-
def __init__(self, *args, **kwargs):
89-
super(TestModifyPlanningScene, self).__init__(*args, **kwargs)
87+
def setUp(self):
9088
self.mps = stages.ModifyPlanningScene("mps")
9189

9290
def test_attach_objects_invalid_args(self):
@@ -117,8 +115,7 @@ def test_allow_collisions(self):
117115

118116

119117
class TestStages(unittest.TestCase):
120-
def __init__(self, *args, **kwargs):
121-
super(TestStages, self).__init__(*args, **kwargs)
118+
def setUp(self):
122119
self.planner = core.PipelinePlanner()
123120

124121
def _check(self, stage, name, value):

0 commit comments

Comments
 (0)