Skip to content

Commit fc66f61

Browse files
committed
remote test skips, migrate to new style bdsim unit test support
1 parent c075f91 commit fc66f61

File tree

2 files changed

+66
-72
lines changed

2 files changed

+66
-72
lines changed

roboticstoolbox/blocks/mobile.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -288,7 +288,7 @@ class VehiclePlot(GraphicsBlock):
288288

289289
# TODO add ability to render an image instead of an outline
290290

291-
def __init__(self, animation=None, path=None, labels=['X', 'Y'], square=True, init=None, scale=True, **blockargs):
291+
def __init__(self, animation=None, path=None, labels=['X', 'Y'], square=True, init=None, scale="auto", **blockargs):
292292
"""
293293
Create a vehicle animation
294294

roboticstoolbox/blocks/test_blocks.py

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

33
from bdsim.blocks.linalg import *
4+
from bdsim import BDSim
45

56
import unittest
67
import numpy.testing as nt
@@ -22,7 +23,7 @@ def test_fkine(self):
2223
T = robot.fkine(q)
2324

2425
block = FKine(robot)
25-
nt.assert_array_almost_equal(block._output(q)[0], T)
26+
nt.assert_array_almost_equal(block.T_output(q)[0], T)
2627

2728
def test_ikine(self):
2829

@@ -31,7 +32,7 @@ def test_ikine(self):
3132
T = robot.fkine(q)
3233
block = IKine(robot, seed=0)
3334

34-
q_ik = block._output(T)[0] # get IK from block
35+
q_ik = block.T_output(T)[0] # get IK from block
3536
nt.assert_array_almost_equal(robot.fkine(q_ik), T) # test it's FK is correct
3637

3738
def test_jacobian(self):
@@ -41,45 +42,44 @@ def test_jacobian(self):
4142

4243
J = robot.jacob0(q)
4344
block = Jacobian(robot)
44-
nt.assert_array_almost_equal(block._output(q)[0], J)
45+
nt.assert_array_almost_equal(block.T_output(q)[0], J)
4546

4647
J = robot.jacobe(q)
4748
block = Jacobian(robot, frame="e")
48-
nt.assert_array_almost_equal(block._output(q)[0], J)
49+
nt.assert_array_almost_equal(block.T_output(q)[0], J)
4950

5051
J = robot.jacob0(q)
5152
block = Jacobian(robot, pinv=True)
52-
nt.assert_array_almost_equal(block._output(q)[0], np.linalg.pinv(J))
53+
nt.assert_array_almost_equal(block.T_output(q)[0], np.linalg.pinv(J))
5354

5455
def test_gravload(self):
5556

5657
robot = rtb.models.DH.Puma560()
5758
q = robot.configs["qn"]
5859

5960
block = Gravload(robot)
60-
nt.assert_array_almost_equal(block._output(q)[0], robot.gravload(q))
61+
nt.assert_array_almost_equal(block.T_output(q)[0], robot.gravload(q))
6162

6263
def test_gravload_x(self):
6364
robot = rtb.models.DH.Puma560()
6465
q = robot.configs["qn"]
6566

6667
block = Gravload_X(robot)
67-
nt.assert_array_almost_equal(block._output(q)[0], robot.gravload_x(q))
68+
nt.assert_array_almost_equal(block.T_output(q)[0], robot.gravload_x(q))
6869

6970
def test_inertia(self):
7071
robot = rtb.models.DH.Puma560()
7172
q = robot.configs["qn"]
7273

7374
block = Inertia(robot)
74-
nt.assert_array_almost_equal(block._output(q)[0], robot.inertia(q))
75+
nt.assert_array_almost_equal(block.T_output(q)[0], robot.inertia(q))
7576

7677
def test_inertia_x(self):
7778
robot = rtb.models.DH.Puma560()
7879
q = robot.configs["qn"]
7980

8081
block = Inertia_X(robot)
81-
nt.assert_array_almost_equal(block._output(q)[0], robot.inertia_x(q))
82-
82+
nt.assert_array_almost_equal(block.T_output(q)[0], robot.inertia_x(q))
8383

8484
def test_idyn(self):
8585
robot = rtb.models.DH.Puma560()
@@ -88,12 +88,12 @@ def test_idyn(self):
8888
block = IDyn(robot)
8989
qd = [0.1, 0.1, 0.1, 0.2, 0.2, 0.3]
9090
qdd = [0.1, 0.1, 0.1, 0.2, 0.2, 0.3]
91-
nt.assert_array_almost_equal(block._output(q, qd, qdd)[0], robot.rne(q, qd, qdd))
91+
nt.assert_array_almost_equal(block.T_output(q, qd, qdd)[0], robot.rne(q, qd, qdd))
9292

9393
block = IDyn(robot, gravity=[0, 0, 0])
9494
qd = [0.1, 0.1, 0.1, 0.2, 0.2, 0.3]
9595
qdd = [0.1, 0.1, 0.1, 0.2, 0.2, 0.3]
96-
nt.assert_array_almost_equal(block._output(q, qd, qdd)[0], robot.rne(q, qd, qdd, gravity=[0,0,0]))
96+
nt.assert_array_almost_equal(block.T_output(q, qd, qdd)[0], robot.rne(q, qd, qdd, gravity=[0,0,0]))
9797

9898
def test_fdyn(self):
9999
robot = rtb.models.DH.Puma560()
@@ -105,10 +105,9 @@ def test_fdyn(self):
105105

106106
x = np.r_[q, np.zeros((6,))]
107107
xd = np.r_[np.zeros((6,)), robot.accel(q, qd, tau)]
108-
block.test_inputs = [tau] # set inputs
109108
block._x = x # set state [q, qd]
110-
nt.assert_equal(block.deriv(), xd)
111-
nt.assert_equal(block.output()[0], q)
109+
nt.assert_equal(block.T_deriv(tau), xd)
110+
nt.assert_equal(block.output(tau)[0], q)
112111
nt.assert_equal(block.getstate0(), x)
113112

114113
@unittest.skip
@@ -143,19 +142,19 @@ def test_delta(self):
143142

144143
T1 = SE3()
145144
T2 = SE3.Trans(0.01, 0.02, 0.03) * SE3.RPY(0.01, 0.02, 0.03)
146-
nt.assert_array_almost_equal(block._output(T1, T2)[0], T1.delta(T2))
145+
nt.assert_array_almost_equal(block.T_output(T1, T2)[0], T1.delta(T2))
147146

148147
block = Delta2Tr()
149148

150149
delta = [0.01, 0.02, 0.03, 0.04, 0.05, 0.06]
151-
nt.assert_array_almost_equal(block._output(delta)[0], SE3.Delta(delta))
150+
nt.assert_array_almost_equal(block.T_output(delta)[0], SE3.Delta(delta))
152151

153152
def test_tr2t(self):
154153

155154
T = SE3.Trans(1,2,3) * SE3.RPY(0.3, 0.4, 0.5)
156155

157156
block = TR2T()
158-
out = block._output(T)
157+
out = block.T_output(T)
159158
self.assertEqual(len(out), 3)
160159
self.assertAlmostEqual(out[0], 1)
161160
self.assertAlmostEqual(out[1], 2)
@@ -168,7 +167,7 @@ def test_point2tr(self):
168167
block = Point2Tr(T)
169168

170169
t = np.r_[3, 4, 5]
171-
nt.assert_array_almost_equal(block._output(t)[0], SE3.Trans(t) * SE3.RPY(0.3, 0.4, 0.5))
170+
nt.assert_array_almost_equal(block.T_output(t)[0], SE3.Trans(t) * SE3.RPY(0.3, 0.4, 0.5))
172171

173172

174173
def test_jtraj(self):
@@ -185,8 +184,8 @@ class State:
185184
s.T = 5
186185

187186
block.start(state=s)
188-
nt.assert_array_almost_equal(block._output(t=0)[0], q1)
189-
nt.assert_array_almost_equal(block._output(t=5)[0], q2)
187+
nt.assert_array_almost_equal(block.T_output(t=0)[0], q1)
188+
nt.assert_array_almost_equal(block.T_output(t=5)[0], q2)
190189

191190
def test_ctraj(self):
192191

@@ -202,55 +201,55 @@ class State:
202201
s.T = 5
203202

204203
block.start(state=s)
205-
nt.assert_array_almost_equal(block._output(t=0)[0], T1)
206-
nt.assert_array_almost_equal(block._output(t=5)[0], T2)
204+
nt.assert_array_almost_equal(block.T_output(t=0)[0], T1)
205+
nt.assert_array_almost_equal(block.T_output(t=5)[0], T2)
207206

208207
def test_lspb(self):
209208

210209
block = LSPB(2, 3, T=5)
211210
block.start()
212211

213-
out = block._output(t=0)
212+
out = block.T_output(t=0)
214213
nt.assert_array_almost_equal(out[0], 2)
215214
nt.assert_array_almost_equal(out[1], 0)
216215

217-
out = block._output(t=5)
216+
out = block.T_output(t=5)
218217
nt.assert_array_almost_equal(out[0], 3)
219218
nt.assert_array_almost_equal(out[1], 0)
220219

221220
def test_circlepath(self):
222221

223222
block = CirclePath(radius=2, centre=[1,2,3], frequency=0.25, phase=0, unit="rps")
224223

225-
nt.assert_array_almost_equal(block._output(t=0)[0], (1+2,2,3))
226-
nt.assert_array_almost_equal(block._output(t=1)[0], (1,2+2,3))
227-
nt.assert_array_almost_equal(block._output(t=2)[0], (1-2,2,3))
224+
nt.assert_array_almost_equal(block.T_output(t=0)[0], (1+2,2,3))
225+
nt.assert_array_almost_equal(block.T_output(t=1)[0], (1,2+2,3))
226+
nt.assert_array_almost_equal(block.T_output(t=2)[0], (1-2,2,3))
228227

229228
def test_traj(self):
230229

231230
block = Traj([1,2], [3,4], traj="trapezoidal", T=5)
232231
block.start()
233232

234-
nt.assert_array_almost_equal(block._output(t=0)[0], [1,2])
235-
nt.assert_array_almost_equal(block._output(t=0)[1], [0,0])
233+
nt.assert_array_almost_equal(block.T_output(t=0)[0], [1,2])
234+
nt.assert_array_almost_equal(block.T_output(t=0)[1], [0,0])
236235

237-
nt.assert_array_almost_equal(block._output(t=5)[0], [3,4])
238-
nt.assert_array_almost_equal(block._output(t=5)[1], [0,0])
236+
nt.assert_array_almost_equal(block.T_output(t=5)[0], [3,4])
237+
nt.assert_array_almost_equal(block.T_output(t=5)[1], [0,0])
239238

240-
nt.assert_array_almost_equal(block._output(t=2.5)[0], [2,3])
239+
nt.assert_array_almost_equal(block.T_output(t=2.5)[0], [2,3])
241240

242241
block = Traj([1,2], [3,4], traj="quintic", T=5)
243242
block.start()
244243

245-
nt.assert_array_almost_equal(block._output(t=0)[0], [1,2])
246-
nt.assert_array_almost_equal(block._output(t=0)[1], [0,0])
247-
nt.assert_array_almost_equal(block._output(t=0)[2], [0,0])
244+
nt.assert_array_almost_equal(block.T_output(t=0)[0], [1,2])
245+
nt.assert_array_almost_equal(block.T_output(t=0)[1], [0,0])
246+
nt.assert_array_almost_equal(block.T_output(t=0)[2], [0,0])
248247

249-
nt.assert_array_almost_equal(block._output(t=5)[0], [3,4])
250-
nt.assert_array_almost_equal(block._output(t=5)[1], [0,0])
251-
nt.assert_array_almost_equal(block._output(t=5)[2], [0,0])
248+
nt.assert_array_almost_equal(block.T_output(t=5)[0], [3,4])
249+
nt.assert_array_almost_equal(block.T_output(t=5)[1], [0,0])
250+
nt.assert_array_almost_equal(block.T_output(t=5)[2], [0,0])
252251

253-
nt.assert_array_almost_equal(block._output(t=2.5)[0], [2,3])
252+
nt.assert_array_almost_equal(block.T_output(t=2.5)[0], [2,3])
254253

255254
class MobileBlockTest(unittest.TestCase):
256255

@@ -260,10 +259,10 @@ def test_bicycle(self):
260259
block = Bicycle(x0=x, L=3)
261260

262261
block._x = x
263-
nt.assert_array_almost_equal(block._output(0, 0, t=0)[0], x)
262+
nt.assert_array_almost_equal(block.T_output(0, 0, t=0)[0], x)
264263
nt.assert_array_almost_equal(block.deriv(), [0, 0, 0])
265264

266-
nt.assert_array_almost_equal(block._output(10, 0.3, t=0)[0], x)
265+
nt.assert_array_almost_equal(block.T_output(10, 0.3, t=0)[0], x)
267266
nt.assert_array_almost_equal(block.deriv(),
268267
[10*np.cos(x[2]), 10*np.sin(x[2]), 10/3*np.tan(0.3)])
269268

@@ -274,10 +273,10 @@ def test_unicycle(self):
274273
block = Unicycle(x0=x, W=3)
275274

276275
block._x = x
277-
nt.assert_array_almost_equal(block._output(0, 0, t=0)[0], x)
276+
nt.assert_array_almost_equal(block.T_output(0, 0, t=0)[0], x)
278277
nt.assert_array_almost_equal(block.deriv(), [0, 0, 0])
279278

280-
nt.assert_array_almost_equal(block._output(10, 0.3, t=0)[0], x)
279+
nt.assert_array_almost_equal(block.T_output(10, 0.3, t=0)[0], x)
281280
nt.assert_array_almost_equal(block.deriv(),
282281
[10*np.cos(x[2]), 10*np.sin(x[2]), 0.3])
283282

@@ -288,26 +287,20 @@ def test_diffsteer(self):
288287
block = DiffSteer(x0=x, W=3, R=1/np.pi)
289288

290289
block._x = x
291-
nt.assert_array_almost_equal(block._output(0, 0, t=0)[0], x)
290+
nt.assert_array_almost_equal(block.T_output(0, 0, t=0)[0], x)
292291
nt.assert_array_almost_equal(block.deriv(), [0, 0, 0])
293292

294-
nt.assert_array_almost_equal(block._output(5, -5, t=0)[0], x)
293+
nt.assert_array_almost_equal(block.T_output(5, -5, t=0)[0], x)
295294
nt.assert_array_almost_equal(block.deriv(),
296295
[0, 5, -5])
297296

298-
@unittest.skip
299297
def test_vehicleplot(self):
300298

301299
bike = Bicycle()
302-
block = VehiclePlot(bike)
303-
304-
class State:
305-
pass
300+
block = VehiclePlot()
306301

307-
s = State()
308-
309-
block.start(state=s)
310-
block.step(state=s)
302+
s = block.T_start()
303+
block.T_step(np.array([0, 0, 0]), state=s)
311304

312305
class MultirotorBlockTest(unittest.TestCase):
313306

@@ -317,7 +310,7 @@ def test_multirotor(self):
317310
block = MultiRotor(model=quadrotor)
318311

319312
block._x = x
320-
out = block._output(np.r_[ 614.675223, -614.675223, 614.675223, -614.675223], t=0)[0]
313+
out = block.T_output(np.r_[ 614.675223, -614.675223, 614.675223, -614.675223], t=0)[0]
321314
self.assertIsInstance(out, dict)
322315

323316
out = block.deriv()
@@ -328,7 +321,7 @@ def test_multirotor(self):
328321
def test_multirotormixer(self):
329322

330323
block = MultiRotorMixer(model=quadrotor)
331-
nt.assert_array_almost_equal(block._output(0, 0, 0, -20, t=0)[0],
324+
nt.assert_array_almost_equal(block.T_output(0, 0, 0, -20, t=0)[0],
332325
[ 614.675223, -614.675223, 614.675223, -614.675223])
333326

334327

@@ -366,36 +359,37 @@ def test_quadrotor(self):
366359

367360
# check deriv, checked against MATLAB version 20200621
368361
u = [800 * np.r_[1, -1, 1, -1]] # too little thrust, falling
369-
d = block.T_deriv(u)
362+
d = block.T_deriv(*u)
370363
self.assertIsInstance(d, np.ndarray)
371364
self.assertEqual(d.shape, (12,))
372365
self.assertGreater(d[8], 0)
373366
nt.assert_array_almost_equal(np.delete(d, 8), np.zeros((11,))) # other derivs are zero
374367

375368
u = [900 * np.r_[1, -1, 1, -1]] # too much thrust, rising
376-
self.assertLess(block.T_deriv(u)[8], 0)
369+
self.assertLess(block.T_deriv(*u)[8], 0)
377370

378371
u = [800 * np.r_[1.2, -1, 0.8, -1]] # + pitch
379-
self.assertGreater(block.T_deriv(u)[10], 20)
372+
self.assertGreater(block.T_deriv(*u)[10], 20)
380373

381374
u = [800 * np.r_[0.8, -1, 1.2, -1]] # - pitch
382-
self.assertLess(block.T_deriv(u)[10], -20)
375+
self.assertLess(block.T_deriv(*u)[10], -20)
383376

384377
u = [800 * np.r_[1, -0.8, 1, -1.2]] # + roll
385-
self.assertGreater(block.T_deriv(u)[9], 20)
378+
self.assertGreater(block.T_deriv(*u)[9], 20)
386379

387380
u = [800 * np.r_[1, -1.2, 1, -0.8]] # - roll
388-
self.assertLess(block.T_deriv(u)[9], -20)
381+
self.assertLess(block.T_deriv(*u)[9], -20)
389382

390-
@unittest.skip
391383
def test_quadrotorplot(self):
392-
393-
b = MultiRotorPlot(quadrotor)
394-
395-
b.start()
396-
397-
b.setinputs(np.r_[0.5, 0, -1, 0, 0, 0, 0,0,0,0,0,0])
398-
b.step()
384+
385+
block = MultiRotor(quadrotor)
386+
u = [100 * np.r_[1, -1, 1, -1]]
387+
block.setstate(block.getstate0())
388+
out = block.T_output(u)[0]
389+
390+
block = MultiRotorPlot(quadrotor)
391+
s = block.T_start()
392+
block.T_step(out, state=s)
399393

400394
# ---------------------------------------------------------------------------------------#
401395
if __name__ == '__main__':

0 commit comments

Comments
 (0)