3DR
  • Cloud
  • Python
  • Android
  • Support
  • Introduction
    • About DroneKit
      • Open source community
      • Compatibility
      • API features
      • Technical support
    • Release Notes
      • Latest release
      • Changelog
        • Version 2.9.1 (2017-04-21)
        • Version 2.9.0 (2016-08-29)
        • Version 2.8.0 (2016-07-15)
        • Version 2.7.0 (2016-06-21)
        • Version 2.6.0 (2016-06-17)
        • Version 2.5.0 (2016-05-04)
        • Version 2.4.0 (2016-02-29)
        • Version 2.3.0 (2016-02-26)
        • Version 2.2.0 (2016-02-19)
        • Version 2.1.0 (2016-02-16)
        • Version 2.0.2 (2015-11-30)
        • Version 2.0.0 (2015-11-23)
      • All releases
      • Working with releases
    • Migrating to DKPY 2.0
      • Installation
      • Launching scripts
      • Code changes
        • Connecting to a vehicle
        • Connection status checks
        • Script completion checks
        • Command line arguments
        • Current script directory
        • Vehicle.location
        • Takeoff and movement commands
        • Home location
        • Missions and Waypoints
        • Observing attribute changes
        • Parameter changes
        • Intercepting MAVLink Messages
        • New attributes
        • Channel Overrides
      • Debugging
    • Open Source Licence
  • Quick Start
    • Installation
    • Basic “Hello Drone”
    • Next Steps
  • Developing
    • Installing DroneKit
    • Companion Computers
      • RaspberryPi
      • Intel Edison
      • BeagleBoneBlack
      • Odroid
    • Simulated Vehicle
      • DroneKit-SITL
        • Installation
        • Running SITL
        • Connecting to DroneKit-SITL
        • DroneKit-SITL Python API
      • Building SITL from source
      • Connecting an additional Ground Station
    • Best Practices
      • General considerations
      • Connecting
      • Launch sequence
      • Movement commands
      • Vehicle information
      • Missions and waypoints
      • Monitor and react to state changes
      • Sleep the script when not needed
      • Exiting a script
      • Subclass Vehicle
      • Debugging
      • Launching scripts
      • Current script directory
    • Coding Standards
  • Guide
    • Connecting to a Vehicle
      • Connection string options
      • Connecting to multiple vehicles
    • Vehicle State and Settings
      • Attributes
        • Getting attributes
        • Setting attributes
        • Observing attribute changes
        • Home location
      • Parameters
        • Getting parameters
        • Setting parameters
        • Listing all parameters
        • Observing parameter changes
      • Known issues
    • Taking Off
    • Guiding and Controlling Copter
      • Controlling vehicle movement
        • Position control
        • Velocity control
        • Acceleration and force control
      • Guided mode commands
        • Sending messages/commands
        • Supported commands
        • Setting the Yaw
        • Setting the ROI
        • Command acknowledgements and response values
      • Frame conversion functions
      • Other information
    • Missions
      • Mission Command Overview
      • Download current mission
      • Clearing current mission
      • Creating/adding mission commands
      • Modifying missions
      • Running and monitoring missions
      • Handling the end of a mission
      • Useful Mission functions
        • Load a mission from a file
        • Save a mission to a file
        • Get distance to waypoint
      • Useful Links
    • Debugging
      • pdb - The Python Debugger
      • pudb - A full-screen, console-based Python debugger
      • Print/log statements
      • Other IDEs/debuggers
    • MAVLink Messages
      • Creating a message listener
      • Watching all messages
      • Removing an observer
  • Examples
    • Running the Examples
    • Vehicle State
      • Running the example
      • How does it work?
      • Known issues
      • Source code
    • Simple Goto
      • Running the example
      • How does it work?
        • Takeoff
        • Flying to a point - simple_goto
        • RTL - Return to launch
      • Source code
    • Guided Movement and Commands
      • Running the example
      • How does it work?
        • goto() - convenience function
        • send_ned_velocity()
        • send_global_velocity()
        • goto_position_target_global_int()
        • goto_position_target_local_ned()
      • Testbed settings
      • Source code
    • Basic Mission
      • Running the example
      • How does it work?
      • Known issues
      • Source code
    • Mission Import/Export
      • Running the example
      • How does it work?
      • Known issues
      • Source code
    • Create Attribute in App
      • Running the example
      • How does it work?
        • Subclassing Vehicle
        • Using the Vehicle subclass
      • Known issues
      • Source code
    • Follow Me (Linux only)
      • Running the example
      • How does it work?
      • Source code
    • Drone Delivery
      • Running the example
      • Screenshots
      • How it works
        • Using attribute observers
        • Starting CherryPy from a DroneKit application
      • Known issues
      • Source code
    • Flight Replay
      • Running the example
      • How it works
        • Getting the points
        • Setting the new waypoints
      • Known issues
      • Source code
    • Channel Overrides
      • Running the example
      • How does it work?
      • Source code
  • Contributing
    • How you can Contribute
    • Contributing to the API
      • Submitting changes
      • Test code
        • Setting up local testing
        • Unit tests
        • Integration tests
    • Contributing to the Documentation
      • Documentation system overview
      • Submitting changes
      • Building the docs
      • Style guide
    • Building DroneKit-Python on Windows
      • Install DroneKit using WinPython command line
      • Fetch and build DroneKit source
      • Updating DroneKit
    • Building DroneKit-Python on Linux
      • Fetch and build DroneKit source
      • Updating DroneKit
  • API Reference
    • Index

MAVLink Messages¶

Some useful MAVLink messages sent by the autopilot are not (yet) directly available to DroneKit-Python scripts through the observable attributes in Vehicle.

This topic shows how you can intercept specific MAVLink messages by defining a listener callback function using the Vehicle.on_message() decorator.

Tip

Example: Create Attribute in App shows how you can extend this approach to create a new Vehicle attribute in your client code.

Creating a message listener¶

The Vehicle.on_message() decorator can be used to set a particular function as the callback handler for a particular message type. You can create listeners for as many messages as you like, or even multiple listeners for the same message.

For example, the code snippet below shows how to set a listener for the RANGEFINDER message:

#Create a message listener using the decorator.
@vehicle.on_message('RANGEFINDER')
def listener(self, name, message):
    print message

Tip

Every single listener can have the same name/prototpye as above (“listener”) because Python does not notice the decorated functions are in the same scope.

Unfortunately this also means that you can’t unregister a callback created using this method.

The messages are classes from the pymavlink library. The output of the code above looks something like:

RANGEFINDER {distance : 0.0899999961257, voltage : 0.00900000054389}
...

You can access the message fields directly. For example, to access the RANGEFINDER message your listener function might look like this:

#Create a message listener using the decorator.
@vehicle.on_message('RANGEFINDER')
def listener(self, name, message):
    print 'distance: %s' % message.distance
    print 'voltage: %s' % message.voltage

Watching all messages¶

You can register a callback for all messages by setting the message name as the wildcard string (‘*’):

#Create a message listener for all messages.
@vehicle.on_message('*')
def listener(self, name, message):
    print 'message: %s' % message

Removing an observer¶

Callbacks registered using the Vehicle.on_message() decorator cannot be removed. This is generally not a problem, because in most cases you’re interested in messages for the lifetime of a session.

If you do need to be able to remove messages you can instead add the callback using Vehicle.add_message_listener, and then remove it by calling Vehicle.remove_message_listener.

Next Previous

© Copyright 2015-2016, 3D Robotics.

Built with Sphinx using a theme provided by 3D Robotics for DroneKit.