Example: Channels and Channel Overrides

This example shows how to get channel information and to get/set channel-override information.

Warning

Channel overrides (a.k.a. “RC overrides”) are highly dis-commended (they are primarily intended for simulating user input and when implementing certain types of joystick control).

Instead use the appropriate MAVLink commands like DO_SET_SERVO/DO_SET_RELAY, or more generally set the desired position or direction/speed.

If you have no choice but to use a channel-override please explain why in a Github issue and we will attempt to find a better alternative.

Running the example

The example can be run as described in Running the Examples (which in turn assumes that the vehicle and DroneKit have been set up as described in Installing DroneKit).

In summary, after cloning the repository:

  1. Navigate to the example folder as shown:

    cd dronekit-python/examples/channel_overrides/
    
  2. You can run the example against a simulator (DroneKit-SITL) by specifying the Python script without any arguments. The example will download SITL binaries (if needed), start the simulator, and then connect to it:

    python channel_overrides.py
    

    On the command prompt you should see (something like):

    Starting copter simulator (SITL)
    SITL already Downloaded.
    Connecting to vehicle on: tcp:127.0.0.1:5760
    >>> APM:Copter V3.3 (d6053245)
    >>> Frame: QUAD
    >>> Calibrating barometer
    >>> Initialising APM...
    >>> barometer calibration complete
    >>> GROUND START
    Channel values from RC Tx: {'1': 1500, '3': 1000, '2': 1500, '5': 1800, '4': 1500, '7': 1000, '6': 1000, '8': 1800}
    Read channels individually:
     Ch1: 1500
     Ch2: 1500
     Ch3: 1000
     Ch4: 1500
     Ch5: 1800
     Ch6: 1000
     Ch7: 1000
     Ch8: 1800
    Number of channels: 8
     Channel overrides: {}
    Set Ch2 override to 200 (indexing syntax)
     Channel overrides: {'2': 200}
     Ch2 override: 200
    Set Ch3 override to 300 (dictionary syntax)
     Channel overrides: {'3': 300}
    Set Ch1-Ch8 overrides to 110-810 respectively
     Channel overrides: {'1': 110, '3': 310, '2': 210, '5': 510, '4': 4100, '7': 710, '6': 610, '8': 810}
     Cancel Ch2 override (indexing syntax)
     Channel overrides: {'1': 110, '3': 310, '5': 510, '4': 4100, '7': 710, '6': 610, '8': 810}
    Clear Ch3 override (del syntax)
     Channel overrides: {'1': 110, '5': 510, '4': 4100, '7': 710, '6': 610, '8': 810}
    Clear Ch5, Ch6 override and set channel 3 to 500 (dictionary syntax)
     Channel overrides: {'3': 500}
    Clear all overrides
     Channel overrides: {}
     Close vehicle object
    Completed
    
  3. You can run the example against a specific connection (simulated or otherwise) by passing the connection string for your vehicle in the --connect parameter.

    For example, to connect to SITL running on UDP port 14550 on your local computer:

    python channel_overrides.py --connect 127.0.0.1:14550
    

How does it work?

The RC transmitter channels are connected to the autopilot and control the vehicle.

The values of the first four channels map to the main flight controls: 1=Roll, 2=Pitch, 3=Throttle, 4=Yaw (the mapping is defined in RCMAP_ parameters in Plane, Copter , Rover).

The remaining channel values are configurable, and their purpose can be determined using the RCn_FUNCTION parameters. In general a value of 0 set for a specific RCn_FUNCTION indicates that the channel can be mission controlled (i.e. it will not directly be controlled by normal autopilot code).

You can read the values of the channels using the Vehicle.channels attribute. The values are regularly updated, from the UAV, based on the RC inputs from the transmitter. These can be read either as a set or individually:

# Get all channel values from RC transmitter
print "Channel values from RC Tx:", vehicle.channels

# Access channels individually
print "Read channels individually:"
print " Ch1: %s" % vehicle.channels['1']
print " Ch2: %s" % vehicle.channels['2']

You can override the values sent to the vehicle by the autopilot using Vehicle.channels.overrides. The overrides can be written individually using an indexing syntax or as a set using a dictionary syntax.

# Set Ch2 override to 200 using indexing syntax
vehicle.channels.overrides['2'] = 200
# Set Ch3, Ch4 override to 300,400 using dictionary syntax"
vehicle.channels.overrides = {'3':300, '4':400}

To clear all overrides, set the attribute to an empty dictionary. To clear an individual override you can set its value to None (or call del on it):

# Clear override by setting channels to None
# Clear using index syntax
vehicle.channels.overrides['2'] = None

# Clear using 'del' syntax
del vehicle.channels.overrides['3']

# Clear using dictionary syntax (and set override at same time!)
vehicle.channels.overrides = {'5':None, '6':None,'3':500}

# Clear all overrides by setting an empty dictionary
vehicle.channels.overrides = {}

Read the channel overrides either as a dictionary or by index.

# Get all channel overrides
print " Channel overrides: %s" % vehicle.channels.overrides
# Print just one channel override
print " Ch2 override: %s" % vehicle.channels.overrides['2']

Note

You’ll get a KeyError exception if you read a channel override that has not been set.

Source code

The full source code at documentation build-time is listed below (current version on github):

#!/usr/bin/env python
# -*- coding: utf-8 -*-

"""
© Copyright 2015-2016, 3D Robotics.

channel_overrides.py: 

Demonstrates how set and clear channel-override information.

# NOTE: 
Channel overrides (a.k.a "RC overrides") are highly discommended (they are primarily implemented 
for simulating user input and when implementing certain types of joystick control).

They are provided for development purposes. Please raise an issue explaining why you need them
and we will try to find a better alternative: https://github.com/dronekit/dronekit-python/issues

Full documentation is provided at http://python.dronekit.io/examples/channel_overrides.html
"""
from __future__ import print_function
from dronekit import connect


#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.')
parser.add_argument('--connect', 
                   help="vehicle connection target string. If not specified, SITL automatically started and used.")
args = parser.parse_args()

connection_string = args.connect
sitl = None


#Start SITL if no connection string specified
if not connection_string:
    import dronekit_sitl
    sitl = dronekit_sitl.start_default()
    connection_string = sitl.connection_string()


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

# Get all original channel values (before override)
print("Channel values from RC Tx:", vehicle.channels)

# Access channels individually
print("Read channels individually:")
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'])
print("Number of channels: %s" % len(vehicle.channels))


# Override channels
print("\nChannel overrides: %s" % vehicle.channels.overrides)

print("Set Ch2 override to 200 (indexing syntax)")
vehicle.channels.overrides['2'] = 200
print(" Channel overrides: %s" % vehicle.channels.overrides)
print(" Ch2 override: %s" % vehicle.channels.overrides['2'])

print("Set Ch3 override to 300 (dictionary syntax)")
vehicle.channels.overrides = {'3':300}
print(" Channel overrides: %s" % vehicle.channels.overrides)

print("Set Ch1-Ch8 overrides to 110-810 respectively")
vehicle.channels.overrides = {'1': 110, '2': 210,'3': 310,'4':4100, '5':510,'6':610,'7':710,'8':810}
print(" Channel overrides: %s" % vehicle.channels.overrides) 


# Clear override by setting channels to None
print("\nCancel Ch2 override (indexing syntax)")
vehicle.channels.overrides['2'] = None
print(" Channel overrides: %s" % vehicle.channels.overrides) 

print("Clear Ch3 override (del syntax)")
del vehicle.channels.overrides['3']
print(" Channel overrides: %s" % vehicle.channels.overrides) 

print("Clear Ch5, Ch6 override and set channel 3 to 500 (dictionary syntax)")
vehicle.channels.overrides = {'5':None, '6':None,'3':500}
print(" Channel overrides: %s" % vehicle.channels.overrides) 

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

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

# Shut down simulator if it was started.
if sitl is not None:
    sitl.stop()

print("Completed")