Getting started with MAVSDK – Python

Getting started with MAVSDK-Python

Author: Jonas Vautherin | Auterion Software Engineer and MAVSDK core maintainer

Following my presentation at the first PX4 DevSummit last summer, this post will focus on showing, step by step, how to get up and running with a drone using MAVSDK-Python. No particular knowledge of MAVSDK or MAVLink is expected here, except for two prerequisites: having a drone (preferably a simulated one, for a start), and running a version of Python no older than 3.6. Don’t worry if you don’t have that, as I will give you the right directions on this blog. Currently, the latest version of MAVSDK-Python is 0.3.0. For the impatients who already satisfy the prerequisites, feel free to jump to “Quick Start” below. But before we get started, let’s try to understand why we do this and who this is for.

The Goal

Every single use case involving a drone requires a ground station or a connection to the cloud: one needs to plan a mission, check that the drone is ready to fly, and control the mission during the flight. Most drone manufacturers provide an SDK to control their products, and the PX4 open source community is no different in this regard. What are the advantages of MAVSDK?

  • Designed for speed and efficiency

  • Offers multi-language support

  • Is available in multiple development environments

  • Runs on any device using MAVLink

  • Allows plugin integration

With MAVSDK we also aim at serving different actors, e.g. service providers and drone manufacturers, to share and collaborate on a common API without preventing them from diversifying. All drones provide telemetry and basic mission features, but let’s say one drone carries a very specific sensor, in that case, a drone manufacturer should be able to add unilateral support for this sensor without even open sourcing it.

What is MAVSDK?

MAVSDK is a set of libraries providing a high-level API to MAVLink, providing easy to learn programmatic access to vehicle information and telemetry, as well as control over missions, movement, and other operations.

What does that mean exactly? Well, let’s say you have a drone (or robot). If that drone is MAVLink-enabled (i.e. it “talks MAVLink”), then MAVSDK will allow you to write programs that control it. If you are not sure whether or not your drone talks MAVLink, the simple rule is this: if QGroundControl can connect to it, then it talks MAVLink.

MAVSDK is primarily used by developers as a tool for integrating different components on a vehicle – the flight stack, companion computer, and MAVLink peripherals (e.g. cameras). It can also be used for implementing ground station functionality that is specific to a particular domain (that would not normally be in a generic GCS like QGroundControl).

 This article will focus on a simple setup with a simulator running on your computer (we call that “Software in the Loop”, or “SITL”), to which MAVSDK will connect.

Prerequisites

  • Python 3.6+: run python --version or python3 --version in a terminal to check the installed version.
  • A running SITL instance (jMAVSim, gazebo, …). A quick way to run a headless gazebo SITL instance is documented here.

Quick Start

Enough talking, let’s get some code running!

Installing through pip

First, let’s install MAVSDK-Python:

pip install mavsdk

Make sure that the output of this command confirms that the installation succeeded! Note that on some systems, you may have to run pip3 install --user mavsdk (install in user space), sudo pip3 install mavsdk (install on your system), or you may want to run in a Python venv.

For a quick start in a REPL (interactive shell), we will also install the lightweight package called “aioconsole”, which provides apython (which is a REPL for running asyncio code):

pip3 install aioconsole

Starting SITL

Now let’s run SITL (e.g. make posix jmavsim, or using the headless gazebo docker container that was linked above). I usually like to check that it is working by taking off manually from the SITL interactive console:

pxh> commander takeoff
pxh> commander land

SITL may error with the following message:

ERROR [commander] rejecting takeoff, no position lock yet. Please retry..

Which means that you need to wait for it to get ready. I usually wait for the following messages before I try to take off from commander:

INFO [ecl/EKF] EKF GPS checks passed (WGS-84 origin set)
INFO [ecl/EKF] EKF commencing GPS fusion

Taking off from MAVSDK-Python

When we know that the simulator is ready, we can open an apython REPL:

apython

In which we can import MAVSDK, as follows:

from mavsdk import System

We then create a drone object, which will be the entrypoint to MAVSDK everywhere in the scripts:

drone = System()

Without going into details now, let’s just note that we also need to “connect” the drone object to the actual vehicle, with:

await drone.connect()

And finally, let’s arm and takeoff!

await drone.action.arm()
await drone.action.takeoff()

If everything went well, your drone should takeoff. In the pxh console, you should see a log line like:

INFO [commander] Takeoff detected

If running a graphical interface, you should see the drone taking off. Here is what it looks like in jMAVSim:

Taking off in jMAVSim

jMAVSim after a successful takeoff.

Note: make sure to send the takeoff() not too long after arm(), because the drone will automatically disarm after a few seconds if nothing happens.

It could happen that you get an exception, like:

raise ActionError(result, “arm()”)
mavsdk.generated.action.ActionError: COMMAND_DENIED: ‘Command denied’; origin: arm(); params: ()

This is not a bug! It means that the arm() call was rejected by PX4, with the error code COMMAND_DENIED. It happens for instance when you try to arm before the drone gets a GPS fix. Most functions in MAVSDK-Python can raise exceptions that your code should manage with try... except.

With the drone now flying, feel free to land whenever you want:

await drone.action.land()

And that’s it for our “Hello World”! Note that we have been using the apython REPL to run all that interactively, but the same can be achieved by running the takeoff_and_land.py example (in which case the aioconsole package is not needed at all).

Example scripts

We do provide a number of examples in the MAVSDK-Python repository. Note that the examples may evolve over time. At the time of this writing, the version of MAVSDK available from pip is “0.3.0”, and therefore the corresponding examples can be found in the corresponding tag. So if an example doesn’t work with your installation, make sure to check that.

To build on the take off example above, let’s now have a look at the corresponding script:

#!/usr/bin/env python3

import asyncio
from mavsdk import System


async def run():

    drone = System()
    await drone.connect(system_address="udp://:14540")

    print("Waiting for drone...")
    async for state in drone.core.connection_state():
        if state.is_connected:
            print(f"Drone discovered with UUID: {state.uuid}")
            break

    print("-- Arming")
    await drone.action.arm()

    print("-- Taking off")
    await drone.action.takeoff()

    await asyncio.sleep(5)

    print("-- Landing")
    await drone.action.land()


if __name__ == "__main__":
    loop = asyncio.get_event_loop()
    loop.run_until_complete(run())

Running this script will result in the drone taking off and landing five seconds later. Let’s first have a look at the general syntax. We are using asyncio, which is part of the Python standard library. It may seem a bit intimidating at first, but it is actually pretty easy to get started. Obviously, we first need to import the package: import asyncio. Then, we define our main routine, here called run(). In asyncio, it is called a “coroutine” and its definition starts with the async keyword. You can create other coroutines the same way. For instance, await drone.action.takeoff() is actually calling another coroutine, that is defined with async def takeoff() somewhere in MAVSDK. And that’s the second rule: when calling a coroutine, you need to “await” for it. And it results in a normal, blocking function call, just like we would expect.

One more thing to note with the run() coroutine is that we want it to be the entry point of our script (I compared it before to a “main” function). And that’s precisely what is done at the end of the script:

if __name__ == "__main__":
    loop = asyncio.get_event_loop()
    loop.run_until_complete(run())

Here we just tell asyncio to run our main coroutine until it completes.

Ok, so we have seen how to import asyncio, how to create a main coroutine as the entry point to our script, how to define coroutines (async def my_coroutine()), and how to call a coroutine with await. The next thing we miss in order to understand MAVSDK-Python is the async generators. We use one in the beginning of the script, while we wait for a drone to connect:

print("Waiting for drone...")
async for state in drone.core.connection_state():
    if state.is_connected:
        print(f"Drone discovered with UUID: {state.uuid}")
        break

It is nothing fancy, in the end: it just looks like a for loop. Except that again, we prepend it with the async keyword. In this case, we receive connection_state() events until one tells us that a drone connected (if state.is_connected), and then stop the loop at that point. Another way would be to just run that loop in parallel (similar to running it in a thread). That’s not in the scope of this blog post but if you are interested, have a look at the telemetry_takeoff_and_land.py example, which prints some telemetry data while doing the exact same “take off, wait five seconds and land” routine.

The last thing I would like to note is the following:

await drone.connect(system_address="udp://:14540")

You may have noticed that we call connect() with an argument here (
system_address). In this case, we are explicitly telling MAVSDK to listen for UDP broadcasts on port 14540. That’s the default, so you may as well call await drone.connect(), like we did in the REPL in the beginning of this article. But that’s interesting to know, because you may want to be listening on port 14550 (system_address="udp://:14550")) or on a serial port (system_address="serial:///dev/ttyACM0:115200").

Conclusion

That’s it for today! I hope this quick introduction will help getting started with MAVSDK-Python and asyncio. Because asyncio is part of the Python standard library, it is super well documented, so feel free to read about it! When it comes to MAVSDK, you know the two constructions we have: coroutines (e.g. calling await drone.action.arm()), and async generators (e.g. calling async for position in await drone.telemetry.position()).

Lastly, note that you can benefit from the auto-completion of an IDE like PyCharm to get the available functions and their documentation, as can be seen in the following screenshot:

Auto-completion in PyCharm

Auto-completion in PyCharm

2019-10-30T14:56:51+00:00