This guide provides a broad overview of how to use the API, its main programming idioms and best practices. More detail information is linked from each section.
DroneKit-Python communicates with vehicle autopilots using the MAVLink protocol, which defines how commands, telemetry and vehicle settings/parameters are sent between vehicles, companion computers, ground stations and other systems on a MAVLink network.
Some general considerations from using this protocol are:
Developers should code defensively. Where possible:
Vehicle.is_armable
before trying to arm the vehicle).GUIDED
your script should
stop sending commands.In most cases you’ll use the normal way to connect to a vehicle,
setting wait_ready=True
to ensure that the vehicle is already populated with attributes
when the connect()
returns:
from dronekit import connect
# Connect to the Vehicle (in this case a UDP endpoint)
vehicle = connect('REPLACE_connection_string_for_your_vehicle', wait_ready=True)
The connect()
call will sometimes fail with an exception.
Additional information about an exception can be obtained by
running the connect within a try-catch
block as shown:
import dronekit
import socket
import exceptions
try:
dronekit.connect('REPLACE_connection_string_for_your_vehicle', heartbeat_timeout=15)
# Bad TCP connection
except socket.error:
print 'No server exists!'
# Bad TTY connection
except exceptions.OSError as e:
print 'No serial exists!'
# API Error
except dronekit.APIException:
print 'Timeout!'
# Other error
except:
print 'Some other error!'
Tip
The default heartbeat_timeout
on connection is 30 sections. Usually a connection will
succeed quite quickly, so you may wish to reduce this in the connect()
method as shown in the
code snippet above.
If a connection succeeds from a ground station, but not from DroneKit-Python it may be that your baud
rate is incorrect for your hardware. This rate can also be set in the connect()
method.
Generally you should use the standard launch sequence described in Taking Off:
Vehicle.is_armable
until the vehicle is ready to arm.Vehicle.mode
to GUIDED
Vehicle.armed
to True
and
poll on the same attribute until the vehicle is armed.Vehicle.simple_takeoff
with a target altitude.The approach ensures that commands are only sent to the vehicle when it is able
to act on them (e.g. we know Vehicle.is_armable
is True
before trying to arm, we know
Vehicle.armed
is True
before we take off).
It also makes debugging takeoff problems a lot easier.
DroneKit-Python provides Vehicle.simple_goto
for moving to a specific position (at a defined speed). It is also possible to control movement by sending commands to specify the vehicle’s velocity components.
Note
As with Vehicle.simple_takeoff
, movement
commands are asynchronous, and will be interrupted if another command arrives
before the vehicle reaches its target. Calling code should block and wait (or
check that the operation is complete) before preceding to the next command.
For more information see: Guiding and Controlling Copter.
Vehicle state information is exposed through vehicle attributes which can be read and observed (and in some cases written) and vehicle settings which can be read, written, iterated and observed using parameters (a special attribute). All the attributes are documented in Vehicle State and Settings.
Attributes are populated by MAVLink messages from the vehicle. Information read from an attribute may not precisely reflect the actual value on the vehicle. Commands sent to the vehicle may not arrive, or may be ignored by the autopilot.
If low-latency is critical, we recommend you verify that the update rate is achievable and
perhaps modify script behaviour if Vehicle.last_heartbeat
falls outside
a useful range.
When setting attributes, poll their values to confirm that they have changed. This applies, in particular,
to Vehicle.armed
and Vehicle.mode
.
DroneKit-Python can also create and modify autonomous missions.
While it is possible to construct DroneKit-Python apps by dynamically constructing missions “on the fly”, we recommend you use guided mode for Copter apps. This generally results in a better experience.
Tip
If a mission command is not available in guided mode, it can be useful to switch to a mission and call it, then change back to normal guided mode operation.
Almost all attributes can be observed - see Observing attribute changes for more information.
Exactly what state information you observe, and how you react to it, depends on your particular script:
Vehicle.mode
and
stop sending commands if the mode changes unexpectedly (this usually indicates
that the user has taken control of the vehicle).Vehicle.last_heartbeat
and could attempt to reconnect if the value gets too high.Vehicle.system_status
for CRITICAL
or EMERGENCY
in order to implement specific emergency handling.Sleeping your script can reduce the CPU overhead.
For example, at low speeds you might only need to check whether you’ve reached a target every few seconds.
Using time.sleep(2)
between checks will be more efficient than checking more often.
Scripts should call Vehicle.close()
before exiting to ensure that all messages have flushed before the script completes:
# About to exit script
vehicle.close()
If you need to use functionality that is specific to particular hardware, we
recommend you subclass Vehicle
and pass this new class into
connect()
.
Example: Create Attribute in App shows how you can do this.
DroneKit-Python apps are ordinary standalone Python scripts, and can be debugged using standard Python methods (including the debugger/IDE of your choice).
Scripts are run from an ordinary Python command prompt. For example:
python some_python_script.py [arguments]
Command line arguments are passed into the script as sys.argv
variables (the normal)
and you can use these directly or via an argument parser (e.g.
argparse).
You can use normal Python methods for getting file system information:
import os.path
full_directory_path_of_current_script = os.path.dirname(os.path.abspath(__file__))