8000 Added tests for ET class · navrobot/robotics-toolbox-python@1f1dd1b · GitHub
[go: up one dir, main page]

Skip to content

Commit 1f1dd1b

Browse files
committed
Added tests for ET class
1 parent f7fc838 commit 1f1dd1b

File tree

1 file changed

+136
-0
lines changed

1 file changed

+136
-0
lines changed

test/test_et.py

Lines changed: 136 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,136 @@
1+
#!/usr/bin/env python3
2+
# -*- coding: utf-8 -*-
3+
"""
4+
Created on Fri May 1 14:04:04 2020
5+
@author: Jesse Haviland
6+
"""
7+
8+
import numpy.testing as nt
9+
import numpy as np
10+
import roboticstoolbox as rp
11+
import spatialmath.base as sm
12+
import unittest
13+
14+
15+
class TestET(unittest.TestCase):
16+
17+
def test_TRx(self):
18+
fl = 1.543
19+
20+
nt.assert_array_almost_equal(rp.ET.TRx(fl), sm.trotx(fl))
21+
nt.assert_array_almost_equal(rp.ET.TRx(-fl), sm.trotx(-fl))
22+
nt.assert_array_almost_equal(rp.ET.TRx(0), sm.trotx(0))
23+
24+
def test_TRy(self):
25+
fl = 1.543
26+
27+
nt.assert_array_almost_equal(rp.ET.TRy(fl), sm.troty(fl))
28+
nt.assert_array_almost_equal(rp.ET.TRy(-fl), sm.troty(-fl))
29+
nt.assert_array_almost_equal(rp.ET.TRy(0), sm.troty(0))
30+
31+
def test_TRz(self):
32+
fl = 1.543
33+
34+
nt.assert_array_almost_equal(rp.ET.TRz(fl), sm.trotz(fl))
35+
nt.assert_array_almost_equal(rp.ET.TRz(-fl), sm.trotz(-fl))
36+
nt.assert_array_almost_equal(rp.ET.TRz(0), sm.trotz(0))
37+
38+
def test_Ttx(self):
39+
fl = 1.543
40+
41+
nt.assert_array_almost_equal(rp.ET.Ttx(fl), sm.transl(fl, 0, 0))
42+
nt.assert_array_almost_equal(rp.ET.Ttx(-fl), sm.transl(-fl, 0, 0))
43+
nt.assert_array_almost_equal(rp.ET.Ttx(0), sm.transl(0, 0, 0))
44+
45+
def test_Tty(self):
46+
fl = 1.543
47+
48+
nt.assert_array_almost_equal(rp.ET.Tty(fl), sm.transl(0, fl, 0))
49+
nt.assert_array_almost_equal(rp.ET.Tty(-fl), sm.transl(0, -fl, 0))
50+
nt.assert_array_almost_equal(rp.ET.Tty(0), sm.transl(0, 0, 0))
51+
52+
def test_Ttz(self):
53+
fl = 1.543
54+
55+
nt.assert_array_almost_equal(rp.ET.Ttz(fl), sm.transl(0, 0, fl))
56+
nt.assert_array_almost_equal(rp.ET.Ttz(-fl), sm.transl(0, 0, -fl))
57+
nt.assert_array_almost_equal(rp.ET.Ttz(0), sm.transl(0, 0, 0))
58+
59+
def test_str(self):
60+
rx = rp.ET(rp.ET.TRx, 1.543)
61+
ry = rp.ET(rp.ET.TRy, 1.543)
62+
rz = rp.ET(rp.ET.TRz, 1.543)
63+
tx = rp.ET(rp.ET.Ttx, 1.543)
64+
ty = rp.ET(rp.ET.Tty, 1.543)
65+
tz = rp.ET(rp.ET.Ttz, 1.543)
66+
67+
self.assertEqual(str(rx), 'Rx(88.4074)')
68+
self.assertEqual(str(ry), 'Ry(88.4074)')
69+
self.assertEqual(str(rz), 'Rz(88.4074)')
70+
self.assertEqual(str(tx), 'tx(1.543)')
71+
self.assertEqual(str(ty), 'ty(1.543)')
72+
self.assertEqual(str(tz), 'tz(1.543)')
73+
self.assertEqual(str(rx), repr(rx))
74+
self.assertEqual(str(ry), repr(ry))
75+
self.assertEqual(str(rz), repr(rz))
76+
self.assertEqual(str(tx), repr(tx))
77+
self.assertEqual(str(ty), repr(ty))
78+
self.assertEqual(str(tz), repr(tz))
79+
80+
def test_str_q(self):
81+
rx = rp.ET(rp.ET.TRx, i=86)
82+
ry = rp.ET(rp.ET.TRy, i=86)
83+
rz = rp.ET(rp.ET.TRz, i=86)
84+
tx = rp.ET(rp.ET.Ttx, i=86)
85+
ty = rp.ET(rp.ET.Tty, i=86)
86+
tz = rp.ET(rp.ET.Ttz, i=86)
87+
88+
self.assertEqual(str(rx), 'Rx(q86)')
89+
self.assertEqual(str(ry), 'Ry(q86)')
90+
self.assertEqual(str(rz), 'Rz(q86)')
91+
self.assertEqual(str(tx), 'tx(q86)')
92+
self.assertEqual(str(ty), 'ty(q86)')
93+
self.assertEqual(str(tz), 'tz(q86)')
94+
self.assertEqual(str(rx), repr(rx))
95+
self.assertEqual(str(ry), repr(ry))
96+
self.assertEqual(str(rz), repr(rz))
97+
self.assertEqual(str(tx), repr(tx))
98+
self.assertEqual(str(ty), repr(ty))
99+
self.assertEqual(str(tz), repr(tz))
100+
101+
def test_T_real(self):
102+
fl = 1.543
103+
rx = rp.ET(rp.ET.TRx, fl)
104+
ry = rp.ET(rp.ET.TRy, fl)
105+
rz = rp.ET(rp.ET.TRz, fl)
106+
tx = rp.ET(rp.ET.Ttx, fl)
107+
ty = rp.ET(rp.ET.Tty, fl)
108+
tz = rp.ET(rp.ET.Ttz, fl)
109+
110+
nt.assert_array_almost_equal(rx.T(), sm.trotx(fl))
111+
nt.assert_array_almost_equal(ry.T(), sm.troty(fl))
112+
nt.assert_array_almost_equal(rz.T(), sm.trotz(fl))
113+
nt.assert_array_almost_equal(tx.T(), sm.transl(fl, 0, 0))
114+
nt.assert_array_almost_equal(ty.T(), sm.transl(0, fl, 0))
115+
nt.assert_array_almost_equal(tz.T(), sm.transl(0, 0, fl))
116+
117+
def test_T_real(self):
118+
fl = 1.543
119+
rx = rp.ET(rp.ET.TRx, i=86)
120+
ry = rp.ET(rp.ET.TRy, i=86)
121+
rz = rp.ET(rp.ET.TRz, i=86)
122+
tx = rp.ET(rp.ET.Ttx, i=86)
123+
ty = rp.ET(rp.ET.Tty, i=86)
124+
tz = rp.ET(rp.ET.Ttz, i=86)
125+
126+
nt.assert_array_almost_equal(rx.T(fl), sm.trotx(fl))
127+
nt.assert_array_almost_equal(ry.T(fl), sm.troty(fl))
128+
nt.assert_array_almost_equal(rz.T(fl), sm.trotz(fl))
129+
nt.assert_array_almost_equal(tx.T(fl), sm.transl(fl, 0, 0))
130+
nt.assert_array_almost_equal(ty.T(fl), sm.transl(0, fl, 0))
131+
nt.assert_array_almost_equal(tz.T(fl), sm.transl(0, 0, fl))
132+
133+
134+
if __name__ == '__main__':
135+
136+
unittest.main()

0 commit comments

Comments
 (0)
0