dronesim Docs
  • DRONESIM
  • Simulation setup
    • Accessing the simulation dashboard
    • Navigating the User Interface
  • Testing SITL without a transmitter or gamepad
  • Connecting to local apps
    • MAVProxy
    • Mission Planner
    • QGroundControl
  • Development tutorials
    • Forwarding MAVLink packets
    • Getting Started with MAVSDK and PX4
    • Getting Started with Pymavlink – Connecting to a Drone Simulator
  • Setting Up a VPN for UAS Projects Using ZeroTier
Powered by GitBook
On this page
  1. Development tutorials

Getting Started with Pymavlink – Connecting to a Drone Simulator

Blog Post:

PyMAVLink is a Python library that can easily interface with MAVLink-based systems like drones and unmanned vehicles. With PyMAVLink, you can develop scripts to communicate with your drone, retrieve telemetry data, and even control the vehicle. One popular use case is connecting PyMAVLink to a drone simulator to fetch real-time MAVLink data.

This blog post’ll walk you through setting up PyMAVLink, connecting it to a simulated drone in dronesim.xyz over TCP, and fetching some MAVLink data.


What is PyMAVLink?

PyMAVLink is part of the MAVLink ecosystem, and it acts as the Python interface for generating and parsing MAVLink messages. It allows you to:

  • Connect to MAVLink systems over serial, TCP, or UDP.

  • Retrieve telemetry data such as GPS position, attitude, and battery levels.

  • Send commands to the drone, such as arming/disarming or setting waypoints.

  • Create custom applications that work with MAVLink.

Step 1: Installing PyMAVLink

Before we begin, let’s install PyMAVLink. You can install it using pip:

pip install pymavlink

This will install PyMAVLink and its dependencies.


Step 2: Setting Up Drone Simulation

For this tutorial, we’ll use dronesim.xyz, a web-based drone simulator. This platform allows you to simulate a MAVLink-compatible drone and provides a TCP connection to receive MAVLink data.

To start:

  1. Start the simulator and take note of the TCP port it provides (usually 127.0.0.1:5760 for localhost).

The simulator will now simulate a drone, and you can connect to it using PyMAVLink over TCP.


Step 3: Connecting PyMAVLink to the Simulated Drone

Now that the simulator is running, we’ll create a Python script to connect PyMAVLink to the simulator’s TCP port and fetch some primary MAVLink data.

Below is a Python example to connect to dronesim.xyz via TCP and retrieve telemetry data like the drone’s heartbeat and GPS coordinates.

from pymavlink import mavutil

# Step 1: Establish a connection to the drone simulator over TCP
# Replace 127.0.0.1:5760 with the actual TCP address if needed
connection = mavutil.mavlink_connection('tcp:127.0.0.1:5760')

# Step 2: Wait for the heartbeat message to confirm the connection
print("Waiting for heartbeat from the drone...")
connection.wait_heartbeat()
print("Heartbeat received! Drone is connected.")

# Step 3: Retrieve and display MAVLink messages from the drone
while True:
    # Fetch the next message
    msg = connection.recv_match(type=['GLOBAL_POSITION_INT', 'ATTITUDE'], blocking=True)
    
    if msg is None:
        continue

    # Process and display Global Position data
    if msg.get_type() == 'GLOBAL_POSITION_INT':
        print(f"Global Position: Lat={msg.lat / 1e7}, Lon={msg.lon / 1e7}, Alt={msg.alt / 1000.0} meters")

    # Process and display Attitude data
    elif msg.get_type() == 'ATTITUDE':
        print(f"Attitude: Roll={msg.roll}, Pitch={msg.pitch}, Yaw={msg.yaw}")

Explanation of the Code:

  1. Establish a Connection: We use mavutil.mavlink_connection to establish a connection to the drone simulator over TCP. The address tcp:127.0.0.1:5760 refers to the local host (your machine) and the default port used by dronesim.xyz.

  2. Wait for Heartbeat: After connecting, the script waits for a MAVLink heartbeat message. The heartbeat indicates the drone (or simulator) is connected and functioning correctly. Once the heartbeat is received, the connection is confirmed.

  3. Fetch MAVLink Messages: Inside a loop, we use recv_match to receive MAVLink messages of specific types: GLOBAL_POSITION_INT (which provides GPS data) and ATTITUDE (which provides orientation data). The loop will continuously fetch and print the position and attitude of the simulated drone.

    • GLOBAL_POSITION_INT message gives latitude, longitude, and altitude. The values must be converted to standard units (e.g., latitude and longitude are given in degrees * 10^7).

    • ATTITUDE message provides the drone’s roll, pitch, and yaw in radians.

Step 4: Running the Script

To run the script, save it as pymavlink_example.py and execute it using Python:

python pymavlink_example.py

You should see output like this:

Waiting for heartbeat from the drone...
Heartbeat received! Drone is connected.
Global Position: Lat=47.397742, Lon=8.545594, Alt=501.0 meters
Attitude: Roll=0.0023, Pitch=-0.0156, Yaw=1.002
Global Position: Lat=47.397742, Lon=8.545595, Alt=502.5 meters
Attitude: Roll=0.0024, Pitch=-0.0154, Yaw=1.001
...

This indicates that your PyMAVLink script successfully connects to the drone simulator and retrieves MAVLink data such as position and orientation.

Step 5: Modifying the Script to Fetch Other MAVLink Data

PyMAVLink provides access to all MAVLink messages, so you can easily modify the script to retrieve other types of data, such as battery status, system status, and more. Here's how you can extend the script to fetch the drone's battery status:

from pymavlink import mavutil

# Connect to the drone simulator
connection = mavutil.mavlink_connection('tcp:127.0.0.1:5760')

# Wait for heartbeat
print("Waiting for heartbeat from the drone...")
connection.wait_heartbeat()
print("Heartbeat received! Drone is connected.")

while True:
    msg = connection.recv_match(type=['GLOBAL_POSITION_INT', 'ATTITUDE', 'SYS_STATUS'], blocking=True)
    
    if msg is None:
        continue

    if msg.get_type() == 'GLOBAL_POSITION_INT':
        print(f"Global Position: Lat={msg.lat / 1e7}, Lon={msg.lon / 1e7}, Alt={msg.alt / 1000.0} meters")

    elif msg.get_type() == 'ATTITUDE':
        print(f"Attitude: Roll={msg.roll}, Pitch={msg.pitch}, Yaw={msg.yaw}")

    elif msg.get_type() == 'SYS_STATUS':
        print(f"Battery: {msg.battery_remaining}%")

This code now also retrieves the battery status (SYS_STATUS), showing the percentage of battery remaining.


This example is just the beginning. PyMAVLink provides access to a wide range of MAVLink messages and commands, allowing you to create custom solutions for your specific use cases. Happy coding, and enjoy experimenting with drone simulations!


References:

PreviousGetting Started with MAVSDK and PX4NextSetting Up a VPN for UAS Projects Using ZeroTier

Last updated 1 month ago

Visit in your browser.

dronesim.xyz
PyMAVLink Documentation
Dronesim.xyz