Example: Vehicle State

This example shows how to get/set vehicle attribute, parameter and channel-override information, how to observe vehicle attribute changes, and how to get the home position.

The guide topic Vehicle State and Settings provides a more detailed explanation of how the API should be used.

Running the example

The vehicle and DroneKit should be set up as described in Getting Started.

If you’re using a simulated vehicle remember to disable arming checks so that the example can run. You can also add a virtual rangefinder (otherwise the Vehicle.rangefinder attribute may return values of None for the distance and voltage).

Once MAVProxy is running and the API is loaded, you can start the example by typing: api start vehicle_state.py.


The command above assumes you started the MAVProxy prompt in a directory containing the example script. If not, you will have to specify the full path to the script (something like): api start /home/user/git/dronekit-python/examples/vehicle_state/vehicle_state.py.

On the MAVProxy console you should see (something like):

MAV> api start vehicle_state.py

Get all vehicle attribute values:
 Location:  Attitude: Attitude:pitch=-0.00405988190323,yaw=-0.0973932668567,roll=-0.00393210304901
 Velocity: [0.06, -0.07, 0.0]
 GPS: GPSInfo:fix=3,num_sat=10
 Groundspeed: 0.0
 Airspeed: 0.0
 Mount status: [None, None, None]
 Battery: Battery voltage: 12590, current: 0, level: 99
 Rangefinder: Rangefinder: distance=0.189999997616, voltage=0.0190000012517
 Rangefinder distance: 0.189999997616
 Rangefinder voltage: 0.0190000012517
 Armed: False
Set Vehicle.mode=GUIDED (currently: STABILIZE)
 Waiting for mode change ...
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
Set Vehicle.armed=True (currently: False)
 Waiting for arming...
APM: Initialising APM...
Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}

Add mode attribute observer for Vehicle.mode
 Set mode=STABILIZE (currently: GUIDED)
 Wait 2s so callback invoked before observer removed
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
 CALLBACK: Mode changed to:  STABILIZE

Get home location
Requesting 0 waypoints t=Fri May 15 11:35:58 2015 now=Fri May 15 11:35:58 2015
 Home WP: MISSION_ITEM {target_system : 255, target_component : 0, seq : 0, frame : 0, command : 16, current : 0, autocontinue : 1, param1 : 0.0, param2 : 0.0, param3 : 0.0, param4 : 0.0, x : -35.3632621765, y : 149.165237427, z : 583.729980469}

Read vehicle param 'THR_MIN': 130.0
Write vehicle param 'THR_MIN' : 10
timeout setting THR_MIN to 10.000000
Read new value of param 'THR_MIN': 10.0

Set MAVLink callback handler (start receiving all MAVLink messages)
Wait 1s so mavrx_debug_handler has a chance to be called before it is removed
Raw MAVLink message:  RAW_IMU {time_usec : 894620000, xacc : -3, yacc : 10, zacc : -999, xgyro : 1, ygyro : 0, zgyro : 1, xmag : 153, ymag : 52, zmag : -364}
Raw MAVLink message:  SCALED_PRESSURE {time_boot_ms : 895340, press_abs : 945.038024902, press_diff : 0.0, temperature : 2600}
Remove the MAVLink callback handler (stop getting messages)

Overriding RC channels for roll and yaw
 Current overrides are: {'1': 900, '4': 1000}
 Channel default values: {'1': 1500, '3': 1000, '2': 1500, '5': 1800, '4': 1500, '7': 1000, '6': 1000, '8': 1800}
 Cancelling override

Reset vehicle attributes/parameters and exit
Got MAVLink msg: COMMAND_ACK {command : 11, result : 0}
Got MAVLink msg: COMMAND_ACK {command : 400, result : 0}
timeout setting THR_MIN to 130.000000
APIThread-0 exiting...

How does it work?

The guide topic Vehicle State and Settings provides an explanation of how this code works.

Known issues

This example works around the known issues in the API. Provided that the vehicle is connected and able to arm, it should run through to completion.

Two cases where you may observe issues are:

Source code

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

vehicle_state.py: Get and set vehicle state, parameter and channel-override information. 

It also demonstrates how to observe vehicle attribute (state) changes. 

Full documentation is provided at http://python.dronekit.io/examples/vehicle_state.html

from droneapi.lib import VehicleMode
from pymavlink import mavutil
import time

# First get an instance of the API endpoint
api = local_connect()
# Get the connected vehicle (currently only one vehicle can be returned).
vehicle = api.get_vehicles()[0]

# Get all vehicle attributes (state)
print "\nGet all vehicle attribute values:"
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" % vehicle.mode.name    # settable
print " Armed: %s" % vehicle.armed    # settable

# Set vehicle mode and armed attributes (the only settable attributes)
print "Set Vehicle.mode=GUIDED (currently: %s)" % vehicle.mode.name 
vehicle.mode = VehicleMode("GUIDED")
vehicle.flush()  # Flush to guarantee that previous writes to the vehicle have taken place
while not vehicle.mode.name=='GUIDED' and not api.exit:  #Wait until mode has changed
    print " Waiting for mode change ..."

print "Set Vehicle.armed=True (currently: %s)" % vehicle.armed 
vehicle.armed = True
while not vehicle.armed and not api.exit:
    print " Waiting for arming..."

# Show how to add and remove and attribute observer callbacks (using mode as example) 
def mode_callback(attribute):
    print " CALLBACK: Mode changed to: ", vehicle.mode.name

print "\nAdd mode attribute observer for Vehicle.mode" 
vehicle.add_attribute_observer('mode', mode_callback)	

print " Set mode=STABILIZE (currently: %s)" % vehicle.mode.name 
vehicle.mode = VehicleMode("STABILIZE")

print " Wait 2s so callback invoked before observer removed"

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

# Get Vehicle Home location ((0 index in Vehicle.commands)
print "\nGet home location" 
cmds = vehicle.commands
print " Home WP: %s" % cmds[0]

# Get/Set Vehicle Parameters
print "\nRead vehicle param 'THR_MIN': %s" % vehicle.parameters['THR_MIN']
print "Write vehicle param 'THR_MIN' : 10"
print "Read new value of param 'THR_MIN': %s" % vehicle.parameters['THR_MIN']

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

print "\nSet MAVLink callback handler (start receiving all MAVLink messages)"                 

print "Wait 1s so mavrx_debug_handler has a chance to be called before it is removed"

print "Remove the MAVLink callback handler (stop getting messages)"  

# Overriding an RC channel
# NOTE: CHANNEL OVERRIDES may be useful for simulating user input and when implementing certain types of joystick control. 
#DO NOT use unless there is no other choice (there almost always is!)
print "\nOverriding RC channels for roll and yaw"
vehicle.channel_override = { "1" : 900, "4" : 1000 }
print " Current overrides are:", vehicle.channel_override
print " Channel default values:", vehicle.channel_readback  # All channel values before override

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

## Reset variables to sensible values.
print "\nReset vehicle attributes/parameters and exit"
vehicle.mode = VehicleMode("STABILIZE")
vehicle.armed = False