Skip to content

Commit e9cfddc

Browse files
committed
improve tests
1 parent 58adfd3 commit e9cfddc

File tree

2 files changed

+56
-4
lines changed

2 files changed

+56
-4
lines changed

tests/test_DHRobot.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1086,8 +1086,8 @@ def test_cinertia(self):
10861086
[0.2795, -0.0703, 0.2767, 0.0000, 0.1713, 0.0000],
10871087
[0.0000, -0.9652, -0.0000, 0.1941, 0.0000, 0.5791]]
10881088

1089-
M0 = puma.cinertia(q)
1090-
M1 = puma.cinertia(np.c_[q, q].T)
1089+
M0 = puma.inertia_x(q)
1090+
M1 = puma.inertia_x(np.c_[q, q].T)
10911091

10921092
nt.assert_array_almost_equal(M0, Mr, decimal=4)
10931093
nt.assert_array_almost_equal(M1[0, :, :], Mr, decimal=4)
@@ -1195,7 +1195,6 @@ def test_jacob_dot(self):
11951195
q = puma.qr
11961196

11971197
j0 = puma.jacob_dot(q, q)
1198-
j1 = puma.jacob_dot()
11991198

12001199
res = [-0.0000, -1.0654, -0.3702, 2.4674, 0, 0]
12011200

tests/test_ERobot.py

Lines changed: 54 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@
1111
import spatialmath as sm
1212
from math import pi, sin, cos
1313

14-
1514
class TestERobot(unittest.TestCase):
1615

1716
def test_ets_init(self):
@@ -725,6 +724,60 @@ def test_invdyn(self):
725724
tau = robot.rne(q, z, [1, 1])
726725
nt.assert_array_almost_equal(tau, np.r_[d11 + d12, d21 + d22])
727726

727+
class TestERobot2(unittest.TestCase):
728+
def test_plot2(self):
729+
panda = rtb.models.DH.Panda()
730+
e = panda.plot2(panda.qr, block=False, name=True)
731+
e.close()
732+
733+
def test_plot2_traj(self):
734+
panda = rtb.models.DH.Panda()
735+
q = np.random.rand(3, 7)
736+
e = panda.plot2(block=False, q=q, dt=0)
737+
e.close()
738+
739+
def test_teach2_basic(self):
740+
l0 = rtb.DHLink(d=2)
741+
r0 = rtb.DHRobot([l0, l0])
742+
e = r0.teach2(block=False)
743+
e.step()
744+
e.close()
745+
746+
def test_teach2(self):
747+
panda = rtb.models.DH.Panda()
748+
e = panda.teach(panda.qr, block=False)
749+
e.close()
750+
751+
e2 = panda.teach2(block=False, q=panda.qr)
752+
e2.close()
753+
754+
def test_plot_with_vellipse2(self):
755+
panda = rtb.models.DH.Panda()
756+
e = panda.plot2(
757+
panda.qr, block=False, vellipse=True, limits=[1, 2, 1, 2])
758+
e.step()
759+
e.close()
760+
761+
def test_plot_with_fellipse2(self):
762+
panda = rtb.models.DH.Panda()
763+
e = panda.plot2(panda.qr, block=False, fellipse=True)
764+
e.close()
765+
766+
def test_plot_with_vellipse2_fail(self):
767+
panda = rtb.models.DH.Panda()
768+
panda.q = panda.qr
769+
770+
from roboticstoolbox.backends.PyPlot import PyPlot2
771+
e = PyPlot2()
772+
e.launch()
773+
e.add(panda.fellipse(
774+
q=panda.qr, centre=[0, 1]))
775+
776+
with self.assertRaises(ValueError):
777+
e.add(panda.fellipse(
778+
q=panda.qr, centre='ee', opt='rot'))
779+
780+
e.close()
728781

729782
if __name__ == '__main__': # pragma nocover
730783

0 commit comments

Comments
 (0)
pFad - Phonifier reborn

Pfad - The Proxy pFad of © 2024 Garber Painting. All rights reserved.

Note: This service is not intended for secure transactions such as banking, social media, email, or purchasing. Use at your own risk. We assume no liability whatsoever for broken pages.


Alternative Proxies:

Alternative Proxy

pFad Proxy

pFad v3 Proxy

pFad v4 Proxy