This is the API Reference for the DroneKit-Python API.
The main API is the Vehicle
class.
The code snippet below shows how to use connect()
to obtain an instance of a connected vehicle:
from dronekit import connect
# Connect to the Vehicle using "connection string" (in this case an address on network)
vehicle = connect('127.0.0.1:14550', wait_ready=True)
Vehicle
provides access to vehicle state through python attributes
(e.g. Vehicle.mode
)
and to settings/parameters though the Vehicle.parameters
attribute.
Asynchronous notification on vehicle attribute changes is available by registering listeners/observers.
Vehicle movement is primarily controlled using the Vehicle.armed
attribute and
Vehicle.simple_takeoff()
and Vehicle.simple_goto
in GUIDED mode.
Velocity-based movement and control over other vehicle features can be achieved using custom MAVLink messages
(Vehicle.send_mavlink()
, Vehicle.message_factory()
).
It is also possible to work with vehicle “missions” using the Vehicle.commands
attribute, and run them in AUTO mode.
All the logging is handled through the builtin Python logging module.
A number of other useful classes and methods are listed below.
dronekit.
APIException
¶Base class for DroneKit related exceptions.
Parameters: | message (String) – Message string describing the exception |
---|
dronekit.
Attitude
(pitch, yaw, roll)¶Attitude information.
An object of this type is returned by Vehicle.attitude
.
Parameters: |
|
---|
dronekit.
Battery
(voltage, current, level)¶System battery information.
An object of this type is returned by Vehicle.battery
.
Parameters: |
|
---|
dronekit.
Capabilities
(capabilities)¶Autopilot capabilities (supported message types and functionality).
An object of this type is returned by Vehicle.capabilities
.
See the enum MAV_PROTOCOL_CAPABILITY.
New in version 2.0.3.
mission_float
¶Autopilot supports MISSION float message type (Boolean).
param_float
¶Autopilot supports the PARAM float message type (Boolean).
mission_int
¶Autopilot supports MISSION_INT scaled integer message type (Boolean).
command_int
¶Autopilot supports COMMAND_INT scaled integer message type (Boolean).
param_union
¶Autopilot supports the PARAM_UNION message type (Boolean).
ftp
¶Autopilot supports ftp for file transfers (Boolean).
set_attitude_target
¶Autopilot supports commanding attitude offboard (Boolean).
set_attitude_target_local_ned
¶Autopilot supports commanding position and velocity targets in local NED frame (Boolean).
set_altitude_target_global_int
¶Autopilot supports commanding position and velocity targets in global scaled integers (Boolean).
terrain
¶Autopilot supports terrain protocol / data handling (Boolean).
set_actuator_target
¶Autopilot supports direct actuator control (Boolean).
flight_termination
¶Autopilot supports the flight termination command (Boolean).
compass_calibration
¶Autopilot supports onboard compass calibration (Boolean).
dronekit.
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.
For more information and examples see Example: Channels and Channel Overrides.
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¶overrides
¶Attribute to read, set and clear channel overrides (also known as “rc overrides”)
associated with a Vehicle
(via Vehicle.channels
). This is an
object of type ChannelsOverride
.
For more information and examples see Example: Channels and Channel Overrides.
To set channel overrides:
# Set and clear overrids using dictionary syntax (clear by setting override to none)
vehicle.channels.overrides = {'5':None, '6':None,'3':500}
# You can also set and clear overrides using indexing syntax
vehicle.channels.overrides['2'] = 200
vehicle.channels.overrides['2'] = None
# Clear using 'del'
del vehicle.channels.overrides['3']
# Clear all overrides by setting an empty dictionary
vehicle.channels.overrides = {}
Read the channel overrides either as a dictionary or by index. Note that you’ll get
a KeyError
exception if you read a channel override that has not been set.
# Get all channel overrides
print " Channel overrides: %s" % vehicle.channels.overrides
# Print just one channel override
print " Ch2 override: %s" % vehicle.channels.overrides['2']
pop
(k[, d]) → v, remove specified key and return the corresponding value.¶If key is not found, d is returned if given, otherwise KeyError is raised
popitem
() → (k, v), remove and return some (key, value) pair as a¶2-tuple; but raise KeyError if D is empty.
setdefault
(k[, d]) → D.get(k,d), also set D[k]=d if k not in D¶update
([E, ]**F) → None. Update D from dict/iterable E and F.¶If E present and has a .keys() method, does: for k in E: D[k] = E[k] If E present and lacks .keys() method, does: for (k, v) in E: D[k] = v In either case, this is followed by: for k in F: D[k] = F[k]
values
() → list of D's values¶viewitems
() → a set-like object providing a view on D's items¶viewkeys
() → a set-like object providing a view on D's keys¶viewvalues
() → an object providing a view on D's values¶dronekit.
ChannelsOverride
(vehicle)¶A dictionary class for managing Vehicle channel overrides.
Channels can be read, written, or cleared by index or using a dictionary syntax.
To clear a value, set it to None
or use del
on the item.
An object of this type is returned by Vehicle.channels.overrides
.
For more information and examples see Example: Channels and Channel Overrides.
clear
() → None. Remove all items from D.¶copy
() → a shallow copy of D¶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¶pop
(k[, d]) → v, remove specified key and return the corresponding value.¶If key is not found, d is returned if given, otherwise KeyError is raised
popitem
() → (k, v), remove and return some (key, value) pair as a¶2-tuple; but raise KeyError if D is empty.
setdefault
(k[, d]) → D.get(k,d), also set D[k]=d if k not in D¶update
([E, ]**F) → None. Update D from dict/iterable E and F.¶If E present and has a .keys() method, does: for k in E: D[k] = E[k] If E present and lacks .keys() method, does: for (k, v) in E: D[k] = v In either case, this is followed by: for k in F: D[k] = F[k]
values
() → list of D's values¶viewitems
() → a set-like object providing a view on D's items¶viewkeys
() → a set-like object providing a view on D's keys¶viewvalues
() → an object providing a view on D's values¶dronekit.
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: |
|
---|
format_attr
(field)¶override field getter
dronekit.
CommandSequence
(vehicle)¶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_ready()
to block your thread until the download is complete.
The code to download the commands from a vehicle is shown below:
#Connect to a vehicle object (for example, on com14)
vehicle = connect('com14', wait_ready=True)
# Download the vehicle waypoints (commands). Wait until download is complete.
cmds = vehicle.commands
cmds.download()
cmds.wait_ready()
The set of commands can be changed and uploaded to the client. The changes are not guaranteed to be complete until
upload()
is called.
cmds = vehicle.commands
cmds.clear()
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)
cmds.upload()
add
(cmd)¶Add a new command (waypoint) at the end of the command list.
Note
Commands are sent to the vehicle only after you call :upload()
.
Parameters: | cmd (Command) – The command to be added. |
---|
clear
()¶Clear the command list.
This command will be sent to the vehicle only after you call upload()
.
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_ready()
to block your thread until the download is complete.
next
¶Get the currently active waypoint number.
upload
(timeout=None)¶Call upload()
after adding
or clearing
mission commands.
After the return from upload()
any writes are guaranteed to have completed (or thrown an
exception) and future reads will see their effects.
Parameters: | timeout (int) – The timeout for uploading the mission. No timeout if not provided or set to None. |
---|
wait_ready
(**kwargs)¶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.
dronekit.
GPSInfo
(eph, epv, fix_type, satellites_visible)¶Standard information about GPS.
If there is no GPS lock the parameters are set to None
.
Parameters: |
|
---|
dronekit.
Gimbal
(vehicle)¶Gimbal status and control.
An object of this type is returned by Vehicle.gimbal
. The
gimbal orientation can be obtained from its roll
, pitch
and
yaw
attributes.
The gimbal orientation can be set explicitly using rotate()
or you can set the gimbal (and vehicle) to track a specific “region of interest” using
target_location()
.
Note
None
. If a gimbal is present,
the attributes are populated shortly after initialisation by messages from the autopilot.pitch
¶Gimbal pitch in degrees relative to the vehicle (see diagram for attitude). A value of 0 represents a camera pointed straight ahead relative to the front of the vehicle, while -90 points the camera straight down.
Note
This is the last pitch value sent to the gimbal (not the actual/measured pitch).
release
()¶Release control of the gimbal to the user (RC Control).
This should be called once you’ve finished controlling the mount with either rotate()
or target_location()
. Control will automatically be released if you change vehicle mode.
roll
¶Gimbal roll in degrees relative to the vehicle (see diagram for attitude).
Note
This is the last roll value sent to the gimbal (not the actual/measured roll).
rotate
(pitch, roll, yaw)¶Rotate the gimbal to a specific vector.
#Point the gimbal straight down
vehicle.gimbal.rotate(-90, 0, 0)
Parameters: |
|
---|
target_location
(roi)¶Point the gimbal at a specific region of interest (ROI).
#Set the camera to track the current home location.
vehicle.gimbal.target_location(vehicle.home_location)
The target position must be defined in a LocationGlobalRelative
or LocationGlobal
.
This function can be called in AUTO or GUIDED mode.
In order to clear an ROI you can send a location with all zeros (e.g. LocationGlobalRelative(0,0,0)
).
Parameters: | roi – Target location in global relative frame. |
---|
yaw
¶Gimbal yaw in degrees relative to global frame (0 is North, 90 is West, 180 is South etc).
Note
This is the last yaw value sent to the gimbal (not the actual/measured yaw).
dronekit.
LocationGlobal
(lat, lon, alt=None)¶A global location object.
The latitude and longitude are relative to the WGS84 coordinate system. The altitude is relative to mean sea-level (MSL).
For example, a global location object with altitude 30 metres above sea level might be defined as:
LocationGlobal(-34.364114, 149.166022, 30)
An object of this type is owned by Vehicle.location
. See that class for information on
reading and observing location in the global frame.
Parameters: |
|
---|
dronekit.
LocationGlobalRelative
(lat, lon, alt=None)¶A global location object, with attitude relative to home location altitude.
The latitude and longitude are relative to the WGS84 coordinate system. The altitude is relative to the home position.
For example, a LocationGlobalRelative
object with an altitude of 30 metres above the home location might be defined as:
LocationGlobalRelative(-34.364114, 149.166022, 30)
An object of this type is owned by Vehicle.location
. See that class for information on
reading and observing location in the global-relative frame.
Parameters: |
|
---|
dronekit.
LocationLocal
(north, east, down)¶A local location object.
The north, east and down are relative to the EKF origin. This is most likely the location where the vehicle was turned on.
An object of this type is owned by Vehicle.location
. See that class for information on
reading and observing location in the local frame.
Parameters: |
|
---|
distance_home
()¶Distance away from home, in meters. Returns 3D distance if down is known, otherwise 2D distance.
dronekit.
Locations
(vehicle)¶An object for holding location information in global, global relative and local frames.
Vehicle
owns an object of this type. See Vehicle.location
for information on
reading and observing location in the different frames.
The different frames are accessed through the members, which are created with this object. They can be read, and are observable.
add_attribute_listener
(attr_name, observer)¶Add an attribute listener callback.
The callback function (observer
) is invoked differently depending on the type of attribute.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle “state” are
only updated when their values change (for example Vehicle.system_status
,
Vehicle.armed
, and Vehicle.mode
).
The callback can be removed using remove_attribute_listener()
.
Note
The on_attribute()
decorator performs the same operation as this method, but with
a more elegant syntax. Use add_attribute_listener
by preference if you will need to remove
the observer.
The argument list for the callback is observer(object, attr_name, attribute_value)
:
self
- the associated Vehicle
. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).attr_name
- the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.value
- the attribute value (so you don’t need to re-query the vehicle object).The example below shows how to get callbacks for (global) location changes:
#Callback to print the location in global frame
def location_callback(self, attr_name, msg):
print "Location (Global): ", msg
#Add observer for the vehicle's current location
vehicle.add_attribute_listener('global_frame', location_callback)
See Observing attribute changes for more information.
Parameters: |
|
---|
global_frame
¶Location in global frame (a LocationGlobal
).
The latitude and longitude are relative to the WGS84 coordinate system. The altitude is relative to mean sea-level (MSL).
This is accessed through the Vehicle.location
attribute:
print "Global Location: %s" % vehicle.location.global_frame
print "Sea level altitude is: %s" % vehicle.location.global_frame.alt
Its lat
and lon
attributes are populated shortly after GPS becomes available.
The alt
can take several seconds longer to populate (from the barometer).
Listeners are not notified of changes to this attribute until it has fully populated.
To watch for changes you can use Vehicle.on_attribute()
decorator or
add_attribute_listener()
(decorator approach shown below):
@vehicle.on_attribute('location.global_frame')
def listener(self, attr_name, value):
print " Global: %s" % value
#Alternatively, use decorator: ``@vehicle.location.on_attribute('global_frame')``.
global_relative_frame
¶Location in global frame, with altitude relative to the home location
(a LocationGlobalRelative
).
The latitude and longitude are relative to the
WGS84 coordinate system.
The altitude is relative to home location
.
This is accessed through the Vehicle.location
attribute:
print "Global Location (relative altitude): %s" % vehicle.location.global_relative_frame
print "Altitude relative to home_location: %s" % vehicle.location.global_relative_frame.alt
local_frame
¶Location in local NED frame (a LocationGlobalRelative
).
This is accessed through the Vehicle.location
attribute:
print "Local Location: %s" % vehicle.location.local_frame
This location will not start to update until the vehicle is armed.
notify_attribute_listeners
(attr_name, value, cache=False)¶This method is used to update attribute observers when the named attribute is updated.
You should call it in your message listeners after updating an attribute with information from a vehicle message.
By default the value of cache
is False
and every update from the vehicle is sent to listeners
(whether or not the attribute has changed). This is appropriate for attributes which represent sensor
or heartbeat-type monitoring.
Set cache=True
to update listeners only when the value actually changes (cache the previous
attribute value). This should be used where clients will only ever need to know the value when it has
changed. For example, this setting has been used for notifying mode
changes.
See Example: Create Attribute in App for more information.
Parameters: |
|
---|
on_attribute
(name)¶Decorator for attribute listeners.
The decorated function (observer
) is invoked differently depending on the type of attribute.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle “state” are
only updated when their values change (for example Vehicle.system_status()
,
Vehicle.armed
, and Vehicle.mode
).
The argument list for the callback is observer(object, attr_name, attribute_value)
self
- the associated Vehicle
. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).attr_name
- the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.msg
- the attribute value (so you don’t need to re-query the vehicle object).Note
There is no way to remove an attribute listener added with this decorator. Use
add_attribute_listener()
if you need to be able to remove
the attribute listener
.
The code fragment below shows how you can create a listener for the attitude attribute.
@vehicle.on_attribute('attitude')
def attitude_listener(self, name, msg):
print '%s attribute is: %s' % (name, msg)
See Observing attribute changes for more information.
Parameters: |
|
---|
remove_attribute_listener
(attr_name, observer)¶Remove an attribute listener (observer) that was previously added using add_attribute_listener()
.
For example, the following line would remove a previously added vehicle ‘global_frame’
observer called location_callback
:
vehicle.remove_attribute_listener('global_frame', location_callback)
See Observing attribute changes for more information.
Parameters: |
|
---|
dronekit.
Parameters
(vehicle)¶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 Parameters, Plane Parameters, Rover Parameters.
The code fragment below shows how to get and set the value of a parameter.
# 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
It is also possible to observe parameters and to iterate the Vehicle.parameters
.
For more information see the guide.
add_attribute_listener
(attr_name, *args, **kwargs)¶Add a listener callback on a particular parameter.
The callback can be removed using remove_attribute_listener()
.
Note
The on_attribute()
decorator performs the same operation as this method, but with
a more elegant syntax. Use add_attribute_listener
only if you will need to remove
the observer.
The callback function is invoked only when the parameter changes.
The callback arguments are:
self
- the associated Parameters
.attr_name
- the parameter name. This can be used to infer which parameter has triggered
if the same callback is used for watching multiple parameters.msg
- the new parameter value (so you don’t need to re-query the vehicle object).The example below shows how to get callbacks for the THR_MIN
parameter:
#Callback function for the THR_MIN parameter
def thr_min_callback(self, attr_name, value):
print " PARAMETER CALLBACK: %s changed to: %s" % (attr_name, value)
#Add observer for the vehicle's THR_MIN parameter
vehicle.parameters.add_attribute_listener('THR_MIN', thr_min_callback)
See Observing parameter changes for more information.
Parameters: |
|
---|
clear
() → None. Remove all items from D.¶get
(k[, d]) → D[k] if k in D, else d. d defaults to None.¶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¶notify_attribute_listeners
(attr_name, *args, **kwargs)¶This method is used to update attribute observers when the named attribute is updated.
You should call it in your message listeners after updating an attribute with information from a vehicle message.
By default the value of cache
is False
and every update from the vehicle is sent to listeners
(whether or not the attribute has changed). This is appropriate for attributes which represent sensor
or heartbeat-type monitoring.
Set cache=True
to update listeners only when the value actually changes (cache the previous
attribute value). This should be used where clients will only ever need to know the value when it has
changed. For example, this setting has been used for notifying mode
changes.
See Example: Create Attribute in App for more information.
Parameters: |
|
---|
on_attribute
(attr_name, *args, **kwargs)¶Decorator for parameter listeners.
Note
There is no way to remove a listener added with this decorator. Use
add_attribute_listener()
if you need to be able to remove
the listener
.
The callback function is invoked only when the parameter changes.
The callback arguments are:
self
- the associated Parameters
.attr_name
- the parameter name. This can be used to infer which parameter has triggered
if the same callback is used for watching multiple parameters.msg
- the new parameter value (so you don’t need to re-query the vehicle object).The code fragment below shows how to get callbacks for the THR_MIN
parameter:
@vehicle.parameters.on_attribute('THR_MIN')
def decorated_thr_min_callback(self, attr_name, value):
print " PARAMETER CALLBACK: %s changed to: %s" % (attr_name, value)
See Observing parameter changes for more information.
Parameters: |
|
---|
pop
(k[, d]) → v, remove specified key and return the corresponding value.¶If key is not found, d is returned if given, otherwise KeyError is raised.
popitem
() → (k, v), remove and return some (key, value) pair¶as a 2-tuple; but raise KeyError if D is empty.
remove_attribute_listener
(attr_name, *args, **kwargs)¶Remove a paremeter listener that was previously added using add_attribute_listener()
.
For example to remove the thr_min_callback()
callback function:
vehicle.parameters.remove_attribute_listener('thr_min', thr_min_callback)
See Observing parameter changes for more information.
Parameters: |
|
---|
setdefault
(k[, d]) → D.get(k,d), also set D[k]=d if k not in D¶update
([E, ]**F) → None. Update D from mapping/iterable E and F.¶If E present and has a .keys() method, does: for k in E: D[k] = E[k] If E present and lacks .keys() method, does: for (k, v) in E: D[k] = v In either case, this is followed by: for k, v in F.items(): D[k] = v
values
() → list of D's values¶wait_ready
(**kwargs)¶Block the calling thread until parameters have been downloaded
dronekit.
Rangefinder
(distance, voltage)¶Rangefinder readings.
An object of this type is returned by Vehicle.rangefinder
.
Parameters: |
|
---|
dronekit.
SystemStatus
(state)¶This object is used to get and set the current “system status”.
An object of this type is returned by Vehicle.system_status
.
state
¶The system state, as a string
.
dronekit.
TimeoutError
¶Raised by operations that have timeouts.
dronekit.
Vehicle
(handler)¶The main vehicle API.
Vehicle state is exposed through ‘attributes’ (e.g. heading
). All attributes can be
read, and some are also settable
(mode
, armed
and home_location
).
Attributes can also be asynchronously monitored for changes by registering listener callback functions.
Vehicle “settings” (parameters) are read/set using the parameters
attribute.
Parameters can be iterated and are also individually observable.
Vehicle movement is primarily controlled using the armed
attribute and
simple_takeoff()
and simple_goto()
in GUIDED mode.
It is also possible to work with vehicle “missions” using the commands
attribute,
and run them in AUTO mode.
STATUSTEXT log messages from the autopilot are handled through a separate logger. It is possible to configure the log level, the formatting, etc. by accessing the logger, e.g.:
import logging
autopilot_logger = logging.getLogger('autopilot')
autopilot_logger.setLevel(logging.DEBUG)
The guide contains more detailed information on the different ways you can use
the Vehicle
class:
Note
This class currently exposes just the attributes that are most commonly used by all
vehicle types. if you need to add additional attributes then subclass Vehicle
as demonstrated in Example: Create Attribute in App.
Please then contribute your additions back to the project!
add_attribute_listener
(attr_name, observer)¶Add an attribute listener callback.
The callback function (observer
) is invoked differently depending on the type of attribute.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle “state” are
only updated when their values change (for example Vehicle.system_status
,
Vehicle.armed
, and Vehicle.mode
).
The callback can be removed using remove_attribute_listener()
.
Note
The on_attribute()
decorator performs the same operation as this method, but with
a more elegant syntax. Use add_attribute_listener
by preference if you will need to remove
the observer.
The argument list for the callback is observer(object, attr_name, attribute_value)
:
self
- the associated Vehicle
. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).attr_name
- the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.value
- the attribute value (so you don’t need to re-query the vehicle object).The example below shows how to get callbacks for (global) location changes:
#Callback to print the location in global frame
def location_callback(self, attr_name, msg):
print "Location (Global): ", msg
#Add observer for the vehicle's current location
vehicle.add_attribute_listener('global_frame', location_callback)
See Observing attribute changes for more information.
Parameters: |
|
---|
add_message_listener
(name, fn)¶Adds a message listener function that will be called every time the specified message is received.
Tip
We recommend you use on_message()
instead of this method as it has a more elegant syntax.
This method is only preferred if you need to be able to
remove the listener
.
The callback function must have three arguments:
self
- the current vehicle.name
- the name of the message that was intercepted.message
- the actual message (a pymavlink
class).For example, in the fragment below my_method
will be called for every heartbeat message:
#Callback method for new messages
def my_method(self, name, msg):
pass
vehicle.add_message_listener('HEARTBEAT',my_method)
See MAVLink Messages for more information.
Parameters: |
|
---|
airspeed
¶Current airspeed in metres/second (double
).
This attribute is settable. The set value is the default target airspeed
when moving the vehicle using simple_goto()
(or other position-based
movement commands).
arm
(wait=True, timeout=None)¶Arm the vehicle.
If wait is True, wait for arm operation to complete before returning. If timeout is nonzero, raise a TimeouTerror if the vehicle has not armed after timeout seconds.
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/disarm 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
capabilities
¶The autopilot capabilities in a Capabilities
object.
New in version 2.0.3.
channels
¶The RC channel values from the RC Transmitter (Channels
).
The attribute can also be used to set and read RC Override (channel override) values
via Vehicle.channels.override
.
For more information and examples see Example: Channels and Channel Overrides.
To read the channels from the RC transmitter:
# 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']
commands
¶Gets the editable waypoints/current mission for this vehicle (CommandSequence
).
This can be used to get, create, and modify a mission.
Returns: | A CommandSequence containing the waypoints for this vehicle. |
---|
disarm
(wait=True, timeout=None)¶Disarm the vehicle.
If wait is True, wait for disarm operation to complete before returning. If timeout is nonzero, raise a TimeouTerror if the vehicle has not disarmed after timeout seconds.
ekf_ok
¶True
if the EKF status is considered acceptable, False
otherwise (boolean
).
flush
()¶Call flush()
after adding
or clearing
mission commands.
After the return from flush()
any writes are guaranteed to have completed (or thrown an
exception) and future reads will see their effects.
Warning
This method is deprecated. It has been replaced by
Vehicle.commands.upload()
.
gimbal
¶Gimbal object for controlling, viewing and observing gimbal status (Gimbal
).
New in version 2.0.1.
groundspeed
¶Current groundspeed in metres/second (double
).
This attribute is settable. The set value is the default target groundspeed
when moving the vehicle using simple_goto()
(or other position-based
movement commands).
heading
¶Current heading in degrees - 0..360, where North = 0 (int
).
home_location
¶The current home location (LocationGlobal
).
To get the attribute you must first download the Vehicle.commands()
.
The attribute has a value of None
until Vehicle.commands()
has been downloaded
and the autopilot has set an initial home location (typically where the vehicle first gets GPS lock).
#Connect to a vehicle object (for example, on com14)
vehicle = connect('com14', wait_ready=True)
# Download the vehicle waypoints (commands). Wait until download is complete.
cmds = vehicle.commands
cmds.download()
cmds.wait_ready()
# Get the home location
home = vehicle.home_location
The home_location
is not observable.
The attribute can be written (in the same way as any other attribute) after it has successfully
been populated from the vehicle. The value sent to the vehicle is cached in the attribute
(and can potentially get out of date if you don’t re-download Vehicle.commands
):
Warning
Setting the value will fail silently if the specified location is more than 50km from the EKF origin.
is_armable
¶Returns True
if the vehicle is ready to arm, false otherwise (Boolean
).
This attribute wraps a number of pre-arm checks, ensuring that the vehicle has booted, has a good GPS fix, and that the EKF pre-arm is complete.
last_heartbeat
¶Time since last MAVLink heartbeat was received (in seconds).
The attribute can be used to monitor link activity and implement script-specific timeout handling.
For example, to pause the script if no heartbeat is received for more than 1 second you might implement
the following observer, and use pause_script
in a program loop to wait until the link is recovered:
pause_script=False
@vehicle.on_attribute('last_heartbeat')
def listener(self, attr_name, value):
global pause_script
if value > 1 and not pause_script:
print "Pausing script due to bad link"
pause_script=True;
if value < 1 and pause_script:
pause_script=False;
print "Un-pausing script"
The observer will be called at the period of the messaging loop (about every 0.01 seconds). Testing
on SITL indicates that last_heartbeat
averages about .5 seconds, but will rarely exceed 1.5 seconds
when connected. Whether heartbeat monitoring can be useful will very much depend on the application.
Note
If you just want to change the heartbeat timeout you can modify the heartbeat_timeout
parameter passed to the connect()
function.
location
¶The vehicle location in global, global relative and local frames (Locations
).
The different frames are accessed through its members:
global_frame
(LocationGlobal
)global_relative_frame
(LocationGlobalRelative
)local_frame
(LocationLocal
)For example, to print the location in each frame for a vehicle
:
# Print location information for `vehicle` in all frames (default printer)
print "Global Location: %s" % vehicle.location.global_frame
print "Global Location (relative altitude): %s" % vehicle.location.global_relative_frame
print "Local Location: %s" % vehicle.location.local_frame #NED
# Print altitudes in the different frames (see class definitions for other available information)
print "Altitude (global frame): %s" % vehicle.location.global_frame.alt
print "Altitude (global relative frame): %s" % vehicle.location.global_relative_frame.alt
print "Altitude (NED frame): %s" % vehicle.location.local_frame.down
Note
All the location “values” (e.g. global_frame.lat
) are initially
created with value None
. The global_frame
, global_relative_frame
latitude and longitude values are populated shortly after initialisation but
global_frame.alt
may take a few seconds longer to be updated.
The local_frame
does not populate until the vehicle is armed.
The attribute and its members are observable. To watch for changes in all frames using a listener created using a decorator (you can also define a listener and explicitly add it).
@vehicle.on_attribute('location')
def listener(self, attr_name, value):
# `self`: :py:class:`Vehicle` object that has been updated.
# `attr_name`: name of the observed attribute - 'location'
# `value` is the updated attribute value (a :py:class:`Locations`). This can be queried for the frame information
print " Global: %s" % value.global_frame
print " GlobalRelative: %s" % value.global_relative_frame
print " Local: %s" % value.local_frame
To watch for changes in just one attribute (in this case global_frame
):
@vehicle.on_attribute('location.global_frame')
def listener(self, attr_name, value):
# `self`: :py:class:`Locations` object that has been updated.
# `attr_name`: name of the observed attribute - 'global_frame'
# `value` is the updated attribute value.
print " Global: %s" % value
#Or watch using decorator: ``@vehicle.location.on_attribute('global_frame')``.
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)
.
Note
Vehicles support a subset of the messages defined in the MAVLink standard. For more information about the supported sets see wiki topics: Copter Commands in Guided Mode and Plane Commands in Guided Mode.
All 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)
Some message types include “addressing information”. If present, there is no need to specify the target_system
id (just set to zero) as DroneKit will automatically update messages with the correct ID for the connected
vehicle before sending.
The target_component
should be set to 0 (broadcast) unless the message is to specific component.
CRC fields and sequence numbers (if defined in the message type) are automatically set by DroneKit and can also
be ignored/set to zero.
For more information see the guide topic: Sending messages/commands.
mode
¶This attribute is used to get and set the current flight mode. You
can specify the value as a VehicleMode
, like this:
vehicle.mode = VehicleMode('LOITER')
Or as a simple string:
vehicle.mode = 'LOITER'
If you are targeting ArduPilot you can also specify the flight mode using a numeric value (this will not work with PX4 autopilots):
# set mode to LOITER
vehicle.mode = 5
mount_status
¶Warning
This method is deprecated. It has been replaced by gimbal
.
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.
notify_attribute_listeners
(attr_name, value, cache=False)¶This method is used to update attribute observers when the named attribute is updated.
You should call it in your message listeners after updating an attribute with information from a vehicle message.
By default the value of cache
is False
and every update from the vehicle is sent to listeners
(whether or not the attribute has changed). This is appropriate for attributes which represent sensor
or heartbeat-type monitoring.
Set cache=True
to update listeners only when the value actually changes (cache the previous
attribute value). This should be used where clients will only ever need to know the value when it has
changed. For example, this setting has been used for notifying mode
changes.
See Example: Create Attribute in App for more information.
Parameters: |
|
---|
on_attribute
(name)¶Decorator for attribute listeners.
The decorated function (observer
) is invoked differently depending on the type of attribute.
Attributes that represent sensor values or which are used to monitor connection status are updated
whenever a message is received from the vehicle. Attributes which reflect vehicle “state” are
only updated when their values change (for example Vehicle.system_status()
,
Vehicle.armed
, and Vehicle.mode
).
The argument list for the callback is observer(object, attr_name, attribute_value)
self
- the associated Vehicle
. This may be compared to a global vehicle handle
to implement vehicle-specific callback handling (if needed).attr_name
- the attribute name. This can be used to infer which attribute has triggered
if the same callback is used for watching several attributes.msg
- the attribute value (so you don’t need to re-query the vehicle object).Note
There is no way to remove an attribute listener added with this decorator. Use
add_attribute_listener()
if you need to be able to remove
the attribute listener
.
The code fragment below shows how you can create a listener for the attitude attribute.
@vehicle.on_attribute('attitude')
def attitude_listener(self, name, msg):
print '%s attribute is: %s' % (name, msg)
See Observing attribute changes for more information.
Parameters: |
|
---|
on_message
(name)¶Decorator for message listener callback functions.
Tip
This is the most elegant way to define message listener callback functions.
Use add_message_listener()
only if you need to be able to
remove the listener
later.
A decorated message listener function is called with three arguments every time the specified message is received:
self
- the current vehicle.name
- the name of the message that was intercepted.message
- the actual message (a pymavlink
class).For example, in the fragment below my_method
will be called for every heartbeat message:
@vehicle.on_message('HEARTBEAT')
def my_method(self, name, msg):
pass
See MAVLink Messages for more information.
Parameters: | name (String) – The name of the message to be intercepted by the decorated listener function (or ‘*’ to get all messages). |
---|
parameters
¶The (editable) parameters for this vehicle (Parameters
).
play_tune
(tune)¶Play a tune on the vehicle
rangefinder
¶Rangefinder distance and voltage values (Rangefinder
).
reboot
()¶Requests an autopilot reboot by sending a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN
command.
remove_attribute_listener
(attr_name, observer)¶Remove an attribute listener (observer) that was previously added using add_attribute_listener()
.
For example, the following line would remove a previously added vehicle ‘global_frame’
observer called location_callback
:
vehicle.remove_attribute_listener('global_frame', location_callback)
See Observing attribute changes for more information.
Parameters: |
|
---|
remove_message_listener
(name, fn)¶Removes a message listener (that was previously added using add_message_listener()
).
See MAVLink Messages for more information.
Parameters: |
|
---|
send_calibrate_accelerometer
(simple=False)¶Request accelerometer calibration.
Parameters: | simple – if True, perform simple accelerometer calibration |
---|
send_calibrate_barometer
()¶Request barometer calibration.
send_calibrate_gyro
()¶Request gyroscope calibration.
send_calibrate_magnetometer
()¶Request magnetometer calibration.
send_calibrate_vehicle_level
()¶Request vehicle level (accelerometer trim) calibration.
send_capabilities_request
(vehicle, name, m)¶Request an AUTOPILOT_VERSION packet
send_capabilties_request
(vehicle, name, m)¶An alias for send_capabilities_request.
The word “capabilities” was misspelled in previous versions of this code. This is simply an alias to send_capabilities_request using the legacy name.
send_mavlink
(message)¶This method is used to send raw MAVLink “custom messages” to the vehicle.
The function can send arbitrary messages/commands to the connected 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.
For more information see the guide topic: Sending messages/commands.
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. |
---|
simple_goto
(location, airspeed=None, groundspeed=None)¶Go to a specified global location (LocationGlobal
or LocationGlobalRelative
).
There is no mechanism for notification when the target location is reached, and if another command arrives before that point that will be executed immediately.
You can optionally set the desired airspeed or groundspeed (this is identical to setting
airspeed
or groundspeed
). The vehicle will determine what speed to
use if the values are not set or if they are both set.
The method will change the VehicleMode
to GUIDED
if necessary.
# Set mode to guided - this is optional as the simple_goto method will change the mode if needed.
vehicle.mode = VehicleMode("GUIDED")
# Set the LocationGlobal to head towards
a_location = LocationGlobal(-34.364114, 149.166022, 30)
vehicle.simple_goto(a_location)
Parameters: |
|
---|
simple_takeoff
(alt=None)¶Take off and fly the vehicle to the specified altitude (in metres) and then wait for another command.
Note
This function should only be used on Copter vehicles.
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. simple_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: | alt – Target height, in metres. |
---|
system_status
¶System status (SystemStatus
).
The status has a state
property with one of the following values:
UNINIT
: Uninitialized system, state is unknown.BOOT
: System is booting up.CALIBRATING
: System is calibrating and not flight-ready.STANDBY
: System is grounded and on standby. It can be launched any time.ACTIVE
: System is active and might be already airborne. Motors are engaged.CRITICAL
: System is in a non-normal flight mode. It can however still navigate.EMERGENCY
: System is in a non-normal flight mode. It lost control over parts
or over the whole airframe. It is in mayday and going down.POWEROFF
: System just initialized its power-down sequence, will shut down now.velocity
¶Current velocity as a three element list [ vx, vy, vz ]
(in meter/sec).
wait_for
(condition, timeout=None, interval=0.1, errmsg=None)¶Wait for a condition to be True.
Wait for condition, a callable, to return True. If timeout is nonzero, raise a TimeoutError(errmsg) if the condition is not True after timeout seconds. Check the condition everal interval seconds.
wait_for_alt
(alt, epsilon=0.1, rel=True, timeout=None)¶Wait for the vehicle to reach the specified altitude.
Wait for the vehicle to get within epsilon meters of the given altitude. If rel is True (the default), use the global_relative_frame. If rel is False, use the global_frame. If timeout is nonzero, raise a TimeoutError if the specified altitude has not been reached after timeout seconds.
wait_for_armable
(timeout=None)¶Wait for the vehicle to become armable.
If timeout is nonzero, raise a TimeoutError if the vehicle is not armable after timeout seconds.
wait_for_mode
(mode, timeout=None)¶Set the flight mode.
If wait is True, wait for the mode to change before returning. If timeout is nonzero, raise a TimeoutError if the flight mode hasn’t changed after timeout seconds.
wait_ready
(*types, **kwargs)¶Waits for specified attributes to be populated from the vehicle (values are initially None
).
This is typically called “behind the scenes” to ensure that connect()
does not return until
attributes have populated (via the wait_ready
parameter). You can also use it after connecting to
wait on a specific value(s).
There are two ways to call the method:
#Wait on default attributes to populate
vehicle.wait_ready(True)
#Wait on specified attributes (or array of attributes) to populate
vehicle.wait_ready('mode','airspeed')
Using the wait_ready(True)
waits on parameters
, gps_0
,
armed
, mode
, and attitude
. In practice this usually
means that all supported attributes will be populated.
By default, the method will timeout after 30 seconds and raise an exception if the attributes were not populated.
Parameters: |
|
---|
dronekit.
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:
AUTO
mode for “normal” waypoint missions and GUIDED
mode otherwise.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).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 Modes,
Plane Modes,
Rover Modes). 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 observe changes to the mode and then read the value:
#Callback definition for mode observer
def mode_callback(self, attr_name):
print "Vehicle Mode", self.mode
#Add observer callback for attribute `mode`
vehicle.add_attribute_listener('mode', mode_callback)
The code snippet below shows how to change the vehicle mode to AUTO:
# 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
.
dronekit.
Version
(raw_version, autopilot_type, vehicle_type)¶Autopilot version and type.
An object of this type is returned by Vehicle.version
.
The version number can be read in a few different formats. To get it in a human-readable format, just print vehicle.version. This might print something like “APM:Copter-3.3.2-rc4”.
New in version 2.0.3.
major
¶Major version number (integer).
patch
¶Patch version number (integer).
release
¶Release type (integer). See the enum FIRMWARE_VERSION_TYPE.
This is a composite of the product release cycle stage (rc, beta etc) and the version in that cycle - e.g. 23.
is_stable
()¶Returns True if the autopilot reports that the current firmware is a stable release (not a pre-release or development version).
release_type
()¶Returns text describing the release type e.g. “alpha”, “stable” etc.
release_version
()¶Returns the version within the release type (an integer). This method returns “23” for Copter-3.3rc23.
dronekit.
connect
(ip, _initialize=True, wait_ready=None, timeout=30, still_waiting_callback=<function default_still_waiting_callback>, still_waiting_interval=1, status_printer=None, vehicle_class=None, rate=4, baud=115200, heartbeat_timeout=30, source_system=255, source_component=0, use_native=False)¶Returns a Vehicle
object connected to the address specified by string parameter ip
.
Connection string parameters (ip
) for different targets are listed in the getting started guide.
The method is usually called with wait_ready=True
to ensure that vehicle parameters and (most) attributes are
available when connect()
returns.
from dronekit import connect
# Connect to the Vehicle using "connection string" (in this case an address on network)
vehicle = connect('127.0.0.1:14550', wait_ready=True)
Parameters: |
|
---|---|
Returns: | A connected vehicle of the type defined in |