Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Implements Channels functionality as its own object. #427

Merged
merged 7 commits into from
Nov 11, 2015
Merged

Implements Channels functionality as its own object. #427

merged 7 commits into from
Nov 11, 2015

Conversation

tcr3dr
Copy link
Contributor

@tcr3dr tcr3dr commented Nov 6, 2015

This PR brings back RC support by creating a new abstraction, Channels.

len(vehicle.channels) == 8
vehicle.channels['1'] == <rc readback value>
vehicle.channels['2'] == ...
vehicle.channels.overrides == {}
vehicle.channels.overrides = {'1': 1500} # this setter sends the MAVLink RC override command
vehicle.channels.overrides == {'1': 1500} # getter returns our overrides

This also allows other mechanisms of subclassing via vehicle_class to create new channels options:

class SoloChannels(Channels):
    def _update_channel(self, channel, value):
        ...
    @overrides.setter
    def overrides(self, newch):
        ...

class SoloVehicle(Vehicle):
    def __init__(self, ...):
        super().__init__()
        self.channels = SoloChannels(self)

So we can support SITL overrides, Solo overrides, or by default on the Vehicle, we just use MAVLink overrides.

@hamishwillee
Copy link
Contributor

@tcr3dr The setter is crashing, so I can't fully test this. My test code below, but specifically, if I do this:

print "Set Ch1 to 1000"
vehicle.channels.overrides = {'1': 1000}

I get this:

Set Ch1 to 1000
Traceback (most recent call last):
  File "E:\deleteme\dronekit-python\examples\channel_overrides\channel_overrides.py", line 42, in <module>
    vehicle.channels.overrides = {'1': 1000}
  File "build\bdist.win-amd64\egg\dronekit\lib\__init__.py", line 427, in overrides
AttributeError: 'Channels' object has no attribute '_master'

If I do the following:

print "Channels: %s" % vehicle.channels
print "Channel overrides: %s" % vehicle.channels.overrides
print "Ch1: %s" % vehicle.channels['1']
print "Ch2: %s" % vehicle.channels['2']
print "Ch7: %s" % vehicle.channels['7']
print "Ch8: %s" % vehicle.channels['8']

I get the output below. Would I be correct in thinking that the vehilce.channels is a dictionary - the first value is the set of overrides, the second set is the read channel values? This feels a bit odd to be able to query like this, and then access as vehicle.channel.overrides. But perhaps not.

Number of channels: 8
Channels: {1: None, 2: None, 3: None, 4: None, 5: None, 6: None, 7: None, 8: None, '1': 1500, '3': 1000, '2': 1500, '5': 1800, '4': 1500, '7': 1000, '6': 1000, '8': 1800}
Channel overrides: {}
Ch1: 1500
Ch2: 1500
Ch7: 1000
Ch8: 1800

Some questions

  • The channel values (before override) are populated from messages? (ie how are these updated?
  • How should you reset a particular channel override? Do vehicle.channels.overrides = {'1': None} perhaps?
    • would it make more sense to recommend individual updates- this doesn't seem to work (ie readback doesn't show a change) vehicle.channels.overrides[1]=1000

My example code

from dronekit import connect
from dronekit.lib import VehicleMode
from pymavlink import mavutil
import time

#Set up option parsing to get connection string
import argparse  
parser = argparse.ArgumentParser(description='Example showing how to set and clear vehicle channel-override information. Connects to SITL on local PC by default.')
parser.add_argument('--connect', default='127.0.0.1:14550',
                   help="vehicle connection target. Default '127.0.0.1:14550'")
args = parser.parse_args()


# Connect to the Vehicle
print 'Connecting to vehicle on: %s' % args.connect
vehicle = connect(args.connect, wait_ready=True)

print "Number of channels: %s" % len(vehicle.channels)
len(vehicle.channels) == 8
print "Channels: %s" % vehicle.channels
print "Channel overrides: %s" % vehicle.channels.overrides
print "Ch1: %s" % vehicle.channels['1']
print "Ch2: %s" % vehicle.channels['2']
print "Ch7: %s" % vehicle.channels['7']
print "Ch8: %s" % vehicle.channels['8']
print "Set Ch1 to 1000"
vehicle.channels.overrides = {'1': 1000}
print "Channel overrides: %s" % vehicle.channels.overrides
print "Set Ch2 to 1010"
vehicle.channels.overrides = {'2': 1010}
print "Channel overrides: %s" % vehicle.channels.overrides


#vehicle.channels['1'] == <rc readback value>
#vehicle.channels['2'] == ...
#vehicle.channels.overrides == {}
#vehicle.channels.overrides = {'1': 1500} # this setter sends the MAVLink RC override command
#vehicle.channels.overrides == {'1': 1500} # getter returns our overrides

# Short wait before exiting
time.sleep(5)

#Close vehicle object before exiting script
print "Close vehicle object"
vehicle.close()

print("Completed")

@tcr3dr tcr3dr force-pushed the tcr-rc branch 2 times, most recently from fe27bb6 to 58efa90 Compare November 9, 2015 20:20
@tcr3dr
Copy link
Contributor Author

tcr3dr commented Nov 9, 2015

To clarify: vehicle.channels is the readback of the RC values we get back from the autopilot. vehicle.channels.overrides is the dict of what override values we have set and maintain.

The channel values (before override) are populated from messages? (ie how are these updated?)

They are populated from the RC_CHANNELS_RAW message.

How should you reset a particular channel override? Do vehicle.channels.overrides = {'1': None} perhaps?

What now works is setting that value directly. vehicle.channels.overrides['1'] = None or del vehicle.channels.overrides['1']. You can also override the entire overrides dict directly, and None values will be skipped: vehicle.channels.overrides = {'1': None, '2': 1500} will clear all overrides, then only override '2' channel.

would it make more sense to recommend individual updates- this doesn't seem to work (ie readback doesn't show a change) vehicle.channels.overrides[1]=1000

This now works.

Also you can index by either string or number, if that's helpful. Canonically, we should recommend strings: vehicle.channels['1']

@hamishwillee
Copy link
Contributor

New test code:

from dronekit import connect, VehicleMode
#from dronekit.lib import VehicleMode
from pymavlink import mavutil
import time

#Set up option parsing to get connection string
import argparse  
parser = argparse.ArgumentParser(description='Example showing how to set and clear vehicle channel-override information. Connects to SITL on local PC by default.')
parser.add_argument('--connect', default='127.0.0.1:14550',
                   help="vehicle connection target. Default '127.0.0.1:14550'")
args = parser.parse_args()


# Connect to the Vehicle
print 'Connecting to vehicle on: %s' % args.connect
vehicle = connect(args.connect, wait_ready=True)

print "Number of channels: %s" % len(vehicle.channels)
print "Channels: %s" % vehicle.channels
print "Ch1: %s" % vehicle.channels['1']
print "Ch2: %s" % vehicle.channels['2']
print "Ch3: %s" % vehicle.channels['3']
print "Ch4: %s" % vehicle.channels['4']
print "Ch5: %s" % vehicle.channels['5']
print "Ch6: %s" % vehicle.channels['6']
print "Ch7: %s" % vehicle.channels['7']
print "Ch8: %s" % vehicle.channels['8']

#test 
try:
    print "Ch9: %s" % vehicle.channels['9']
    print "Fail - can read over end of channels"
except:
    print "Pass - cannot read over end of channels"

try:
    print "Ch0: %s" % vehicle.channels['0']
    print "Fail - can read over start of channels"
except:
    print "Pass - cannot read over start of channels"

try:    
    print "Try to write channel 1 to a value"
    vehicle.channels['1']=200
    print "Fail - can write a channel value"
except:
    print "Pass - can't write a channels"    

print "Channel overrides: %s" % vehicle.channels.overrides

print "Set Ch1 to 100 using braces syntax"
vehicle.channels.overrides = {'1': 1000}
print "Channel overrides: %s" % vehicle.channels.overrides

print "Set Ch2 to 200 using bracket"
vehicle.channels.overrides['2'] = 200
print "Channel overrides: %s" % vehicle.channels.overrides


print "Set Ch2 to 1010"
vehicle.channels.overrides = {'2': 1010}
print "Channel overrides: %s" % vehicle.channels.overrides

print "Set Ch3,4,5,6,7 to 300,400-700 respectively"
vehicle.channels.overrides = {'3': 300, '4':400, '5':500,'6':600,'7':700}
print "Channel overrides: %s" % vehicle.channels.overrides

try:
    print "Set Ch8 to 800 using braces"
    vehicle.channels.overrides = {'8': 800}
    print "Channel overrides: %s" % vehicle.channels.overrides
    print "succeed - can write channel 8 using braces"
except:
    print "Fail, except on setting channel override 8 using braces"

try:
    print "Set Ch8 to 800 using brackets"
    vehicle.channels.overrides['8'] = 800
    print "Channel overrides: %s" % vehicle.channels.overrides
    print "succeed - can write channel 8 using brackets"
except:
    print "Fail, except on setting channel override 8 using braces"    

try:    
    print "Try to write channel 9 override to a value with brackets"
    vehicle.channels.overrides['9']=900
    print "Fail - can write channels.overrides 9"
except:
    print "Pass - can't write a channels"    

try:    
    print "Try to write channel 9 override to a value with braces"
    vehicle.channels.overrides={'9': 900}
    print "Fail - can write channels.overrides 9 with braces"
except:
    print "Pass - can't write a channels.overrides 9 with braces"    

print "Clear channel 3 brackets"
vehicle.channels.overrides['3'] = None
print "Channel overrides: %s" % vehicle.channels.overrides

print "Clear channel 2 braces"
vehicle.channels.overrides = {'2': None}
print "Channel overrides: %s" % vehicle.channels.overrides


print "Clear all channels"
vehicle.channels.overrides = {}
print "Channel overrides: %s" % vehicle.channels.overrides

print "Set Ch2 to 33, clear channel 6"
vehicle.channels.overrides = {'2': 33, '6':None}
print "Channel overrides: %s" % vehicle.channels.overrides


#vehicle.channels['1'] == <rc readback value>
#vehicle.channels['2'] == ...
#vehicle.channels.overrides == {}
#vehicle.channels.overrides = {'1': 1500} # this setter sends the MAVLink RC override command
#vehicle.channels.overrides == {'1': 1500} # getter returns our overrides

# Short wait before exiting
time.sleep(5)

#Close vehicle object before exiting script
print "Close vehicle object"
vehicle.close()

print("Completed")

@hamishwillee
Copy link
Contributor

@tcr3dr This has a bug that you can't write the 8'th channel override value. If you try to set the 8th value you get

Set Ch8 to 800 using braces
Traceback (most recent call last):
  File "E:\deleteme\dronekit-python\examples\channel_overrides\test.py", line 69, in <module>
    vehicle.channels.overrides = {'8': 800}
  File "build\bdist.win-amd64\egg\dronekit\lib\__init__.py", line 479, in overrides
  File "build\bdist.win-amd64\egg\dronekit\lib\__init__.py", line 410, in __setitem__
Exception: Invalid channel index 8

In addition, you can clear individual items, but it would be quite nice to be able to clear all of them at the same time. The below does nothing:

print "Clear all channels"
vehicle.channels.overrides = {}
print "Channel overrides: %s" % vehicle.channels.overrides

@hamishwillee
Copy link
Contributor

@tcr3dr Should I be able to observe the individual channels?

@hamishwillee
Copy link
Contributor

@tcr3dr I have just made some docs/example changes to reflect the new channels.

  • The example crashes because of the channel override channel 8 indexing issue.

  • This also doesn't have any information about observing the channels - waiting on your feedback on this

  • This deletes the old channel readback stuff. It adds documentation for the new classes. I'm not completely convinced by this, so all the sub classes refer back to the example documentation which is fairly comprehensive ... in the ref itself there is documentation, but it is a bit spread among the various classes.

  • I still need to add this change to the migration document

  • There is a lot of not very useful Channels, ChannelsOverride documentation being built (ie it may be useful ... but it may not be). YOu might want to build and see if we need it all or should have more information. For example, Channels doc is generated as below ...

    class dronekit.lib.Channels(vehicle, count)
    A dictionary class for managing RC channel information associated with a Vehicle.
    
    An object of this type is accessed through Vehicle.channels. This object also stores the current vehicle channel overrides through its overrides attribute.
    
    clear() → None. Remove all items from D.
    copy() → a shallow copy of D
    count
    The number of channels defined in the dictionary (currently 8).
    
    fromkeys(S[, v]) → New dict with keys from S and values equal to v.
    v defaults to None.
    
    get(k[, d]) → D[k] if k in D, else d. d defaults to None.
    has_key(k) → True if D has a key k, else False
    items() → list of D's (key, value) pairs, as 2-tuples
    iteritems() → an iterator over the (key, value) items of D
    iterkeys() → an iterator over the keys of D
    itervalues() → an iterator over the values of D
    keys() → list of D's keys
    

Anyway, this is "a good start" but may need updates once you've checked it out, and maybe built the docs to inspect.

@tcr3dr
Copy link
Contributor Author

tcr3dr commented Nov 11, 2015

@hamishwillee The tests have been updated, this should fix the indexing issue and clarify some other aspects (like vehicle.channels.override = {} clearing all overrides)

@hamishwillee
Copy link
Contributor

@tcr3dr Yes, fixes worked well. I've updated docs to now index 8 and clearing work. Also added doc to migration guide. You should merge this now :-)

tcr3dr added a commit that referenced this pull request Nov 11, 2015
Implements Channels functionality as its own object.
@tcr3dr tcr3dr merged commit bf8e8da into master Nov 11, 2015
@tcr3dr tcr3dr deleted the tcr-rc branch November 11, 2015 20:10
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants