@@ -396,15 +396,50 @@ def decorator(fn):
396
396
self .add_attribute_listener (name , fn )
397
397
return decorator
398
398
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
+
399
431
class Channels (dict ):
400
432
"""
401
433
Implements RC object.
402
434
"""
403
435
404
436
def __init__ (self , vehicle , count ):
437
+ self ._vehicle = vehicle
405
438
self ._count = count
439
+ self ._overrides = ChannelsOverride (vehicle )
440
+
441
+ # populate readback
406
442
self ._readonly = False
407
- self ._overrides = {}
408
443
for k in range (0 , count ):
409
444
self [k + 1 ] = None
410
445
self ._readonly = True
@@ -413,34 +448,39 @@ def __init__(self, vehicle, count):
413
448
def count (self ):
414
449
return self ._count
415
450
451
+ def __getitem__ (self , key ):
452
+ return dict .__getitem__ (self , str (key ))
453
+
416
454
def __setitem__ (self , key , value ):
417
455
if self ._readonly :
418
456
raise TypeError ('__setitem__ is not supported on Channels object' )
419
- return dict .__setitem__ (self , key , value )
457
+ return dict .__setitem__ (self , str ( key ) , value )
420
458
421
459
def __len__ (self ):
422
460
return self ._count
423
461
424
462
def _update_channel (self , channel , value ):
425
463
# If we have channels on different ports, we expand the Channels
426
464
# object to support them.
427
- channel = str (channel )
465
+ channel = int (channel )
428
466
self ._readonly = False
429
467
self [channel ] = value
430
468
self ._readonly = True
431
- self ._count = max (self ._count , int ( channel ) )
469
+ self ._count = max (self ._count , channel )
432
470
433
471
@property
434
472
def overrides (self ):
435
- return copy . copy ( self ._overrides )
473
+ return self ._overrides
436
474
437
475
@overrides .setter
438
476
def overrides (self , newch ):
439
- self ._overrides = {}
440
477
for k , v in newch .iteritems ():
441
478
if v :
442
479
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
+
444
484
445
485
class Vehicle (HasObservers ):
446
486
"""
0 commit comments