8000 robot tests · naren200/robotics-toolbox-python@538210e · GitHub
[go: up one dir, main page]

Skip to content

Commit 538210e

Browse files
committed
robot tests
1 parent ec278e3 commit 538210e

File tree

3 files changed

+147
-16
lines changed

3 files changed

+147
-16
lines changed

roboticstoolbox/models/URDF/PR2.py

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

3-
from roboticstoolbox.robot.ERobot import ERobot
3+
from roboticstoolbox.robot.ERobot import Robot
44
import numpy as np
55

66

7-
class PR2(ERobot):
7+
class PR2(Robot):
88
def __init__(self):
99

1010
links, name, urdf_string, urdf_filepath = self.URDF_read(

roboticstoolbox/robot/Robot.py

Lines changed: 13 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@
5454
from pathlib import PurePosixPath, Path
5555

5656
if TYPE_CHECKING:
57-
from matplotlib.cm import Color
57+
from matplotlib.cm import Color # pragma: nocover
5858
else:
5959
Color = None
6060

@@ -144,8 +144,6 @@ def __init__(
144144

145145
# Time to checkout the links for geometry information
146146
for link in self.links:
147-
if not isinstance(link, BaseLink):
148-
raise TypeError("links should all be Link subclass")
149147

150148
# Add link back to robot object
151149
link._robot = self
@@ -231,6 +229,9 @@ def _sort_links(
231229
# ------------------------------
232230
for k, link in enumerate(links):
233231

232+
if not isinstance(link, BaseLink):
233+
raise TypeError("links should all be Link subclass")
234+
234235
# If link has no name, give it one
235236
if link.name is None or link.name == "":
236237
link.name = f"link-{k}"
@@ -277,7 +278,7 @@ def _sort_links(
277278

278279
self._base_link = link
279280

280-
if self.base_link is None: # Pragma: nocover
281+
if not hasattr(self, "_base_link"):
281282
raise ValueError(
282283
"Invalid link configuration provided, must have a base link"
283284
)
@@ -353,7 +354,13 @@ def visit_link(link, jindex):
353354
# visit all links in DFS order
354355
self.dfs_links(self.base_link, lambda link: visit_link(link, jindex))
355356

356-
elif all([link.jindex is not None for link in links if link.isjoint]):
357+
elif all(
358+
[
359+
link.jindex is not None and not link.ets._auto_jindex
360+
for link in links
361+
if link.isjoint
362+
]
363+
):
357364
# Jindex set on all, check they are unique and contiguous
358365
if check_jindex:
359366
jset = set(range(n))
@@ -1025,7 +1032,7 @@ def qlim(self) -> NDArray:
10251032
v = link.qlim
10261033
else:
10271034
# Fixed link
1028-
continue
1035+
continue # pragma: nocover
10291036

10301037
limits[:, j] = v
10311038
j += 1
@@ -2226,14 +2233,6 @@ def URDF(cls, file_path: str, gripper: Union[int, str, None] = None):
22262233
urdf_filepath=urdf_filepath,
22272234
)
22282235

2229-
@property
2230-
def urdf_string(self):
2231-
return self._urdf_string
2232-
2233-
@property
2234-
def urdf_filepath(self):
2235-
return self._urdf_filepath
2236-
22372236
# --------------------------------------------------------------------- #
22382237
# --------- Utility Methods ------------------------------------------- #
22392238
# --------------------------------------------------------------------- #

tests/test_BaseRobot.py

Lines changed: 132 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,85 @@ def test_init4(self):
6363
self.assertEqual(robot.manufacturer, "I made it")
6464
self.assertEqual(robot.comment, "other stuff")
6565

66+
def test_init5(self):
67+
68+
base = SE3.Trans(0, 0, 0.1).A
69+
ets = ETS(rtb.ET.Rz())
70+
robot = Robot(ets, base=base, tool=base)
71+
nt.assert_almost_equal(robot.base.A, base)
72+
nt.assert_almost_equal(robot.tool.A, base)
73+
74+
def test_init6(self):
75+
76+
base = SE3.Trans(0, 0, 0.1)
77+
ets = ETS(rtb.ET.Rz())
78+
robot = Robot(ets, base=base, tool=base)
79+
nt.assert_almost_equal(robot.base.A, base.A)
80+
nt.assert_almost_equal(robot.tool.A, base.A)
81+
82+
def test_init7(self):
83+
84+
keywords = 2
85+
ets = ETS(rtb.ET.Rz())
86+
87+
with self.assertRaises(TypeError):
88+
Robot(ets, keywords=keywords) # type: ignore
89+
90+
def test_init8(self):
91+
92+
links = [2, 3, 4, 5]
93+
94+
with self.assertRaises(TypeError):
95+
BaseRobot(links=links) # type: ignore
96+
97+
def test_init9(self):
98+
99+
robot = rtb.models.Panda()
100+
robot2 = rtb.models.PR2()
101+
102+
self.assertTrue(robot2._hasdynamics)
103+
self.assertTrue(robot._hasgeometry)
104+
self.assertTrue(robot._hascollision)
105+
106+
def test_init10(self):
107+
108+
links = [Link(name="link1"), Link(name="link1"), Link(name="link1")]
109+
110+
with self.assertRaises(ValueError):
111+
Robot(links)
112+
113+
def test_init11(self):
114+
115+
l1 = Link(parent="l3")
116+
l2 = Link(parent=l1)
117+
l3 = Link(parent=l2, name="l3")
118+
119+
links = [l1, l2, l3]
120+
121+
with self.assertRaises(ValueError):
122+
Robot(links)
123+
124+
def test_init12(self):
125+
126+
l1 = Link(jindex=1, ets=rtb.ET.Rz())
127+
l2 = Link(jindex=2, parent=l1, ets=rtb.ET.Rz())
128+
l3 = Link(parent=l2, ets=rtb.ET.Rz())
129+
130+
links = [l1, l2, l3]
131+
132+
with self.assertRaises(ValueError):
133+
Robot(links)
134+
135+
def test_iter(self):
136+
robot = rtb.models.Panda()
137+
for link in robot:
138+
self.assertIsInstance(link, Link)
139+
140+
def test_get(self):
141+
panda = rtb.models.ETS.Panda()
142+
self.assertIsInstance(panda[1], Link)
143+
self.assertIsInstance(panda["link0"], Link)
144+
66145
def test_init_ets(self):
67146

68147
ets = (
@@ -278,6 +357,59 @@ def test_manuf(self):
278357

279358
self.assertIsInstance(panda.manufacturer, str)
280359

360+
def test_str(self):
361+
panda = rtb.models.Panda()
362+
pr2 = rtb.models.PR2()
363+
self.assertIsInstance(str(panda), str)
364+
self.assertIsInstance(str(pr2), str)
365+
self.assertIsInstance(repr(panda), str)
366+
self.assertIsInstance(repr(pr2), str)
367+
368+
def test_nlinks(self):
369+
panda = rtb.models.Panda()
370+
self.assertEqual(panda.nlinks, 12)
371+
372+
def test_configs(self):
373+
panda = rtb.models.Panda()
374+
configs = panda.configs
375+
376+
nt.assert_equal(configs["qr"], panda.qr)
377+
nt.assert_equal(configs["qz"], panda.qz)
378+
379+
def test_keywords(self):
380+
panda = Robot(
381+
ETS([ET.Rz(qlim=[-1, 1]), ET.tz(qlim=[-1, 1]), ET.SE3(SE3.Trans(1, 2, 3))]),
382+
keywords=["test"],
383+
)
384+
self.assertEqual(panda.keywords, ["test"])
385+
self.assertFalse(panda.symbolic)
386+
self.assertFalse(panda.hasdynamics)
387+
self.assertFalse(panda.hasgeometry)
388+
self.assertFalse(panda.hascollision)
389+
self.assertEqual(panda.default_backend, None)
390+
panda.default_backend = "Swift"
391+
392+
self.assertEqual(panda.qlim[0, 0], -1.0)
393+
394+
def test_qlim(self):
395+
panda = Robot(ETS([ET.Rz(qlim=[-1, 1]), ET.tz()]), keywords=["test"])
396+
397+
with self.assertRaises(ValueError):
398+
panda.qlim
399+
400+
def test_joint_types(self):
401+
panda = Robot(
402+
ETS([ET.Rz(qlim=[-1, 1]), ET.tz(qlim=[-1, 1]), ET.SE3(SE3.Trans(1, 2, 3))]),
403+
)
404+
405+
self.assertTrue(panda.prismaticjoints[1])
406+
self.assertTrue(panda.revolutejoints[0])
407+
408+
def test_urdf_string(self):
409+
panda = rtb.models.Panda()
410+
self.assertIsInstance(panda.urdf_string, str)
411+
self.assertIsInstance(panda.urdf_filepath, str)
412+
281413
# def test_yoshi(self):
282414
# puma = rtb.models.Puma560()
283415
# q = puma.qn

0 commit comments

Comments
 (0)
0