Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 0ff65cb

Browse files
committedNov 9, 2015
Adds tests and fixes dict objects in channels.
1 parent 3d7c2da commit 0ff65cb

File tree

2 files changed

+105
-7
lines changed

2 files changed

+105
-7
lines changed
 

‎dronekit/lib/__init__.py

+47-7
Original file line numberDiff line numberDiff line change
@@ -396,15 +396,50 @@ def decorator(fn):
396396
self.add_attribute_listener(name, fn)
397397
return decorator
398398

399+
400+
class ChannelsOverride(dict):
401+
def __init__(self, vehicle):
402+
self._vehicle = vehicle
403+
self._count = 8 # Fixed by MAVLink
404+
405+
def __getitem__(self, key):
406+
return dict.__getitem__(self, str(key))
407+
408+
def __setitem__(self, key, value):
409+
if not (int(key) >= 0 and int(key) < self._count):
410+
raise Exception('Invalid channel index %s' % key)
411+
if not value:
412+
dict.__delitem__(self, str(key))
413+
else:
414+
dict.__setitem__(self, str(key), value)
415+
self._send()
416+
417+
def __delitem__(self, key):
418+
dict.__delitem__(self, str(key))
419+
self._send()
420+
421+
def __len__(self):
422+
return self._count
423+
424+
def _send(self):
425+
overrides = [0] * 8
426+
for k, v in self.iteritems():
427+
overrides[int(k)-1] = v
428+
self._vehicle._master.mav.rc_channels_override_send(0, 0, *overrides)
429+
430+
399431
class Channels(dict):
400432
"""
401433
Implements RC object.
402434
"""
403435

404436
def __init__(self, vehicle, count):
437+
self._vehicle = vehicle
405438
self._count = count
439+
self._overrides = ChannelsOverride(vehicle)
440+
441+
# populate readback
406442
self._readonly = False
407-
self._overrides = {}
408443
for k in range(0, count):
409444
self[k + 1] = None
410445
self._readonly = True
@@ -413,34 +448,39 @@ def __init__(self, vehicle, count):
413448
def count(self):
414449
return self._count
415450

451+
def __getitem__(self, key):
452+
return dict.__getitem__(self, str(key))
453+
416454
def __setitem__(self, key, value):
417455
if self._readonly:
418456
raise TypeError('__setitem__ is not supported on Channels object')
419-
return dict.__setitem__(self, key, value)
457+
return dict.__setitem__(self, str(key), value)
420458

421459
def __len__(self):
422460
return self._count
423461

424462
def _update_channel(self, channel, value):
425463
# If we have channels on different ports, we expand the Channels
426464
# object to support them.
427-
channel = str(channel)
465+
channel = int(channel)
428466
self._readonly = False
429467
self[channel] = value
430468
self._readonly = True
431-
self._count = max(self._count, int(channel))
469+
self._count = max(self._count, channel)
432470

433471
@property
434472
def overrides(self):
435-
return copy.copy(self._overrides)
473+
return self._overrides
436474

437475
@overrides.setter
438476
def overrides(self, newch):
439-
self._overrides = {}
440477
for k, v in newch.iteritems():
441478
if v:
442479
self._overrides[str(k)] = v
443-
self._master.mav.rc_channels_override_send(0, 0, *list(self._overrides.values()))
480+
else:
481+
del self._overrides[str(k)]
482+
self._overrides._send()
483+
444484

445485
class Vehicle(HasObservers):
446486
"""

‎dronekit/test/sitl/test_channels.py

+58
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
from dronekit import connect
2+
from dronekit.lib import VehicleMode
3+
from pymavlink import mavutil
4+
import time
5+
from dronekit import connect, VehicleMode, LocationGlobal
6+
from dronekit.test import with_sitl
7+
from nose.tools import assert_equals, assert_not_equals
8+
9+
def assert_readback(vehicle, values):
10+
i = 10
11+
while i > 0:
12+
time.sleep(.1)
13+
i -= .1
14+
for k, v in values.iteritems():
15+
if vehicle.channels[k] != v:
16+
continue
17+
break
18+
if i <= 0:
19+
raise Exception('Did not match in channels readback %s' % values)
20+
21+
@with_sitl
22+
def test_timeout(connpath):
23+
vehicle = connect(connpath, wait_ready=True)
24+
25+
assert_equals(len(vehicle.channels), 8)
26+
assert_equals(len(vehicle.channels.overrides), 8)
27+
28+
assert_equals(sorted(vehicle.channels.keys()), [str(x) for x in range(1, 9)])
29+
assert_equals(sorted(vehicle.channels.overrides.keys()), [])
30+
31+
assert_equals(type(vehicle.channels['1']), int)
32+
assert_equals(type(vehicle.channels['2']), int)
33+
assert_equals(type(vehicle.channels['7']), int)
34+
assert_equals(type(vehicle.channels['8']), int)
35+
assert_equals(type(vehicle.channels[1]), int)
36+
assert_equals(type(vehicle.channels[2]), int)
37+
assert_equals(type(vehicle.channels[7]), int)
38+
assert_equals(type(vehicle.channels[8]), int)
39+
40+
vehicle.channels.overrides = {'1': 1010}
41+
assert_readback(vehicle, {'1': 1010})
42+
43+
vehicle.channels.overrides = {'2': 1020}
44+
assert_readback(vehicle, {'1': 1500, '2': 1010})
45+
46+
vehicle.channels.overrides['1'] = 1010
47+
assert_readback(vehicle, {'1': 1010, '2': 1020})
48+
49+
del vehicle.channels.overrides['1']
50+
assert_readback(vehicle, {'1': 1500, '2': 1020})
51+
52+
vehicle.channels.overrides = {'1': 1010, '2': None}
53+
assert_readback(vehicle, {'1': 1010, '2': 1500})
54+
55+
vehicle.channels.overrides['1'] = None
56+
assert_readback(vehicle, {'1': 1500, '2': 1500})
57+
58+
vehicle.close()

0 commit comments

Comments
 (0)
Please sign in to comment.