-
Notifications
You must be signed in to change notification settings - Fork 145
Expand file tree
/
Copy pathapi_tests.py
More file actions
executable file
·508 lines (395 loc) · 18.9 KB
/
api_tests.py
File metadata and controls
executable file
·508 lines (395 loc) · 18.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
#!/usr/bin/env python3
import unittest
import sys
import os.path
import os
FAKE_SYS = os.path.join(os.path.dirname(__file__), 'fake-sys')
os.environ["FAKE_SYS"] = "1"
sys.path.append(FAKE_SYS)
sys.path.append(os.path.join(os.path.dirname(__file__), '..'))
from populate_arena import populate_arena # noqa: E402
from clean_arena import clean_arena # noqa: E402
import ev3dev2 # noqa: E402
import ev3dev2.stopwatch # noqa: E402
from ev3dev2.motor import \
OUTPUT_A, OUTPUT_B, \
Motor, MediumMotor, LargeMotor, \
MoveTank, MoveSteering, MoveJoystick, \
SpeedPercent, SpeedDPM, SpeedDPS, SpeedRPM, SpeedRPS, SpeedNativeUnits # noqa: E402
from ev3dev2.sensor.lego import InfraredSensor # noqa: E402
from ev3dev2.stopwatch import StopWatch, StopWatchAlreadyStartedException # noqa: E402
from ev3dev2.unit import ( # noqa: E402
DistanceMillimeters, DistanceCentimeters, DistanceDecimeters, DistanceMeters, DistanceInches, DistanceFeet,
DistanceYards, DistanceStuds)
ev3dev2.Device.DEVICE_ROOT_PATH = os.path.join(FAKE_SYS, 'arena')
_internal_set_attribute = ev3dev2.Device._set_attribute
def _set_attribute(self, attribute, name, value):
# Follow the text with a newline to separate new content from stuff that
# already existed in the buffer. On the real device we're writing to sysfs
# attributes where there isn't any persistent buffer, but in the test
# environment they're normal files on disk which retain previous data.
attribute = _internal_set_attribute(self, attribute, name, value)
attribute.write(b'\n')
return attribute
ev3dev2.Device._set_attribute = _set_attribute
_internal_get_attribute = ev3dev2.Device._get_attribute
def _get_attribute(self, attribute, name):
# Split on newline delimiter; see _set_attribute above
attribute, value = _internal_get_attribute(self, attribute, name)
return attribute, value.split('\n', 1)[0]
ev3dev2.Device._get_attribute = _get_attribute
def dummy_wait(self, cond, timeout=None):
pass
Motor.wait = dummy_wait
# for StopWatch
mock_ticks_ms = 0
def _mock_get_ticks_ms():
return mock_ticks_ms
ev3dev2.stopwatch.get_ticks_ms = _mock_get_ticks_ms
def set_mock_ticks_ms(value):
global mock_ticks_ms
mock_ticks_ms = value
class TestAPI(unittest.TestCase):
def setUp(self):
# micropython does not have _testMethodName
try:
print("\n\n{}\n{}".format(self._testMethodName, "=" * len(self._testMethodName, )))
except AttributeError:
pass
# ensure tests don't depend on order based on StopWatch tick state
set_mock_ticks_ms(0)
def test_device(self):
clean_arena()
populate_arena([('medium_motor', 0, 'outA'), ('infrared_sensor', 0, 'in1')])
ev3dev2.Device('tacho-motor', 'motor*')
ev3dev2.Device('tacho-motor', 'motor0')
ev3dev2.Device('tacho-motor', 'motor*', driver_name='lego-ev3-m-motor')
ev3dev2.Device('tacho-motor', 'motor*', address='outA')
with self.assertRaises(ev3dev2.DeviceNotFound):
ev3dev2.Device('tacho-motor', 'motor*', address='outA', driver_name='not-valid')
with self.assertRaises(ev3dev2.DeviceNotFound):
ev3dev2.Device('tacho-motor', 'motor*', address='this-does-not-exist')
ev3dev2.Device('lego-sensor', 'sensor*')
with self.assertRaises(ev3dev2.DeviceNotFound):
ev3dev2.Device('this-does-not-exist')
def test_medium_motor(self):
def dummy(self):
pass
clean_arena()
populate_arena([('medium_motor', 0, 'outA')])
# Do not write motor.command on exit (so that fake tree stays intact)
MediumMotor.__del__ = dummy
m = MediumMotor()
self.assertEqual(m.device_index, 0)
# Check that reading twice works:
self.assertEqual(m.driver_name, 'lego-ev3-m-motor')
self.assertEqual(m.driver_name, 'lego-ev3-m-motor')
self.assertEqual(m.count_per_rot, 360)
self.assertEqual(
m.commands, ['run-forever', 'run-to-abs-pos', 'run-to-rel-pos', 'run-timed', 'run-direct', 'stop', 'reset'])
self.assertEqual(m.duty_cycle, 0)
self.assertEqual(m.duty_cycle_sp, 42)
self.assertEqual(m.polarity, 'normal')
self.assertEqual(m.address, 'outA')
self.assertEqual(m.position, 42)
self.assertEqual(m.position_sp, 42)
self.assertEqual(m.ramp_down_sp, 0)
self.assertEqual(m.ramp_up_sp, 0)
self.assertEqual(m.speed, 0)
self.assertEqual(m.speed_sp, 0)
self.assertEqual(m.state, ['running'])
self.assertEqual(m.stop_action, 'coast')
self.assertEqual(m.time_sp, 1000)
with self.assertRaises(Exception):
m.command
def test_infrared_sensor(self):
clean_arena()
populate_arena([('infrared_sensor', 0, 'in1')])
s = InfraredSensor()
self.assertEqual(s.device_index, 0)
self.assertEqual(s.bin_data_format, 's8')
self.assertEqual(s.bin_data('<b'), (16, ))
self.assertEqual(s.num_values, 1)
self.assertEqual(s.address, 'in1')
self.assertEqual(s.value(0), 16)
self.assertEqual(s.mode, "IR-PROX")
s.mode = "IR-REMOTE"
self.assertEqual(s.mode, "IR-REMOTE")
val = s.proximity
self.assertEqual(s.mode, "IR-PROX")
self.assertEqual(val, 16)
val = s.buttons_pressed()
self.assertEqual(s.mode, "IR-REMOTE")
self.assertEqual(val, [])
def test_medium_motor_write(self):
clean_arena()
populate_arena([('medium_motor', 0, 'outA')])
m = MediumMotor()
self.assertEqual(m.speed_sp, 0)
m.speed_sp = 500
self.assertEqual(m.speed_sp, 500)
def test_motor_on_for_degrees(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA')])
m = LargeMotor()
# simple case
m.on_for_degrees(75, 100)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, 100)
# various negative cases; values act like multiplication
m.on_for_degrees(-75, 100)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, -100)
m.on_for_degrees(75, -100)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, -100)
m.on_for_degrees(-75, -100)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, 100)
# zero speed (on-device, this will return immediately due to reported stall)
m.on_for_degrees(0, 100)
self.assertEqual(m.speed_sp, 0)
self.assertEqual(m.position_sp, 100)
# zero distance
m.on_for_degrees(75, 0)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, 0)
# zero speed and distance
m.on_for_degrees(0, 0)
self.assertEqual(m.speed_sp, 0)
self.assertEqual(m.position_sp, 0)
def test_motor_on_for_rotations(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA')])
m = LargeMotor()
# simple case
m.on_for_rotations(75, 5)
self.assertEqual(m.speed_sp, int(round(0.75 * 1050)))
self.assertEqual(m.position_sp, 5 * 360)
def test_move_tank_relative_distance(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
drive = MoveTank(OUTPUT_A, OUTPUT_B)
# simple case (degrees)
drive.on_for_degrees(50, 25, 100)
self.assertEqual(drive.left_motor.position_sp, 100)
self.assertEqual(drive.left_motor.speed_sp, 0.50 * 1050)
self.assertEqual(drive.right_motor.position_sp, 50)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.25 * 1050, delta=0.5)
# simple case (rotations, based on degrees)
drive.on_for_rotations(50, 25, 10)
self.assertEqual(drive.left_motor.position_sp, 10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 0.50 * 1050)
self.assertEqual(drive.right_motor.position_sp, 5 * 360)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.25 * 1050, delta=0.5)
# negative distance
drive.on_for_rotations(50, 25, -10)
self.assertEqual(drive.left_motor.position_sp, -10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 0.50 * 1050)
self.assertEqual(drive.right_motor.position_sp, -5 * 360)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.25 * 1050, delta=0.5)
# negative speed
drive.on_for_rotations(-50, 25, 10)
self.assertEqual(drive.left_motor.position_sp, -10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 0.50 * 1050)
self.assertEqual(drive.right_motor.position_sp, 5 * 360)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.25 * 1050, delta=0.5)
# negative distance and speed
drive.on_for_rotations(-50, 25, -10)
self.assertEqual(drive.left_motor.position_sp, 10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 0.50 * 1050)
self.assertEqual(drive.right_motor.position_sp, -5 * 360)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.25 * 1050, delta=0.5)
# both speeds zero but nonzero distance
drive.on_for_rotations(0, 0, 10)
self.assertEqual(drive.left_motor.position_sp, 10 * 360)
self.assertAlmostEqual(drive.left_motor.speed_sp, 0)
self.assertEqual(drive.right_motor.position_sp, 10 * 360)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0)
# zero distance
drive.on_for_rotations(25, 50, 0)
self.assertEqual(drive.left_motor.position_sp, 0)
self.assertAlmostEqual(drive.left_motor.speed_sp, 0.25 * 1050, delta=0.5)
self.assertEqual(drive.right_motor.position_sp, 0)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0.50 * 1050)
# zero distance and zero speed
drive.on_for_rotations(0, 0, 0)
self.assertEqual(drive.left_motor.position_sp, 0)
self.assertAlmostEqual(drive.left_motor.speed_sp, 0)
self.assertEqual(drive.right_motor.position_sp, 0)
self.assertAlmostEqual(drive.right_motor.speed_sp, 0)
def test_tank_units(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
drive = MoveTank(OUTPUT_A, OUTPUT_B)
drive.on_for_rotations(SpeedDPS(400), SpeedDPM(10000), 10)
self.assertEqual(drive.left_motor.position, 0)
self.assertEqual(drive.left_motor.position_sp, 10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 400)
self.assertEqual(drive.right_motor.position, 0)
self.assertAlmostEqual(drive.right_motor.position_sp, 10 * 360 * ((10000 / 60) / 400))
self.assertAlmostEqual(drive.right_motor.speed_sp, 10000 / 60, delta=0.5)
def test_steering_units(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
drive = MoveSteering(OUTPUT_A, OUTPUT_B)
drive.on_for_rotations(25, SpeedDPS(400), 10)
self.assertEqual(drive.left_motor.position, 0)
self.assertEqual(drive.left_motor.position_sp, 10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 400)
self.assertEqual(drive.right_motor.position, 0)
self.assertEqual(drive.right_motor.position_sp, 5 * 360)
self.assertEqual(drive.right_motor.speed_sp, 200)
def test_steering_large_value(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
drive = MoveSteering(OUTPUT_A, OUTPUT_B)
drive.on_for_rotations(-100, SpeedDPS(400), 10)
self.assertEqual(drive.left_motor.position, 0)
self.assertEqual(drive.left_motor.position_sp, -10 * 360)
self.assertEqual(drive.left_motor.speed_sp, 400)
self.assertEqual(drive.right_motor.position, 0)
self.assertEqual(drive.right_motor.position_sp, 10 * 360)
self.assertEqual(drive.right_motor.speed_sp, 400)
def test_joystick(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
drive = MoveJoystick(OUTPUT_A, OUTPUT_B)
# With the joystick at (x, y) of (0, 50) we should drive straigh ahead
# at 50% of max_speed
drive.on(0, 50)
self.assertEqual(drive.left_motor.speed_sp, 1050 / 2)
self.assertEqual(drive.right_motor.speed_sp, 1050 / 2)
self.assertEqual(drive.left_motor._get_attribute(None, 'command')[1], 'run-forever')
self.assertEqual(drive.right_motor._get_attribute(None, 'command')[1], 'run-forever')
# With the joystick centered, motors should both be stopped
drive.on(0, 0)
self.assertEqual(drive.left_motor._get_attribute(None, 'command')[1], 'stop')
self.assertEqual(drive.right_motor._get_attribute(None, 'command')[1], 'stop')
def test_units(self):
clean_arena()
populate_arena([('large_motor', 0, 'outA'), ('large_motor', 1, 'outB')])
m = Motor()
self.assertEqual(SpeedPercent(35).to_native_units(m), 35 / 100 * m.max_speed)
self.assertEqual(SpeedDPS(300).to_native_units(m), 300)
self.assertEqual(SpeedNativeUnits(300).to_native_units(m), 300)
self.assertEqual(SpeedDPM(30000).to_native_units(m), (30000 / 60))
self.assertEqual(SpeedRPS(2).to_native_units(m), 360 * 2)
self.assertEqual(SpeedRPM(100).to_native_units(m), (360 * 100 / 60))
self.assertEqual(DistanceMillimeters(42).mm, 42)
self.assertEqual(DistanceCentimeters(42).mm, 420)
self.assertEqual(DistanceDecimeters(42).mm, 4200)
self.assertEqual(DistanceMeters(42).mm, 42000)
self.assertAlmostEqual(DistanceInches(42).mm, 1066.8)
self.assertAlmostEqual(DistanceFeet(42).mm, 12801.6)
self.assertAlmostEqual(DistanceYards(42).mm, 38404.8)
self.assertEqual(DistanceStuds(42).mm, 336)
def test_stopwatch(self):
sw = StopWatch()
self.assertEqual(str(sw), "StopWatch: 00:00:00.000")
sw = StopWatch(desc="test sw")
self.assertEqual(str(sw), "test sw: 00:00:00.000")
self.assertEqual(sw.is_started, False)
sw.start()
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 0)
self.assertEqual(sw.value_secs, 0)
self.assertEqual(sw.value_hms, (0, 0, 0, 0))
self.assertEqual(sw.hms_str, "00:00:00.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), False)
self.assertEqual(sw.is_elapsed_secs(3), False)
set_mock_ticks_ms(1500)
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 1500)
self.assertEqual(sw.value_secs, 1.5)
self.assertEqual(sw.value_hms, (0, 0, 1, 500))
self.assertEqual(sw.hms_str, "00:00:01.500")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), False)
self.assertEqual(sw.is_elapsed_secs(3), False)
set_mock_ticks_ms(3000)
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 3000)
self.assertEqual(sw.value_secs, 3)
self.assertEqual(sw.value_hms, (0, 0, 3, 0))
self.assertEqual(sw.hms_str, "00:00:03.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), True)
self.assertEqual(sw.is_elapsed_secs(3), True)
set_mock_ticks_ms(1000 * 60 * 75.5) # 75.5 minutes
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 1000 * 60 * 75.5)
self.assertEqual(sw.value_secs, 60 * 75.5)
self.assertEqual(sw.value_hms, (1, 15, 30, 0))
self.assertEqual(sw.hms_str, "01:15:30.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), True)
self.assertEqual(sw.is_elapsed_secs(3), True)
try:
# StopWatch can't be started if already running
sw.start()
self.fail()
except StopWatchAlreadyStartedException:
pass
# test reset behavior
sw.restart()
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 0)
self.assertEqual(sw.value_secs, 0)
self.assertEqual(sw.value_hms, (0, 0, 0, 0))
self.assertEqual(sw.hms_str, "00:00:00.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), False)
self.assertEqual(sw.is_elapsed_secs(3), False)
set_mock_ticks_ms(1000 * 60 * 75.5 + 3000)
self.assertEqual(sw.is_started, True)
self.assertEqual(sw.value_ms, 3000)
self.assertEqual(sw.value_secs, 3)
self.assertEqual(sw.value_hms, (0, 0, 3, 0))
self.assertEqual(sw.hms_str, "00:00:03.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), True)
self.assertEqual(sw.is_elapsed_secs(3), True)
# test stop
sw.stop()
set_mock_ticks_ms(1000 * 60 * 75.5 + 10000)
self.assertEqual(sw.is_started, False)
self.assertEqual(sw.value_ms, 3000)
self.assertEqual(sw.value_secs, 3)
self.assertEqual(sw.value_hms, (0, 0, 3, 0))
self.assertEqual(sw.hms_str, "00:00:03.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), True)
self.assertEqual(sw.is_elapsed_secs(3), True)
# test reset
sw.reset()
self.assertEqual(sw.is_started, False)
self.assertEqual(sw.value_ms, 0)
self.assertEqual(sw.value_secs, 0)
self.assertEqual(sw.value_hms, (0, 0, 0, 0))
self.assertEqual(sw.hms_str, "00:00:00.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), False)
self.assertEqual(sw.is_elapsed_secs(3), False)
set_mock_ticks_ms(1000 * 60 * 75.5 + 6000)
self.assertEqual(sw.is_started, False)
self.assertEqual(sw.value_ms, 0)
self.assertEqual(sw.value_secs, 0)
self.assertEqual(sw.value_hms, (0, 0, 0, 0))
self.assertEqual(sw.hms_str, "00:00:00.000")
self.assertEqual(sw.is_elapsed_ms(None), False)
self.assertEqual(sw.is_elapsed_secs(None), False)
self.assertEqual(sw.is_elapsed_ms(3000), False)
self.assertEqual(sw.is_elapsed_secs(3), False)
if __name__ == "__main__":
unittest.main()
del os.environ["FAKE_SYS"]