Vehicle State and Settings

The Vehicle class exposes most state information (position, speed, etc.) through python attributes, while vehicle parameters (settings) are accessed though named elements of Vehicle.parameters.

This topic explains how to get, set and observe vehicle state and parameter information (including getting the Home location). It also describes a few APIs that should be used with caution.


You can test most of the code in this topic by running the Vehicle State example.


Vehicle state information is exposed through vehicle attributes. DroneKit-Python currently supports the following “standard” attributes: Vehicle.location, Vehicle.attitude, Vehicle.velocity, Vehicle.airspeed, Vehicle.groundspeed, Vehicle.gps_0, Vehicle.mount_status, Vehicle.battery, Vehicle.rangefinder, Vehicle.armed, Vehicle.mode.

All of the attributes can be read and observed, but only the Vehicle.mode and Vehicle.armed status can be written.

Getting attributes

The code fragment below shows how to read and print all the attributes. The values are retrieved from the remote device (not cached).

# vehicle is an instance of the Vehicle class
print "Location: %s" % vehicle.location
print "Attitude: %s" % vehicle.attitude
print "Velocity: %s" % vehicle.velocity
print "GPS: %s" % vehicle.gps_0
print "Groundspeed: %s" % vehicle.groundspeed
print "Airspeed: %s" % vehicle.airspeed
print "Mount status: %s" % vehicle.mount_status
print "Battery: %s" % vehicle.battery
print "Rangefinder: %s" % vehicle.rangefinder
print "Rangefinder distance: %s" % vehicle.rangefinder.distance
print "Rangefinder voltage: %s" % vehicle.rangefinder.voltage
print "Mode: %s" %    # settable
print "Armed: %s" % vehicle.armed    # settable

If an attribute cannot be retrieved then the returned object will contain None values for its members (for example, if there was no GPS lock then Vehicle.gps_0 would return a GPSInfo with None values for eph, satellites_visible etc.) Attributes will also return None if the associated hardware is not present on the connected device.


If you’re using a simulated vehicle you can add support for optional hardware including rangefinders and optical flow sensors.

Setting attributes

Only the Vehicle.mode and Vehicle.armed attributes can be written.

The attributes are set by assigning a value. Calling Vehicle.flush() then forces DroneKit to send outstanding messages.

#disarm the vehicle
vehicle.armed = False
vehicle.flush()  # Flush to ensure changes are sent to autopilot


After flush() returns the message is guaranteed to have been sent to the autopilot, but it is not guaranteed to succeed. For example, vehicle arming can fail if the vehicle doesn’t pass pre-arming checks.

While the autopilot does send information about the success (or failure) of the request, this is not currently handled by DroneKit.

Code should not assume that an attempt to set an attribute will succeed. The example code snippet below polls the attribute values to confirm they have changed before proceeding.

vehicle.mode = VehicleMode("GUIDED")
vehicle.armed = True
vehicle.flush()  # Flush to ensure changes are sent to autopilot
while not'GUIDED' and not vehicle.armed and not api.exit:
    print " Getting ready to take off ..."

Observing attribute changes

You can observe any of the attributes and will receive notification every time a value is received from the connected vehicle. This allows you to monitor changes to velocity and other vehicle state without the need for polling.

Observers are added using Vehicle.add_attribute_observer(), specifying the name of the attribute to observe and a callback function. The same string is passed to the callback when it is notified. Observers are removed using remove_attribute_observer().

The code snippet below shows how to add (and remove) a callback function to observe location attribute changes. The two second sleep() is required because otherwise the observer might be removed before the the callback is first run.

# Callback function. The parameter is the name of the observed attribute (a string)
def location_callback(attribute):
    print " CALLBACK: Location changed to: ", vehicle.location

# Add a callback. The first parameter the name of the observed attribute (a string).
vehicle.add_attribute_observer('location', location_callback)

# Wait 2s so callback can be notified before the observer is removed

# Remove observer - specifying the attribute and previously registered callback function
vehicle.remove_attribute_observer('location', location_callback)

The callback is triggered every time a message is received from the vehicle (whether or not the observed attribute changes). Callback code may therefore choose to cache the result and only report changes. For example, the following code can be used in the callback to only print output when the value of Vehicle.rangefinder changes.


def rangefinder_callback(rangefinder):
    global last_rangefinder_distance
    if last_rangefinder_distance == round(vehicle.rangefinder.distance, 1):
    last_rangefinder_distance = round(vehicle.rangefinder.distance, 1)
    print " Rangefinder (metres): %s" % last_rangefinder_distance

vehicle.add_attribute_observer('rangefinder', rangefinder_callback)


Vehicle parameters provide the information used to configure the autopilot for the vehicle-specific hardware/capabilities. These can be read and set using the Vehicle.parameters attribute (a Parameters object).


Copter Parameters, Plane Parameters, and Rover Parameters list all the supported parameters for each platform. The lists are automatically generated from the latest ArduPilot source code, and may contain parameters that are not yet in the stable released versions of the code.

Getting parameters

The parameters are read using the parameter name as a key. Reads will generally succeed unless you attempt to read an unsupported parameter (which results in a Key error exception).

The code example below shows how to set Minimum Throttle (THR_MIN) setting. On Copter and Rover (not Plane), this is the minimum PWM setting for the throttle at which the motors will keep spinning.

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

Setting parameters

Vehicle parameters are set as shown in the code fragment below, using the parameter name as a “key”. As with attributes, the values are not guaranteed to have been sent to the vehicle until after flush() returns.

# Change the parameter value (Copter, Rover)

Observing parameter changes

At time of writing Parameters does not support observing parameter changes.

Home location

The Home location is set when a vehicle is armed and first gets a good location fix from the GPS. The location is used as the target when the vehicle does a “return to launch”. In Copter missions (and most Plane) missions, the altitude of waypoints is set relative to this position.

Unlike other vehicle state information, the home location is accessed as the 0 index value of Vehicle.commands:

cmds = vehicle.commands
print " Home WP: %s" % cmds[0]

The returned value is a Command object.

Discommended APIs

This section describes methods that we recommend you do not use! In general they are provided to handle the (hopefully rare) cases where the “proper” API is missing some needed functionality.

If you have to use these methods please provide feedback explaining why.

Channel Overrides


Channel Overrides may be useful for simulating user input and when implementing certain types of joystick control. They should not be used for direct control of the vehicle 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.

The channel_override 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 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).

An example of setting and clearing overrides is given below:

# Override the channel for roll and yaw
vehicle.channel_override = { "1" : 900, "4" : 1000 }

#print current override values
print "Current overrides are:", vehicle.channel_override

# Print channel values (values if overrides removed)
print "Channel default values:", vehicle.channel_readback

# Cancel override by setting channels to 0
vehicle.channel_override = { "1" : 0, "4" : 0 }