DroneKit-Python API Reference

This is the API Reference for the DroneKit-Python API.

The main API is the Vehicle class. The code snippet below shows how to obtain an instance of the (first) connected vehicle:

# Get a local APIConnection to the autopilot (from companion computer or GCS).
api_connection = local_connect()
# Get the first connected vehicle from the APIConnection
vehicle = api.get_vehicles()[0]

Vehicle provides access to vehicle state through python attributes (e.g. Vehicle.location) and to settings/parameters though the Vehicle.parameters attribute. Asynchronous notification on vehicle attribute changes is available by registering observers.

Vehicle provides two main ways to control vehicle movement and other operations:

A number of other useful classes and methods are listed below.


class droneapi.lib.APIConnection

An API provider.

This is the top level API connection returned from local_connect(). You should not manually create instances of this class.

exit

True if the current thread has been asked to exit.

The connection to the UAV is owned by MAVProxy, which uses this property to signal that the thread should be closed (for whatever reason). Scripts are expected to check the property and close the thread if this if True. For example:

while not api.exit:
    # send commands to vehicle etc.
get_vehicles(query=None)

Get the set of vehicles that are controllable from this connection.

For example, to get the first vehicle in the set with get_vehicles():

api = local_connect()     # Get an APIConnection
first_vehicle = api.get_vehicles()[0]

Note

The set of vehicles connected by the API is configured through MAVProxy. When running on a companion computer there will only ever be one Vehicle in the returned set. A ground control station might potentially control (and hence return) more than one vehicle.

Parameters:query – This parameter is ignored. Use the default.
Returns:Set of Vehicle objects controllable from this connection.
exception droneapi.lib.APIException(msg)

Base class for DroneKit related exceptions.

Parameters:msg (String) – Message string describing the exception
class droneapi.lib.Attitude(pitch, yaw, roll)

Attitude information.

Diagram showing Pitch, Roll, Yaw

Diagram showing Pitch, Roll, Yaw (Creative Commons)

Parameters:
  • pitch – Pitch in radians
  • yaw – Yaw in radians
  • roll – Roll in radians
class droneapi.lib.Battery(voltage, current, level)

System battery information.

Parameters:
  • voltage – Battery voltage in millivolts.
  • current – Battery current, in 10 * milliamperes. None if the autopilot does not support current measurement.
  • level – Remaining battery energy. None if the autopilot cannot estimate the remaining battery.
class droneapi.lib.Command(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)

A waypoint object.

This object encodes a single mission item command. The set of commands that are supported by ArduPilot in Copter, Plane and Rover (along with their parameters) are listed in the wiki article MAVLink Mission Command Messages (MAV_CMD).

For example, to create a NAV_WAYPOINT command:

cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
    mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, 0, 0, 0, 0,-34.364114, 149.166022, 30)
Parameters:
  • target_system – The id number of the message’s target system (drone, GSC) within the MAVLink network. Set this to zero (broadcast) when communicating with a companion computer.
  • target_component – The id of a component the message should be routed to within the target system (for example, the camera). Set to zero (broadcast) in most cases.
  • seq – The sequence number within the mission (the autopilot will reject messages sent out of sequence). This should be set to zero as the API will automatically set the correct value when uploading a mission.
  • frame – The frame of reference used for the location parameters (x, y, z). In most cases this will be mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, which uses the WGS84 global coordinate system for latitude and longitude, but sets altitude as relative to the home position in metres (home altitude = 0). For more information see the wiki here.
  • command – The specific mission command (e.g. mavutil.mavlink.MAV_CMD_NAV_WAYPOINT). The supported commands (and command parameters are listed on the wiki.
  • current – Set to zero (not supported).
  • autocontinue – Set to zero (not supported).
  • param1 – Command specific parameter (depends on specific Mission Command (MAV_CMD)).
  • param2 – Command specific parameter.
  • param3 – Command specific parameter.
  • param4 – Command specific parameter.
  • x – (param5) Command specific parameter used for latitude (if relevant to command).
  • y – (param6) Command specific parameter used for longitude (if relevant to command).
  • z – (param7) Command specific parameter used for altitude (if relevant). The reference frame for altitude depends on the frame.
class droneapi.lib.CommandSequence

A sequence of vehicle waypoints (a “mission”).

Operations include ‘array style’ indexed access to the various contained waypoints.

The current commands/mission for a vehicle are accessed using the Vehicle.commands attribute. Waypoints are not downloaded from vehicle until download() is called. The download is asynchronous; use wait_valid() to block your thread until the download is complete.

The code to download the commands from a vehicle is shown below:

# Connect to API provider and get vehicle
api = local_connect()
vehicle = api.get_vehicles()[0]

# Download the vehicle waypoints (commands). Wait until download is complete.
cmds = vehicle.commands
cmds.download()
cmds.wait_valid()

The set of commands can be changed and uploaded to the client. The changes are not guaranteed to be complete until flush() is called on the parent Vehicle object.

cmds = vehicle.commands
cmds.clear()
vehicle.flush()
lat = -34.364114,
lon = 149.166022
altitude = 30.0
cmd = Command(0,0,0, mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT, mavutil.mavlink.MAV_CMD_NAV_WAYPOINT,
    0, 0, 0, 0, 0, 0,
    lat, lon, altitude)
cmds.add(cmd)
vehicle.flush()
takeoff(altitude)

Note

This function should only be used on Copter vehicles.

Take off and fly the vehicle to the specified altitude (in metres) and then wait for another command.

The vehicle must be in GUIDED mode and armed before this is called.

There is no mechanism for notification when the correct altitude is reached, and if another command arrives before that point (e.g. goto()) it will be run instead.

Warning

Apps should code to ensure that the vehicle will reach a safe altitude before other commands are executed. A good example is provided in the guide topic Taking Off.

Parameters:altitude – Target height, in metres.
add(cmd)

Add a new command (waypoint) at the end of the command list.

Parameters:cmd (Command) – The command to be added.
clear()

Clear the command list.

Warning

Call flush() immediately after clearing the commands/before adding new commands (see #132 for more information).

count

Return number of waypoints.

Returns:The number of waypoints in the sequence.
download()

Download all waypoints from the vehicle.

The download is asynchronous. Use wait_valid() to block your thread until the download is complete.

goto(location)

Go to a specified location (changing VehicleMode to GUIDED if necessary).

# Set mode to guided - this is optional as the goto method will change the mode if needed.
vehicle.mode = VehicleMode("GUIDED")

# Set the location to goto() and flush()
a_location = Location(-34.364114, 149.166022, 30, is_relative=True)
vehicle.commands.goto(a_location)
vehicle.flush()
Parameters:location (Location) – The target location.
next

Get the currently active waypoint number.

wait_valid()

Block the calling thread until waypoints have been downloaded.

This can be called after download() to block the thread until the asynchronous download is complete.

class droneapi.lib.GPSInfo(eph, epv, fix_type, satellites_visible)

Standard information available about GPS.

If there is no GPS lock the parameters are set to None.

Parameters:
  • eph (IntType) – GPS horizontal dilution of position (HDOP) in cm (m*100).
  • epv (IntType) – GPS horizontal dilution of position (VDOP) in cm (m*100).
  • fix_type (IntType) – 0-1: no fix, 2: 2D fix, 3: 3D fix
  • satellites_visible (IntType) – Number of satellites visible.
class droneapi.lib.Location(lat, lon, alt=None, is_relative=True)

A location object.

The latitude and longitude are relative to the WGS84 coordinate system. The altitude is relative to either the home position or “mean sea-level”, depending on the value of the is_relative.

For example, a location object might be defined as:

Location(-34.364114, 149.166022, 30, is_relative=True)
Parameters:
  • lat – Latitude.
  • lon – Longitude.
  • alt – Altitude in meters (either relative or absolute).
  • is_relativeTrue if the specified altitude is relative to a ‘home’ location (this is usually desirable). False to set altitude relative to “mean sea-level”.
class droneapi.lib.Parameters

This object is used to get and set the values of named parameters for a vehicle. See the following links for information about the supported parameters for each platform: Copter, Plane, Rover.

Attribute names are generated automatically based on parameter names. The example below shows how to get and set the value of a parameter. Note that ‘set’ operations are not guaranteed to be complete until flush() is called on the parent Vehicle object.

# Print the value of the THR_MIN parameter.
print "Param: %s" % vehicle.parameters['THR_MIN']

# Change the parameter value to something different.
vehicle.parameters['THR_MIN']=100
vehicle.flush()

Note

At time of writing Parameters does not implement the observer methods, and change notification for parameters is not supported.

add_attribute_observer(attr_name, observer)

Add an attribute observer.

The observer is called with the attr_name argument. This can be used to access the vehicle parameter, as shown below:

#Add observer for the vehicle's current location
vehicle.add_attribute_observer('location', location_callback)

#Callback to print the location
def location_callback(location):
    print "Location: ", vehicle.location

Note

Attribute changes will only be published for changes due to some other entity. They will not be published for changes made by the local API client (in order to prevent redundant notification for local changes).

Parameters:
  • attr_name – The attribute to watch.
  • observer – The callback to invoke when a change in the attribute is detected.
notify_observers(attr_name)

Internal function. Do not use.

This method calls observers when the named attribute has changed.

remove_all_observers()

Internal function. Do not use.

This method removes all attached observers.

remove_attribute_observer(attr_name, observer)

Remove an observer.

For example, the following line would remove a previously added vehicle ‘location’ observer called location_callback:

vehicle.remove_attribute_observer('location', location_callback)
Parameters:
  • attr_name – The attribute name that is to have an observer removed.
  • observer – The callback function to remove.
class droneapi.lib.Rangefinder(distance, voltage)

Rangefinder readings.

Parameters:
  • distance – Distance (metres). None if the vehicle doesn’t have a rangefinder.
  • voltage – Voltage (volts). None if the vehicle doesn’t have a rangefinder.
class droneapi.lib.Vehicle

The main vehicle API

Asynchronous notification on change of vehicle state is available by registering observers (callbacks) for attribute changes.

Most vehicle state is exposed through python attributes (e.g. vehicle.location). Most of these attributes are auto-populated based on the capabilities of the connected autopilot/vehicle.

Particular autopilots/vehicles may define different attributes from this standard list (extra batteries, GPIOs, etc.) However if a standard attribute is defined it must follow the rules specified below.

Autopilot specific attributes & types:

To prevent name clashes the following naming convention should be used:

  • ap_<name> - For autopilot specific parameters (apm 2.5, pixhawk etc.). For example “ap_pin5_mode” and “ap_pin5_value”.
  • user_<name> - For user specific parameters

Standard attributes & types:

location

Current Location.

attitude

Current vehicle Attitude (pitch, yaw, roll).

velocity

Current velocity as a three element list [ vx, vy, vz ] (in meter/sec).

mode

This attribute is used to get and set the current flight mode (VehicleMode).

airspeed

Current airspeed in metres/second (double).

groundspeed

Groundspeed in metres/second (double).

gps_0

GPS position information (GPSInfo).

armed

This attribute can be used to get and set the armed state of the vehicle (boolean).

The code below shows how to read the state, and to arm/disam the vehicle:

# Print the armed state for the vehicle
print "Armed: %s" % vehicle.armed

# Disarm the vehicle
vehicle.armed = False

# Arm the vehicle
vehicle.armed = True
mount_status

Current status of the camera mount (gimbal) as a three element list: [ pitch, yaw, roll ].

The values in the list are set to None if no mount is configured.

battery

Current system Battery status.

rangefinder

Rangefinder distance and voltage values.

channel_override

Warning

RC override may be useful for simulating user input and when implementing certain types of joystick control. It should not be used for direct control of vehicle channels unless there is no other choice!

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

This attribute takes a dictionary argument defining the RC output channels to be overridden (specified by channel number), and their new values. Channels that are not specified in the dictionary are not overridden. All multi-channel updates are atomic.

To cancel an override call channel_override again, setting zero for the overridden channels.

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: 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).

An example of setting and clearing the override is given below:

# Override channels 1 and 4 (only).
vehicle.channel_override = { "1" : 900, "4" : 1000 }
vehicle.flush()

# Cancel override on channel 1 and 4 by sending 0
vehicle.channel_override = { "1" : 0, "4" : 0 }
vehicle.flush()

Changed in version 1.0: This update replaces rc_override with channel_override/channel_readback documentation.

channel_readback

This read-only attribute returns a dictionary containing the original vehicle RC channel values (ignoring any overrides set using channel_override). Dictionary entries have the format channelName -> value.

For example, the returned dictionary might look like this:

RC readback: {'1': 1500, '3': 1000, '2': 1500, '5': 1800, '4': 1500, '7': 1000, '6': 1000, '8': 1800} ? Dictionary () (read only)
add_attribute_observer(attr_name, observer)

Add an attribute observer.

The observer is called with the attr_name argument. This can be used to access the vehicle parameter, as shown below:

#Add observer for the vehicle's current location
vehicle.add_attribute_observer('location', location_callback)

#Callback to print the location
def location_callback(location):
    print "Location: ", vehicle.location

Note

Attribute changes will only be published for changes due to some other entity. They will not be published for changes made by the local API client (in order to prevent redundant notification for local changes).

Parameters:
  • attr_name – The attribute to watch.
  • observer – The callback to invoke when a change in the attribute is detected.
commands

Gets the editable waypoints for this vehicle (the current “mission”).

This can be used to get, create, and modify a mission. It can also be used for direct control of vehicle position (outside missions) using the goto method.

Returns:A CommandSequence containing the waypoints for this vehicle.
flush()

It is important to understand that setting attributes/changing vehicle state may occur over a slow link.

It is not guaranteed that the effects of previous commands will be visible from reading vehicle attributes unless flush() is called first. After the return from flush any writes are guaranteed to have completed (or thrown an exception) and future reads will see their effects.

message_factory

Returns an object that can be used to create ‘raw’ MAVLink messages that are appropriate for this vehicle. The message can then be sent using send_mavlink(message).

These message types are defined in the central MAVLink github repository. For example, a Pixhawk understands the following messages (from pixhawk.xml):

<message id="153" name="IMAGE_TRIGGER_CONTROL">
     <field type="uint8_t" name="enable">0 to disable, 1 to enable</field>
</message>

The name of the factory method will always be the lower case version of the message name with _encode appended. Each field in the XML message definition must be listed as arguments to this factory method. So for this example message, the call would be:

msg = vehicle.message_factory.image_trigger_control_encode(True)
vehicle.send_mavlink(msg)

There is no need to specify the system id, component id or sequence number of messages (if defined in the message type) as the API will set these appropriately when the message is sent.

notify_observers(attr_name)

Internal function. Do not use.

This method calls observers when the named attribute has changed.

parameters

The (editable) parameters for this vehicle (Parameters).

remove_all_observers()

Internal function. Do not use.

This method removes all attached observers.

remove_attribute_observer(attr_name, observer)

Remove an observer.

For example, the following line would remove a previously added vehicle ‘location’ observer called location_callback:

vehicle.remove_attribute_observer('location', location_callback)
Parameters:
  • attr_name – The attribute name that is to have an observer removed.
  • observer – The callback function to remove.

This method is used to send raw MAVLink “custom messages” to the vehicle.

The function can send arbitrary messages/commands to a vehicle at any time and in any vehicle mode. It is particularly useful for controlling vehicles outside of missions (for example, in GUIDED mode).

The message_factory is used to create messages in the appropriate format. Callers do not need to populate sysId/componentId/crc in the packet as the method will take care of that before sending.

Parameters:message – A MAVLink_message instance, created using message_factory. There is need to specify the system id, component id or sequence number of messages as the API will set these appropriately.

Provides asynchronous notification when any MAVLink packet is received by this vehicle.

Only a single callback can be set. unset_mavlink_callback removes the callback.

Tip

This method is implemented - but we hope you don’t need it.

Because of the asynchronous attribute/waypoint/parameter notifications there should be no need for API clients to see raw MAVLink. Please provide feedback if we missed a use-case.

The code snippet below shows how to set a “demo” callback function as the callback handler:

# Demo callback handler for raw MAVLink messages
def mavrx_debug_handler(message):
    print "Received", message

# Set MAVLink callback handler (after getting Vehicle instance)
vehicle.set_mavlink_callback(mavrx_debug_handler)
Parameters:callback – The callback function to be invoked when a raw MAVLink message is received.

Clears the asynchronous notification added by set_mavlink_callback.

The code snippet below shows how to set, then clear, a MAVLink callback function.

# Set MAVLink callback handler (after getting Vehicle instance)
vehicle.set_mavlink_callback(mavrx_debug_handler)

# Remove the MAVLink callback handler. Callback will not be
# called after this point.
vehicle.unset_mavlink_callback()
class droneapi.lib.VehicleMode(name)

This object is used to get and set the current “flight mode”.

The flight mode determines the behaviour of the vehicle and what commands it can obey. The recommended flight modes for DroneKit-Python apps depend on the vehicle type:

  • Copter apps should use AUTO mode for “normal” waypoint missions and GUIDED mode otherwise.
  • Plane and Rover apps should use the AUTO mode in all cases, re-writing the mission commands if “dynamic” behaviour is required (they support only a limited subset of commands in GUIDED mode).
  • Some modes like RETURN_TO_LAUNCH can be used on all platforms. Care should be taken when using manual modes as these may require remote control input from the user.

The available set of supported flight modes is vehicle-specific (see Copter, Plane, Rover). If an unsupported mode is set the script will raise a KeyError exception.

The Vehicle.mode attribute can be queried for the current mode. The code snippet below shows how to read (print) and observe changes to the mode:

def mode_callback(self, mode):
    print "Vehicle Mode", vehicle.mode

vehicle.add_attribute_observer('mode', mode_callback)

The code snippet below shows how to change the vehicle mode to AUTO:

# Get an instance of the API endpoint and a vehicle
api = local_connect()
vehicle = api.get_vehicles()[0]

# Set the vehicle into auto mode
vehicle.mode = VehicleMode("AUTO")

For more information on getting/setting/observing the Vehicle.mode (and other attributes) see the attributes guide.

name

The mode name, as a string.

droneapi.lib.local_connect()

Connect to the API provider for the local vehicle or ground control station.

Returns:The API provider.
Return type:APIConnection